Copter: do not spin motors during arming process

This commit is contained in:
Randy Mackay 2013-07-16 12:43:26 +09:00
parent 9f51a4a4f7
commit e6412b6996

View File

@ -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);