mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 22:18:28 -04:00
Rover: GCS_MAVLink takes care of mavlink capabilities
This commit is contained in:
parent
f759c7ac7e
commit
7d6140e029
@ -1070,6 +1070,19 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
||||
} // end switch
|
||||
} // end handle mavlink
|
||||
|
||||
uint64_t GCS_MAVLINK_Rover::capabilities() const
|
||||
{
|
||||
return (MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT |
|
||||
MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT |
|
||||
MAV_PROTOCOL_CAPABILITY_MISSION_INT |
|
||||
MAV_PROTOCOL_CAPABILITY_COMMAND_INT |
|
||||
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED |
|
||||
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |
|
||||
MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |
|
||||
MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION |
|
||||
GCS_MAVLINK::capabilities());
|
||||
}
|
||||
|
||||
/*
|
||||
* a delay() callback that processes MAVLink packets. We set this as the
|
||||
* callback in long running library initialisation routines to allow
|
||||
|
@ -34,6 +34,7 @@ protected:
|
||||
|
||||
bool set_home_to_current_location(bool lock) override;
|
||||
bool set_home(const Location& loc, bool lock) override;
|
||||
uint64_t capabilities() const override;
|
||||
|
||||
void send_nav_controller_output() const override;
|
||||
|
||||
|
@ -396,9 +396,6 @@ private:
|
||||
void balancebot_pitch_control(float &throttle);
|
||||
bool is_balancebot() const;
|
||||
|
||||
// capabilities.cpp
|
||||
void init_capabilities(void);
|
||||
|
||||
// commands_logic.cpp
|
||||
void update_mission(void);
|
||||
|
||||
|
@ -1,13 +0,0 @@
|
||||
#include "Rover.h"
|
||||
|
||||
void Rover::init_capabilities(void)
|
||||
{
|
||||
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT |
|
||||
MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT |
|
||||
MAV_PROTOCOL_CAPABILITY_MISSION_INT |
|
||||
MAV_PROTOCOL_CAPABILITY_COMMAND_INT |
|
||||
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED |
|
||||
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |
|
||||
MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |
|
||||
MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION);
|
||||
}
|
@ -27,8 +27,6 @@ void Rover::init_ardupilot()
|
||||
AP::fwversion().fw_string,
|
||||
(unsigned)hal.util->available_memory());
|
||||
|
||||
init_capabilities();
|
||||
|
||||
//
|
||||
// Check the EEPROM format version before loading any parameters from EEPROM.
|
||||
//
|
||||
|
Loading…
Reference in New Issue
Block a user