diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index f18b380bf4..a20d3df337 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -53,6 +53,10 @@ void Copter::init_rc_out() motors->init((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_type.get()); #if FRAME_CONFIG != HELI_FRAME motors->set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max()); +#else + // setup correct scaling for ESCs like the UAVCAN PX4ESC which + // take a proportion of speed. + hal.rcout->set_esc_scaling(channel_throttle->get_radio_min(), channel_throttle->get_radio_max()); #endif // delay up to 2 second for first radio input @@ -62,10 +66,6 @@ void Copter::init_rc_out() read_radio(); } - // setup correct scaling for ESCs like the UAVCAN PX4ESC which - // take a proportion of speed. - hal.rcout->set_esc_scaling(channel_throttle->get_radio_min(), channel_throttle->get_radio_max()); - // check if we should enter esc calibration mode esc_calibration_startup_check();