ArduCopter: Call motors_output_enable at correct spot during init

This commit is contained in:
Pat Hickey 2012-01-17 11:47:45 -08:00
parent 2bd2e9c774
commit 368e736a61
2 changed files with 2 additions and 0 deletions

View File

@ -100,6 +100,7 @@ static void init_rc_out()
void output_min()
{
motors_output_enable();
#if FRAME_CONFIG == HELI_FRAME
heli_move_servos_to_mid();
#else

View File

@ -1096,6 +1096,7 @@ static void print_enabled(boolean b)
static void
init_esc()
{
motors_output_enable();
while(1){
read_radio();
delay(100);