From ef5dbae7071437a059d9638843ec8d99cf4cf6f8 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 8 Feb 2016 20:16:59 +0900 Subject: [PATCH] Copter: remove setting of heli_servo_rsc pwm range This object is not used --- ArduCopter/heli.cpp | 13 ------------- 1 file changed, 13 deletions(-) diff --git a/ArduCopter/heli.cpp b/ArduCopter/heli.cpp index c8eed908c2..cf589e055b 100644 --- a/ArduCopter/heli.cpp +++ b/ArduCopter/heli.cpp @@ -16,19 +16,6 @@ static int8_t heli_dynamic_flight_counter; // heli_init - perform any special initialisation required for the tradheli void Copter::heli_init() { - /* - automatically set H_RSC_MIN and H_RSC_MAX from RC8_MIN and - RC8_MAX so that when users upgrade from tradheli version 3.3 to - 3.4 they get the same throttle range as in previous versions of - the code - */ - if (!g.heli_servo_rsc.radio_min.configured()) { - g.heli_servo_rsc.radio_min.set_and_save(g.rc_8.radio_min.get()); - } - if (!g.heli_servo_rsc.radio_max.configured()) { - g.heli_servo_rsc.radio_max.set_and_save(g.rc_8.radio_max.get()); - } - // pre-load stab col values as mode is initialized as Stabilize, but stabilize_init() function is not run on start-up. input_manager.set_use_stab_col(true); input_manager.set_stab_col_ramp(1.0);