AP_Motors: Heli RSC: remove incorrect set range call

This commit is contained in:
Iampete1 2023-06-18 19:49:26 +01:00 committed by Randy Mackay
parent c3528c5c9e
commit 9c6f57fb05
1 changed files with 0 additions and 3 deletions

View File

@ -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