Browse Source

Plane: GCS_MAVLink takes care of mavlink capabilities

master
Peter Barker 7 years ago committed by Peter Barker
parent
commit
33541dcbf6
  1. 15
      ArduPlane/GCS_Mavlink.cpp
  2. 1
      ArduPlane/GCS_Mavlink.h
  3. 1
      ArduPlane/Plane.h
  4. 13
      ArduPlane/capabilities.cpp
  5. 2
      ArduPlane/system.cpp

15
ArduPlane/GCS_Mavlink.cpp

@ -1478,3 +1478,18 @@ bool GCS_MAVLINK_Plane::set_mode(const uint8_t mode) @@ -1478,3 +1478,18 @@ bool GCS_MAVLINK_Plane::set_mode(const uint8_t mode)
}
return false;
}
uint64_t GCS_MAVLINK_Plane::capabilities() const
{
return (MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT |
MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT |
MAV_PROTOCOL_CAPABILITY_COMMAND_INT |
MAV_PROTOCOL_CAPABILITY_MISSION_INT |
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |
MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |
#if AP_TERRAIN_AVAILABLE
(plane.terrain.enabled() ? MAV_PROTOCOL_CAPABILITY_TERRAIN : 0) |
#endif
MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION |
GCS_MAVLINK::capabilities());
}

1
ArduPlane/GCS_Mavlink.h

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

1
ArduPlane/Plane.h

@ -1032,7 +1032,6 @@ private: @@ -1032,7 +1032,6 @@ private:
bool verify_command_callback(const AP_Mission::Mission_Command& cmd);
void notify_flight_mode(enum FlightMode mode);
void log_init();
void init_capabilities(void);
void parachute_check();
#if PARACHUTE == ENABLED
void do_parachute(const AP_Mission::Mission_Command& cmd);

13
ArduPlane/capabilities.cpp

@ -1,13 +0,0 @@ @@ -1,13 +0,0 @@
#include "Plane.h"
void Plane::init_capabilities(void)
{
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT |
MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT |
MAV_PROTOCOL_CAPABILITY_COMMAND_INT |
MAV_PROTOCOL_CAPABILITY_MISSION_INT |
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |
MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |
MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION);
}

2
ArduPlane/system.cpp

@ -27,8 +27,6 @@ void Plane::init_ardupilot() @@ -27,8 +27,6 @@ void Plane::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…
Cancel
Save