Browse Source

ArduSub: 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
2372a4f3b6
  1. 10
      ArduSub/GCS_Mavlink.cpp
  2. 1
      ArduSub/GCS_Mavlink.h

10
ArduSub/GCS_Mavlink.cpp

@ -407,16 +407,6 @@ bool GCS_MAVLINK_Sub::handle_guided_request(AP_Mission::Mission_Command &cmd) @@ -407,16 +407,6 @@ bool GCS_MAVLINK_Sub::handle_guided_request(AP_Mission::Mission_Command &cmd)
return sub.do_guided(cmd);
}
void GCS_MAVLINK_Sub::handle_change_alt_request(AP_Mission::Mission_Command &cmd)
{
// add home alt if needed
if (cmd.content.location.relative_alt) {
cmd.content.location.alt += sub.ahrs.get_home().alt;
}
// To-Do: update target altitude for loiter or waypoint controller depending upon nav mode
}
MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration_baro()
{
if (sub.motors.armed()) {

1
ArduSub/GCS_Mavlink.h

@ -43,7 +43,6 @@ private: @@ -43,7 +43,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;
bool send_info(void);

Loading…
Cancel
Save