mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Tracker: GCS_MAVLink takes care of mavlink capabilities
This commit is contained in:
parent
7d6140e029
commit
c46de4a9a0
@ -530,6 +530,13 @@ mission_failed:
|
|||||||
} // end handle mavlink
|
} // 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
|
* a delay() callback that processes MAVLink packets. We set this as the
|
||||||
* callback in long running library initialisation routines to allow
|
* callback in long running library initialisation routines to allow
|
||||||
|
@ -30,6 +30,7 @@ protected:
|
|||||||
|
|
||||||
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED { return false; }
|
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; }
|
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;
|
void send_nav_controller_output() const override;
|
||||||
|
|
||||||
|
@ -202,9 +202,6 @@ private:
|
|||||||
void one_second_loop();
|
void one_second_loop();
|
||||||
void ten_hz_logging_loop();
|
void ten_hz_logging_loop();
|
||||||
|
|
||||||
// capabilities.cpp
|
|
||||||
void init_capabilities(void);
|
|
||||||
|
|
||||||
// control_auto.cpp
|
// control_auto.cpp
|
||||||
void update_auto(void);
|
void update_auto(void);
|
||||||
void calc_angle_error(float pitch, float yaw, bool direction_reversed);
|
void calc_angle_error(float pitch, float yaw, bool direction_reversed);
|
||||||
|
@ -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);
|
|
||||||
}
|
|
@ -17,8 +17,6 @@ void Tracker::init_tracker()
|
|||||||
AP::fwversion().fw_string,
|
AP::fwversion().fw_string,
|
||||||
(unsigned)hal.util->available_memory());
|
(unsigned)hal.util->available_memory());
|
||||||
|
|
||||||
init_capabilities();
|
|
||||||
|
|
||||||
// Check the EEPROM format version before loading any parameters from EEPROM
|
// Check the EEPROM format version before loading any parameters from EEPROM
|
||||||
load_parameters();
|
load_parameters();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user