AP_MotorsTri: output_min does not set limits

This commit is contained in:
Leonard Hall 2016-01-20 12:13:10 +09:00 committed by Randy Mackay
parent ba659be5cb
commit 80f77bc30b

View File

@ -113,9 +113,6 @@ void AP_MotorsTri::enable()
// output_min - sends minimum values out to the motors
void AP_MotorsTri::output_min()
{
// set lower limit flag
limit.throttle_lower = true;
// send minimum value to each motor
hal.rcout->cork();
rc_write(AP_MOTORS_MOT_1, _throttle_radio_min);