when on landing approach we estimate time to flare based on two noisy
numbers, the vertical speed and height above ground. With noisy
rangefinders this can change rapidly, which resulted in the pitch
limit changing rapidly, leading to a porpoising movement
this limits the rate of change, and also prevents it coming down once
it has nosed up due to pending flare on approach
The calculation of the non-limited airspeed rate demand used the last
non-limited airspeed, whereas it should have used the last adjusted
value. This led to a single frame spike in airspeed demand, which fed
through to a sudden change in pitch integrator.
See discussion here:
https://github.com/ArduPilot/ardupilot/issues/7331
we were getting some uninitialised variables. While it only showed up in
AP_SbusOut, it means we can't be sure it won't happen on other objects,
so safest to remove the approach
Thanks to assistance from Lucas, Peter and Francisco
during the first part of a takeoff when we have not yet reached the
target airspeed this forces the throttle to maximum. This fixes a case
where the throttle may drop too low during the first part of takeoff
and lead to a stall.
recent fixes in Plane have made the stage more accurate so exceptions/hacks are no longer needed to differentiate between knowing if executing NAV_LAND vs being in stage_approach.
we now can exit an underspeed condition if we stay above min speed for
3 seconds and also reach 15% above min speed. This prevents a problem
with the thrust line causing downpitch leading to a crash due to too
much throttle
// @Description: This is the damping gain for the pitch demand loop. Increase to add damping to correct for oscillations in speed and height. If set to 0 then TECS_PTCH_DAMP will be used instead.
+ // @Description: This is the damping gain for the throttle demand loop during and auto-landing. Same as TECS_THR_DAMP but only in effect during an auto-land. Increase to add damping to correct for oscillations in speed and height. When set to 0 landing throttle damp is controlled by TECS_THR_DAMP.