From 98e4037868ce17768c45a74b0900cd5afcdfd2b6 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 18 Jan 2025 09:30:16 +1100 Subject: [PATCH] AP_Motors: move to a uint32_t motor mask --- libraries/AP_Motors/AP_MotorsMulticopter.cpp | 2 +- libraries/AP_Motors/AP_MotorsMulticopter.h | 4 ++-- libraries/AP_Motors/AP_MotorsTri.cpp | 2 +- libraries/AP_Motors/AP_MotorsTri.h | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index e8a099998a..7269918b7a 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -740,7 +740,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, uint16_t mask, float rudder_dt) +void AP_MotorsMulticopter::output_motor_mask(float thrust, uint32_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 7e8491c849..7864f9b57a 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.h +++ b/libraries/AP_Motors/AP_MotorsMulticopter.h @@ -60,7 +60,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, uint16_t mask, float rudder_dt); + virtual void output_motor_mask(float thrust, uint32_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 @@ -204,5 +204,5 @@ protected: } // mask of overridden motors (used by quadplane tiltrotors) - uint16_t _motor_mask_override; + uint32_t _motor_mask_override; }; diff --git a/libraries/AP_Motors/AP_MotorsTri.cpp b/libraries/AP_Motors/AP_MotorsTri.cpp index e387694c20..7f50bc61b4 100644 --- a/libraries/AP_Motors/AP_MotorsTri.cpp +++ b/libraries/AP_Motors/AP_MotorsTri.cpp @@ -351,7 +351,7 @@ void AP_MotorsTri::thrust_compensation(void) /* override tricopter tail servo output in output_motor_mask */ -void AP_MotorsTri::output_motor_mask(float thrust, uint16_t mask, float rudder_dt) +void AP_MotorsTri::output_motor_mask(float thrust, uint32_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 3c034ccc1c..0dd84ca9a0 100644 --- a/libraries/AP_Motors/AP_MotorsTri.h +++ b/libraries/AP_Motors/AP_MotorsTri.h @@ -42,7 +42,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, uint16_t mask, float rudder_dt) override; + void output_motor_mask(float thrust, uint32_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