diff --git a/libraries/AP_Motors/AP_MotorsMatrixTS.cpp b/libraries/AP_Motors/AP_MotorsMatrixTS.cpp index d7e0da6143..2154340f29 100644 --- a/libraries/AP_Motors/AP_MotorsMatrixTS.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrixTS.cpp @@ -25,33 +25,6 @@ extern const AP_HAL::HAL& hal; #define SERVO_OUTPUT_RANGE 4500 -// output a thrust to all motors that match a given motor mask. This -// is used to control motors enabled for forward flight. Thrust is in -// the range 0 to 1 -void AP_MotorsMatrixTS::output_motor_mask(float thrust, uint8_t mask, float rudder_dt) -{ - const int16_t pwm_min = get_pwm_output_min(); - const int16_t pwm_range = get_pwm_output_max() - pwm_min; - - for (uint8_t i=0; i