From 30243ed5fcbe1214c47239a2237e6d39496970fe Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Fri, 12 May 2017 17:02:41 +0200 Subject: [PATCH] ArduCopter: radio fix passthrough range on heli/coax/single --- ArduCopter/radio.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index 9bd168d660..1d7fba2320 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -182,5 +182,5 @@ void Copter::set_throttle_zero_flag(int16_t throttle_control) // pass pilot's inputs to motors library (used to allow wiggling servos while disarmed on heli, single, coax copters) void Copter::radio_passthrough_to_motors() { - motors->set_radio_passthrough(channel_roll->get_control_in()/1000.0f, channel_pitch->get_control_in()/1000.0f, channel_throttle->get_control_in()/1000.0f, channel_yaw->get_control_in()/1000.0f); + motors->set_radio_passthrough(channel_roll->norm_input(), channel_pitch->norm_input(), channel_throttle->norm_input(), channel_yaw->norm_input()); }