From 80f77bc30bbb1571dceccd15c63cf23a5eb8d2e5 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Wed, 20 Jan 2016 12:13:10 +0900 Subject: [PATCH] AP_MotorsTri: output_min does not set limits --- libraries/AP_Motors/AP_MotorsTri.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsTri.cpp b/libraries/AP_Motors/AP_MotorsTri.cpp index 6054d6a26d..abd9c75bfb 100644 --- a/libraries/AP_Motors/AP_MotorsTri.cpp +++ b/libraries/AP_Motors/AP_MotorsTri.cpp @@ -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);