From d5b1f1651ea1c845e65be764fa0cec0cae3b0f46 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 3 Jan 2020 01:17:49 +1100 Subject: [PATCH] Copter: remove unneeded set_range calls on RC Aux channels This isn't an exhaustive list of channels used for auxillary input, so that makes this wrong. RC_Channel goes off the raw get_radio_in values, so setting these is a pointless and potentially confusing state change. Also, Plane and Rover don't do this - so things are more consistent after this. --- ArduCopter/radio.cpp | 6 ------ 1 file changed, 6 deletions(-) diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index 5d91d84fcf..1f1a94a16a 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -31,12 +31,6 @@ void Copter::init_rc_in() channel_yaw->set_angle(ROLL_PITCH_YAW_INPUT_MAX); channel_throttle->set_range(1000); - // set auxiliary servo ranges - rc().channel(CH_5)->set_range(1000); - rc().channel(CH_6)->set_range(1000); - rc().channel(CH_7)->set_range(1000); - rc().channel(CH_8)->set_range(1000); - // set default dead zones default_dead_zones();