GCS_MAVLink: 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 bb42ab3eb3
commit e9358ff491
2 changed files with 1 additions and 2 deletions

View File

@ -863,7 +863,7 @@ private:
void send_distance_sensor(const class AP_RangeFinder_Backend *sensor, const uint8_t instance) const;
virtual bool handle_guided_request(AP_Mission::Mission_Command &cmd) = 0;
virtual void handle_change_alt_request(AP_Mission::Mission_Command &cmd) = 0;
virtual void handle_change_alt_request(AP_Mission::Mission_Command &cmd) {};
void handle_common_mission_message(const mavlink_message_t &msg);
void handle_vicon_position_estimate(const mavlink_message_t &msg);

View File

@ -23,7 +23,6 @@ private:
void handleMessage(const mavlink_message_t &msg) override {}
bool try_send_message(enum ap_message id) override { return true; }
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override { return true; }
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override {}
protected: