Browse Source

ArduCopter: 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.
gps-1.3.1
Peter Barker 3 years ago committed by Andrew Tridgell
parent
commit
4f2cf9ffa2
  1. 10
      ArduCopter/GCS_Mavlink.cpp
  2. 1
      ArduCopter/GCS_Mavlink.h

10
ArduCopter/GCS_Mavlink.cpp

@ -559,16 +559,6 @@ bool GCS_MAVLINK_Copter::handle_guided_request(AP_Mission::Mission_Command &cmd) @@ -559,16 +559,6 @@ bool GCS_MAVLINK_Copter::handle_guided_request(AP_Mission::Mission_Command &cmd)
#endif
}
void GCS_MAVLINK_Copter::handle_change_alt_request(AP_Mission::Mission_Command &cmd)
{
// add home alt if needed
if (cmd.content.location.relative_alt) {
cmd.content.location.alt += copter.ahrs.get_home().alt;
}
// To-Do: update target altitude for loiter or waypoint controller depending upon nav mode
}
void GCS_MAVLINK_Copter::packetReceived(const mavlink_status_t &status,
const mavlink_message_t &msg)
{

1
ArduCopter/GCS_Mavlink.h

@ -52,7 +52,6 @@ private: @@ -52,7 +52,6 @@ private:
void handleMessage(const mavlink_message_t &msg) override;
void handle_command_ack(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 packetReceived(const mavlink_status_t &status,

Loading…
Cancel
Save