Browse Source

Tracker: GCS_MAVLink takes care of mavlink capabilities

master
Peter Barker 7 years ago committed by Peter Barker
parent
commit
c46de4a9a0
  1. 7
      AntennaTracker/GCS_Mavlink.cpp
  2. 1
      AntennaTracker/GCS_Mavlink.h
  3. 3
      AntennaTracker/Tracker.h
  4. 7
      AntennaTracker/capabilities.cpp
  5. 2
      AntennaTracker/system.cpp

7
AntennaTracker/GCS_Mavlink.cpp

@ -530,6 +530,13 @@ mission_failed: @@ -530,6 +530,13 @@ mission_failed:
} // end handle mavlink
uint64_t GCS_MAVLINK_Tracker::capabilities() const
{
return (MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT |
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

1
AntennaTracker/GCS_Mavlink.h

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

3
AntennaTracker/Tracker.h

@ -202,9 +202,6 @@ private: @@ -202,9 +202,6 @@ private:
void one_second_loop();
void ten_hz_logging_loop();
// capabilities.cpp
void init_capabilities(void);
// control_auto.cpp
void update_auto(void);
void calc_angle_error(float pitch, float yaw, bool direction_reversed);

7
AntennaTracker/capabilities.cpp

@ -1,7 +0,0 @@ @@ -1,7 +0,0 @@
#include "Tracker.h"
void Tracker::init_capabilities(void)
{
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT |
MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION);
}

2
AntennaTracker/system.cpp

@ -17,8 +17,6 @@ void Tracker::init_tracker() @@ -17,8 +17,6 @@ void Tracker::init_tracker()
AP::fwversion().fw_string,
(unsigned)hal.util->available_memory());
init_capabilities();
// Check the EEPROM format version before loading any parameters from EEPROM
load_parameters();

Loading…
Cancel
Save