diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index 60688c0ece..6f5ea8daeb 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -49,9 +49,16 @@ void Plane::set_control_channels(void) quadplane.rc_fwd_thr_ch = rc().find_channel_for_option(RC_Channel::AUX_FUNC::FWD_THR); #endif - // setup correct scaling for ESCs like the UAVCAN ESCs which - // take a proportion of speed. - g2.servo_channels.set_esc_scaling_for(SRV_Channel::k_throttle); + bool set_throttle_esc_scaling = true; +#if HAL_QUADPLANE_ENABLED + set_throttle_esc_scaling = !quadplane.enable; +#endif + if (set_throttle_esc_scaling) { + // setup correct scaling for ESCs like the UAVCAN ESCs which + // take a proportion of speed. For quadplanes we use AP_Motors + // scaling + g2.servo_channels.set_esc_scaling_for(SRV_Channel::k_throttle); + } } /*