From d0c6d087a5245ae6382be26afb11d930bc49a927 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Mon, 18 Jan 2016 14:08:50 +0900 Subject: [PATCH] AP_MotorsMatrix: do not set limits in output_min --- libraries/AP_Motors/AP_MotorsMatrix.cpp | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsMatrix.cpp b/libraries/AP_Motors/AP_MotorsMatrix.cpp index aa1b637b43..a9cd071dbb 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrix.cpp @@ -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