mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
Copter: remove broken support for do-change-alt
This command was not implemented fully removing this code resolves a compiler warning
This commit is contained in:
parent
2bc1b7e4d6
commit
72127cde35
@ -922,8 +922,6 @@ void GCS_MAVLINK::handle_change_alt_request(AP_Mission::Mission_Command &cmd)
|
||||
}
|
||||
|
||||
// To-Do: update target altitude for loiter or waypoint controller depending upon nav mode
|
||||
// similar to how do_change_alt works
|
||||
wp_nav.set_desired_alt(cmd.content.location.alt);
|
||||
}
|
||||
|
||||
void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
|
@ -763,29 +763,6 @@ static void do_wait_delay(const AP_Mission::Mission_Command& cmd)
|
||||
|
||||
static void do_change_alt(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
// adjust target appropriately for each nav mode
|
||||
if (control_mode == AUTO) {
|
||||
switch (auto_mode) {
|
||||
case Auto_TakeOff:
|
||||
// To-Do: adjust waypoint target altitude to new provided altitude
|
||||
break;
|
||||
case Auto_WP:
|
||||
case Auto_Spline:
|
||||
// To-Do; reset origin to current location + stopping distance at new altitude
|
||||
break;
|
||||
case Auto_Land:
|
||||
case Auto_RTL:
|
||||
// ignore altitude
|
||||
break;
|
||||
case Auto_CircleMoveToEdge:
|
||||
case Auto_Circle:
|
||||
// move circle altitude up to target (we will need to store this target in circle class)
|
||||
break;
|
||||
case Auto_NavGuided:
|
||||
// ignore altitude
|
||||
break;
|
||||
}
|
||||
}
|
||||
// To-Do: store desired altitude in a variable so that it can be verified later
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user