Browse Source

Rover: init vehicle capabilities

master
squilter 10 years ago committed by Randy Mackay
parent
commit
aa4a7a0b28
  1. 1
      APMrover2/Rover.h
  2. 9
      APMrover2/capabilities.cpp
  3. 2
      APMrover2/system.cpp

1
APMrover2/Rover.h

@ -498,6 +498,7 @@ private: @@ -498,6 +498,7 @@ private:
void do_set_home(const AP_Mission::Mission_Command& cmd);
void do_digicam_configure(const AP_Mission::Mission_Command& cmd);
void do_digicam_control(const AP_Mission::Mission_Command& cmd);
void init_capabilities(void);
public:
bool print_log_menu(void);

9
APMrover2/capabilities.cpp

@ -0,0 +1,9 @@ @@ -0,0 +1,9 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Rover.h"
void Rover::init_capabilities(void)
{
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT);
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT);
}

2
APMrover2/system.cpp

@ -210,6 +210,8 @@ void Rover::init_ardupilot() @@ -210,6 +210,8 @@ void Rover::init_ardupilot()
}
#endif
init_capabilities();
startup_ground();
Log_Write_Startup(TYPE_GROUNDSTART_MSG);

Loading…
Cancel
Save