diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index cea0c7a6ec..9b3a93b0aa 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -161,9 +161,6 @@ void AP_MotorsMulticopter::update_throttle_filter() } else { _throttle_filter.reset(0.0f); } - - // constrain throttle signal to 0-1000 - _throttle_control_input = constrain_float(_throttle_filter.get(),0.0f,1000.0f); } // current_limit_max_throttle - limits maximum throttle based on current