Sub: GCS_MAVLink takes care of mavlink capabilities

This commit is contained in:
Peter Barker 2018-03-29 12:04:11 +11:00 committed by Peter Barker
parent 33541dcbf6
commit 7b80f56a80
5 changed files with 16 additions and 18 deletions

View File

@ -972,6 +972,21 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
} // end switch
} // end handle mavlink
uint64_t GCS_MAVLINK_Sub::capabilities() const
{
return (MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT |
MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT |
MAV_PROTOCOL_CAPABILITY_MISSION_INT |
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED |
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |
MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION |
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
(sub.terrain.enabled() ? MAV_PROTOCOL_CAPABILITY_TERRAIN : 0) |
#endif
MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |
GCS_MAVLINK::capabilities()
);
}
// a RC override message is considered to be a 'heartbeat' from the ground station for failsafe purposes
void GCS_MAVLINK_Sub::handle_rc_channels_override(const mavlink_message_t *msg)

View File

@ -36,6 +36,7 @@ protected:
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
void send_nav_controller_output() const override;
uint64_t capabilities() const override;
private:

View File

@ -660,7 +660,6 @@ private:
void auto_spline_start(const Location& destination, bool stopped_at_start, AC_WPNav::spline_segment_end_type seg_end_type, const Location& next_destination);
void log_init(void);
void init_capabilities(void);
void accel_cal_update(void);
void failsafe_leak_check();

View File

@ -1,15 +0,0 @@
#include "Sub.h"
void Sub::init_capabilities()
{
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT);
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT);
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MISSION_INT);
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED);
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT);
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION);
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET);
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_TERRAIN);
#endif
}

View File

@ -27,8 +27,6 @@ void Sub::init_ardupilot()
AP::fwversion().fw_string,
(unsigned)hal.util->available_memory());
init_capabilities();
// load parameters from EEPROM
load_parameters();