mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
Plane: allow rudder at zero throttle
if rudder disarming is disabled
This commit is contained in:
parent
700519d805
commit
28cf9d2f24
@ -1064,7 +1064,8 @@ void QuadPlane::control_loiter()
|
|||||||
*/
|
*/
|
||||||
float QuadPlane::get_pilot_input_yaw_rate_cds(void) const
|
float QuadPlane::get_pilot_input_yaw_rate_cds(void) const
|
||||||
{
|
{
|
||||||
if (plane.get_throttle_input() <= 0 && !plane.auto_throttle_mode) {
|
if (plane.get_throttle_input() <= 0 && !plane.auto_throttle_mode &&
|
||||||
|
plane.arming.get_rudder_arming_type() != AP_Arming::ARMING_RUDDER_DISABLED) {
|
||||||
// the user may be trying to disarm
|
// the user may be trying to disarm
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user