diff --git a/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp b/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp index 3a3413a4de..70ab8019c9 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp @@ -227,9 +227,6 @@ void AP_MotorsHeli_RSC::init_servo() // setup RSC on specified channel by default SRV_Channels::set_aux_channel_default(_aux_fn, _default_channel); - // set servo range - SRV_Channels::set_range(SRV_Channels::get_motor_function(_aux_fn), 1000); - } // set_power_output_range