mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
Plane: allow rudder arming in CRUISE and FBWB modes
This commit is contained in:
parent
b3eecb87ac
commit
2b144d5c3d
@ -119,8 +119,10 @@ void Plane::rudder_arm_disarm_check()
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// if not in a manual throttle mode then disallow rudder arming/disarming
|
// if not in a manual throttle mode and not in CRUISE or FBWB
|
||||||
if (auto_throttle_mode ) {
|
// modes then disallow rudder arming/disarming
|
||||||
|
if (auto_throttle_mode &&
|
||||||
|
(control_mode != CRUISE && control_mode != FLY_BY_WIRE_B)) {
|
||||||
rudder_arm_timer = 0;
|
rudder_arm_timer = 0;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user