From 57ddc8f58fce6ac2dd83dffa99755f34474abf34 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 12 Oct 2016 13:05:24 +1100 Subject: [PATCH] Plane: use SRV_Channels set_esc_scaling() this fixes throttle range on Disco with SERVO_RNG_ENABLE=1 --- ArduPlane/radio.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index be67320eff..0d3075ff6e 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -39,7 +39,7 @@ void Plane::set_control_channels(void) // 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()); + g2.servo_channels.set_esc_scaling(channel_throttle->get_ch_out()); } /*