mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Plane: smooth the transition to LAND_FINAL in quadplanes
this makes for a much smoother change to LAND_FINAL, without a jerk as it changes vertical speed
This commit is contained in:
parent
5ab3265ee6
commit
2e5c36361e
@ -920,7 +920,7 @@ float QuadPlane::landing_descent_rate_cms(float height_above_ground)
|
||||
{
|
||||
float ret = linear_interpolate(land_speed_cms, wp_nav->get_speed_down(),
|
||||
height_above_ground,
|
||||
land_final_alt, land_final_alt+3);
|
||||
land_final_alt, land_final_alt+6);
|
||||
return ret;
|
||||
}
|
||||
|
||||
@ -2123,7 +2123,6 @@ bool QuadPlane::verify_vtol_land(void)
|
||||
float height_above_ground = plane.relative_ground_altitude(plane.g.rangefinder_landing);
|
||||
if (poscontrol.state == QPOS_LAND_DESCEND && height_above_ground < land_final_alt) {
|
||||
poscontrol.state = QPOS_LAND_FINAL;
|
||||
set_alt_target_current();
|
||||
|
||||
// cut IC engine if enabled
|
||||
if (land_icengine_cut != 0) {
|
||||
|
Loading…
Reference in New Issue
Block a user