mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
ArduCopter: Call motors_output_enable at correct spot during init
This commit is contained in:
parent
2bd2e9c774
commit
368e736a61
@ -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
|
||||
|
@ -1096,6 +1096,7 @@ static void print_enabled(boolean b)
|
||||
static void
|
||||
init_esc()
|
||||
{
|
||||
motors_output_enable();
|
||||
while(1){
|
||||
read_radio();
|
||||
delay(100);
|
||||
|
Loading…
Reference in New Issue
Block a user