Rover: 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:14 +11:00 committed by Andrew Tridgell
parent 24a5f57b45
commit fba1710fbf
2 changed files with 0 additions and 6 deletions

View File

@ -565,11 +565,6 @@ bool GCS_MAVLINK_Rover::handle_guided_request(AP_Mission::Mission_Command &cmd)
return rover.mode_guided.set_desired_location(cmd.content.location);
}
void GCS_MAVLINK_Rover::handle_change_alt_request(AP_Mission::Mission_Command &cmd)
{
// nothing to do
}
MAV_RESULT GCS_MAVLINK_Rover::_handle_command_preflight_calibration(const mavlink_command_long_t &packet)
{
if (is_equal(packet.param6, 1.0f)) {

View File

@ -35,7 +35,6 @@ private:
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;
bool try_send_message(enum ap_message id) override;
void handle_manual_control(const mavlink_message_t &msg);