AP_Motors: only set output side of range for RSC

This commit is contained in:
Andrew Tridgell 2015-12-07 09:19:49 +11:00 committed by Randy Mackay
parent 7cc53b6449
commit e1f4814068

View File

@ -25,7 +25,7 @@ extern const AP_HAL::HAL& hal;
void AP_MotorsHeli_RSC::init_servo()
{
// set servo range
_servo_output.set_range(0,1000);
_servo_output.set_range_out(0,1000);
}
// recalc_scalers - recalculates various scalers used. Should be called at about 1hz to allow users to see effect of changing parameters