From 8d996112ec81bbd9a43e4da064683afc3888084e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 5 May 2018 17:54:57 +1000 Subject: [PATCH] Plane: don't do throttle ESC scaling for quadplanes --- ArduPlane/radio.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index 5fdb0cbae8..b67be48d5a 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -38,9 +38,12 @@ void Plane::set_control_channels(void) SRV_Channels::set_safety_limit(SRV_Channel::k_throttle, aparm.throttle_min<0?SRV_Channel::SRV_CHANNEL_LIMIT_TRIM:SRV_Channel::SRV_CHANNEL_LIMIT_MIN); } - // setup correct scaling for ESCs like the UAVCAN PX4ESC which - // take a proportion of speed - g2.servo_channels.set_esc_scaling_for(SRV_Channel::k_throttle); + if (!quadplane.enable) { + // setup correct scaling for ESCs like the UAVCAN PX4ESC which + // take a proportion of speed. For quadplanes we use AP_Motors + // scaling + g2.servo_channels.set_esc_scaling_for(SRV_Channel::k_throttle); + } } /*