mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Rover: init vehicle capabilities
This commit is contained in:
parent
5f706252fe
commit
c77182b748
@ -498,6 +498,7 @@ private:
|
|||||||
void do_set_home(const AP_Mission::Mission_Command& cmd);
|
void do_set_home(const AP_Mission::Mission_Command& cmd);
|
||||||
void do_digicam_configure(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 do_digicam_control(const AP_Mission::Mission_Command& cmd);
|
||||||
|
void init_capabilities(void);
|
||||||
|
|
||||||
public:
|
public:
|
||||||
bool print_log_menu(void);
|
bool print_log_menu(void);
|
||||||
|
9
APMrover2/capabilities.cpp
Normal file
9
APMrover2/capabilities.cpp
Normal file
@ -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);
|
||||||
|
}
|
@ -210,6 +210,8 @@ void Rover::init_ardupilot()
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
init_capabilities();
|
||||||
|
|
||||||
startup_ground();
|
startup_ground();
|
||||||
Log_Write_Startup(TYPE_GROUNDSTART_MSG);
|
Log_Write_Startup(TYPE_GROUNDSTART_MSG);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user