AntennaTracker: provide default implemenation of handle_change_alt_request

The TODO items to actually implement these are almost 6 years old.
Since then these methods have been burning space.

This doesn't even make sense for several vehicles, so a default
implementation which does nothing seems OK.
This commit is contained in:
Peter Barker 2022-01-29 22:19:13 +11:00 committed by Andrew Tridgell
parent e9358ff491
commit 65ed077a4e
2 changed files with 0 additions and 6 deletions

View File

@ -169,11 +169,6 @@ bool GCS_MAVLINK_Tracker::handle_guided_request(AP_Mission::Mission_Command&)
return false;
}
void GCS_MAVLINK_Tracker::handle_change_alt_request(AP_Mission::Mission_Command&)
{
// do nothing
}
/*
default stream rates to 1Hz
*/

View File

@ -38,7 +38,6 @@ private:
void mavlink_check_target(const mavlink_message_t &msg);
void handleMessage(const mavlink_message_t &msg) override;
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
void handle_set_attitude_target(const mavlink_message_t &msg);
void send_global_position_int() override;