diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index d72966bfa0..2f039a83b0 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -760,7 +760,7 @@ 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, float rudder_dt) +void AP_MotorsMulticopter::output_motor_mask(float thrust, uint16_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; diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.h b/libraries/AP_Motors/AP_MotorsMulticopter.h index 3246d9586b..aa462db447 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.h +++ b/libraries/AP_Motors/AP_MotorsMulticopter.h @@ -64,7 +64,7 @@ public: // 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 - virtual void output_motor_mask(float thrust, uint8_t mask, float rudder_dt); + virtual void output_motor_mask(float thrust, uint16_t mask, float rudder_dt); // get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict diff --git a/libraries/AP_Motors/AP_MotorsTri.cpp b/libraries/AP_Motors/AP_MotorsTri.cpp index ab734a8b15..6486ad8399 100644 --- a/libraries/AP_Motors/AP_MotorsTri.cpp +++ b/libraries/AP_Motors/AP_MotorsTri.cpp @@ -333,7 +333,7 @@ void AP_MotorsTri::thrust_compensation(void) /* override tricopter tail servo output in output_motor_mask */ -void AP_MotorsTri::output_motor_mask(float thrust, uint8_t mask, float rudder_dt) +void AP_MotorsTri::output_motor_mask(float thrust, uint16_t mask, float rudder_dt) { // normal multicopter output AP_MotorsMulticopter::output_motor_mask(thrust, mask, rudder_dt); diff --git a/libraries/AP_Motors/AP_MotorsTri.h b/libraries/AP_Motors/AP_MotorsTri.h index 90b5f25b6c..1f6317ac6e 100644 --- a/libraries/AP_Motors/AP_MotorsTri.h +++ b/libraries/AP_Motors/AP_MotorsTri.h @@ -43,7 +43,7 @@ public: // mask. This is used to control tiltrotor motors in forward // flight. Thrust is in the range 0 to 1 // rudder_dt applys diffential thrust for yaw in the range 0 to 1 - void output_motor_mask(float thrust, uint8_t mask, float rudder_dt) override; + void output_motor_mask(float thrust, uint16_t mask, float rudder_dt) override; // return the roll factor of any motor, this is used for tilt rotors and tail sitters // using copter motors for forward flight