mirror of https://github.com/ArduPilot/ardupilot
Plane: prevent controller windup on ground
when on the ground in an auto-throttle mode lik FBWB or CRUISE, we may have the throttle suppressed. In that case we should not run the multicopter controller on quadplanes, or it may build up control which will then apply on takeoff. This is particularly severe for aircraft that are not level on the ground, such as taildragger quadplanes Fixes https://discuss.ardupilot.org/t/quadplane-flips-on-takeoff/22095 many thanks to Sriram for reporting
This commit is contained in:
parent
1a95dcbdd7
commit
0aed5a9a57
|
@ -1216,7 +1216,7 @@ void QuadPlane::update_transition(void)
|
|||
assistance_needed(aspeed) &&
|
||||
!is_tailsitter() &&
|
||||
hal.util->get_soft_armed() &&
|
||||
(plane.auto_throttle_mode ||
|
||||
((plane.auto_throttle_mode && !plane.throttle_suppressed) ||
|
||||
plane.channel_throttle->get_control_in()>0 ||
|
||||
plane.is_flying())) {
|
||||
// the quad should provide some assistance to the plane
|
||||
|
|
Loading…
Reference in New Issue