AP_MotorsMatrix: do not set limits in output_min

This commit is contained in:
Leonard Hall 2016-01-18 14:08:50 +09:00 committed by Randy Mackay
parent 3fef60da45
commit d0c6d087a5
1 changed files with 1 additions and 7 deletions

View File

@ -88,13 +88,7 @@ void AP_MotorsMatrix::output_min()
{
int8_t i;
// set limits flags
limit.roll_pitch = true;
limit.yaw = true;
limit.throttle_lower = true;
limit.throttle_upper = false;
// fill the motor_out[] array for HIL use and send minimum value to each motor
// send output to each motor
hal.rcout->cork();
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
if( motor_enabled[i] ) {