mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
Plane: only allow right rudder for arming
copter users may try to use left rudder to ensure aircraft is disarmed. Making left rudder arm could be dangerous
This commit is contained in:
parent
77c6e51887
commit
a4af83d454
@ -94,10 +94,8 @@ static void rudder_arm_check()
|
||||
return;
|
||||
}
|
||||
|
||||
// full left or right rudder starts arming counter
|
||||
if (g.rc_4.control_in > 4000
|
||||
|| g.rc_4.control_in < -4000) {
|
||||
|
||||
// full right rudder starts arming counter
|
||||
if (g.rc_4.control_in > 4000) {
|
||||
uint32_t now = millis();
|
||||
|
||||
if (rudder_arm_timer == 0 ||
|
||||
|
Loading…
Reference in New Issue
Block a user