mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
Copter: add short delay to arming to allow RC input
The short delay gives time for the RC inputs to be processed which removes the chance of a false-positive on the "late frame" radio check. A false positive could lead to an immediate disarm right after arming.
This commit is contained in:
parent
8e7b93d1b7
commit
b214b8ba15
@ -197,6 +197,9 @@ static void init_arm_motors()
|
||||
sprayer.test_pump(false);
|
||||
#endif
|
||||
|
||||
// short delay to allow reading of rc inputs
|
||||
delay(30);
|
||||
|
||||
// enable output to motors
|
||||
output_min();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user