Tracker: let GCS superclass specify compass and param float capabilitiy

This commit is contained in:
Peter Barker 2019-10-29 11:47:04 +11:00 committed by Andrew Tridgell
parent d664f18ce4
commit 88ba3e051c
2 changed files with 0 additions and 8 deletions

View File

@ -569,13 +569,6 @@ 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

View File

@ -27,7 +27,6 @@ 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;
void send_pid_tuning() override;