mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Copter: do not spin motors during arming process
This commit is contained in:
parent
9f51a4a4f7
commit
e6412b6996
@ -110,9 +110,6 @@ static void init_arm_motors()
|
||||
|
||||
// disable cpu failsafe because initialising everything takes a while
|
||||
failsafe_disable();
|
||||
|
||||
motors.enable();
|
||||
motors.output_unsafe();
|
||||
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
// start dataflash
|
||||
@ -189,6 +186,9 @@ static void init_arm_motors()
|
||||
return;
|
||||
}
|
||||
|
||||
// enable output to motors
|
||||
output_min();
|
||||
|
||||
// finally actually arm the motors
|
||||
motors.armed(true);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user