mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: Heli RSC: remove incorrect set range call
This commit is contained in:
parent
697efb40de
commit
ea9e051220
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue