mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Copter: Set Force Descend to true only when in the last phase of landing
This commit is contained in:
parent
7c939c5c00
commit
220662a905
@ -497,7 +497,12 @@ int32_t Mode::get_alt_above_ground_cm(void)
|
|||||||
void Mode::land_run_vertical_control(bool pause_descent)
|
void Mode::land_run_vertical_control(bool pause_descent)
|
||||||
{
|
{
|
||||||
float cmb_rate = 0;
|
float cmb_rate = 0;
|
||||||
|
bool ignore_descent_limit = false;
|
||||||
if (!pause_descent) {
|
if (!pause_descent) {
|
||||||
|
|
||||||
|
// do not ignore limits until we have slowed down for landing
|
||||||
|
ignore_descent_limit = (MAX(g2.land_alt_low,100) > get_alt_above_ground_cm()) || copter.ap.land_complete_maybe;
|
||||||
|
|
||||||
float max_land_descent_velocity;
|
float max_land_descent_velocity;
|
||||||
if (g.land_speed_high > 0) {
|
if (g.land_speed_high > 0) {
|
||||||
max_land_descent_velocity = -g.land_speed_high;
|
max_land_descent_velocity = -g.land_speed_high;
|
||||||
@ -531,7 +536,7 @@ void Mode::land_run_vertical_control(bool pause_descent)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// update altitude target and call position controller
|
// update altitude target and call position controller
|
||||||
pos_control->set_pos_target_z_from_climb_rate_cm(cmb_rate, true);
|
pos_control->set_pos_target_z_from_climb_rate_cm(cmb_rate, ignore_descent_limit);
|
||||||
pos_control->update_z_controller();
|
pos_control->update_z_controller();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user