mirror of https://github.com/ArduPilot/ardupilot
Plane: Fix VTOL yaw for STICK_MIXING 0
This commit is contained in:
parent
9d6a138680
commit
9eaf7f5528
|
@ -1314,7 +1314,11 @@ float QuadPlane::get_pilot_input_yaw_rate_cds(void) const
|
|||
return 0;
|
||||
}
|
||||
|
||||
if (plane.g.stick_mixing == STICK_MIXING_DISABLED) {
|
||||
if ((plane.g.stick_mixing == STICK_MIXING_DISABLED) &&
|
||||
(plane.control_mode == &plane.mode_qrtl ||
|
||||
plane.control_mode == &plane.mode_guided ||
|
||||
plane.control_mode == &plane.mode_avoidADSB ||
|
||||
in_vtol_auto())) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue