diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 713b8dccf7..3c3033d8e9 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -626,13 +626,20 @@ void AP_MotorsMulticopter::set_throttle_passthrough_for_esc_calibration(float th // output a thrust to all motors that match a given motor mask. This // is used to control tiltrotor motors in forward flight. Thrust is in // the range 0 to 1 -void AP_MotorsMulticopter::output_motor_mask(float thrust, uint8_t mask) +void AP_MotorsMulticopter::output_motor_mask(float thrust, uint8_t mask, float rudder_dt) { for (uint8_t i=0; i