mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: prevent a change altitude command from causing a sudden descent
when a change altitude command comes in while a large glide slope altitude change is present we could end up using the old glide slope with the new altitude. This resets the altitude offset, causing a direct altitude change
This commit is contained in:
parent
ede920f293
commit
c05a0bc67f
@ -945,6 +945,8 @@ void GCS_MAVLINK::handle_change_alt_request(AP_Mission::Mission_Command &cmd)
|
||||
next_WP_loc.alt += home.alt;
|
||||
}
|
||||
next_WP_loc.flags.relative_alt = false;
|
||||
next_WP_loc.flags.terrain_alt = cmd.content.location.flags.terrain_alt;
|
||||
reset_offset_altitude();
|
||||
}
|
||||
|
||||
|
||||
|
@ -364,6 +364,7 @@ static void do_loiter_time(const AP_Mission::Mission_Command& cmd)
|
||||
static void do_continue_and_change_alt(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
next_WP_loc.alt = cmd.content.location.alt + home.alt;
|
||||
reset_offset_altitude();
|
||||
}
|
||||
|
||||
/********************************************************************************/
|
||||
@ -563,6 +564,7 @@ static void do_change_alt(const AP_Mission::Mission_Command& cmd)
|
||||
change_target_altitude(condition_rate/10);
|
||||
next_WP_loc.alt = condition_value; // For future nav calculations
|
||||
reset_offset_altitude();
|
||||
setup_glide_slope();
|
||||
}
|
||||
|
||||
static void do_within_distance(const AP_Mission::Mission_Command& cmd)
|
||||
|
Loading…
Reference in New Issue
Block a user