AP_Motors: convert to 32 bit motor mask

This commit is contained in:
Iampete1 2021-12-10 16:45:20 +00:00 committed by Andrew Tridgell
parent 7d3368fa33
commit 43832649ec
20 changed files with 28 additions and 28 deletions

View File

@ -100,12 +100,12 @@ void AP_MotorsCoax::output_to_motors()
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
uint16_t AP_MotorsCoax::get_motor_mask()
uint32_t AP_MotorsCoax::get_motor_mask()
{
uint32_t motor_mask =
1U << AP_MOTORS_MOT_5 |
1U << AP_MOTORS_MOT_6;
uint16_t mask = motor_mask_to_srv_channel_mask(motor_mask);
uint32_t mask = motor_mask_to_srv_channel_mask(motor_mask);
// add parent's mask
mask |= AP_MotorsMulticopter::get_motor_mask();

View File

@ -42,7 +42,7 @@ public:
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
uint16_t get_motor_mask() override;
uint32_t get_motor_mask() override;
protected:
// output - sends commands to the motors

View File

@ -111,7 +111,7 @@ public:
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
virtual uint16_t get_motor_mask() override = 0;
virtual uint32_t get_motor_mask() override = 0;
virtual void set_acro_tail(bool set) {}

View File

@ -473,10 +473,10 @@ float AP_MotorsHeli_Dual::get_swashplate (int8_t swash_num, int8_t swash_axis, f
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
uint16_t AP_MotorsHeli_Dual::get_motor_mask()
uint32_t AP_MotorsHeli_Dual::get_motor_mask()
{
// dual heli uses channels 1,2,3,4,5,6 and 8
uint16_t mask = 0;
uint32_t mask = 0;
for (uint8_t i=0; i<AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS; i++) {
mask |= 1U << (AP_MOTORS_MOT_1+i);
}

View File

@ -78,7 +78,7 @@ public:
void calculate_armed_scalars() override;
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
uint16_t get_motor_mask() override;
uint32_t get_motor_mask() override;
// has_flybar - returns true if we have a mechical flybar
bool has_flybar() const override { return AP_MOTORS_HELI_NOFLYBAR; }

View File

@ -183,9 +183,9 @@ void AP_MotorsHeli_Quad::calculate_roll_pitch_collective_factors()
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
uint16_t AP_MotorsHeli_Quad::get_motor_mask()
uint32_t AP_MotorsHeli_Quad::get_motor_mask()
{
uint16_t mask = 0;
uint32_t mask = 0;
for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
mask |= 1U << (AP_MOTORS_MOT_1+i);
}

View File

@ -57,7 +57,7 @@ public:
void calculate_armed_scalars() override;
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
uint16_t get_motor_mask() override;
uint32_t get_motor_mask() override;
// has_flybar - returns true if we have a mechanical flybar
bool has_flybar() const override { return AP_MOTORS_HELI_NOFLYBAR; }

View File

@ -355,7 +355,7 @@ void AP_MotorsHeli_Single::calculate_scalars()
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
uint16_t AP_MotorsHeli_Single::get_motor_mask()
uint32_t AP_MotorsHeli_Single::get_motor_mask()
{
// heli uses channels 1,2,3,4 and 8
// setup fast channels

View File

@ -79,7 +79,7 @@ public:
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
uint16_t get_motor_mask() override;
uint32_t get_motor_mask() override;
// ext_gyro_gain - set external gyro gain in range 0 ~ 1000
void ext_gyro_gain(float gain) override { if (gain >= 0 && gain <= 1000) { _ext_gyro_gain_std = gain; }}

View File

@ -184,15 +184,15 @@ void AP_MotorsMatrix::output_to_motors()
// 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
uint16_t AP_MotorsMatrix::get_motor_mask()
uint32_t AP_MotorsMatrix::get_motor_mask()
{
uint16_t motor_mask = 0;
uint32_t motor_mask = 0;
for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
if (motor_enabled[i]) {
motor_mask |= 1U << i;
}
}
uint16_t mask = motor_mask_to_srv_channel_mask(motor_mask);
uint32_t mask = motor_mask_to_srv_channel_mask(motor_mask);
// add parent's mask
mask |= AP_MotorsMulticopter::get_motor_mask();

View File

@ -60,7 +60,7 @@ public:
// 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
uint16_t get_motor_mask() override;
uint32_t get_motor_mask() override;
// return number of motor that has failed. Should only be called if get_thrust_boost() returns true
uint8_t get_lost_motor() const override { return _motor_lost_index; }

View File

@ -777,7 +777,7 @@ void AP_MotorsMulticopter::output_motor_mask(float thrust, uint8_t mask, float r
// 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
uint16_t AP_MotorsMulticopter::get_motor_mask()
uint32_t AP_MotorsMulticopter::get_motor_mask()
{
return SRV_Channels::get_output_channel_mask(SRV_Channel::k_boost_throttle);
}

View File

@ -68,7 +68,7 @@ public:
// 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
virtual uint16_t get_motor_mask() override;
virtual uint32_t get_motor_mask() override;
// get minimum or maximum pwm value that can be output to motors
int16_t get_pwm_output_min() const { return _pwm_min; }

View File

@ -103,7 +103,7 @@ void AP_MotorsSingle::output_to_motors()
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
uint16_t AP_MotorsSingle::get_motor_mask()
uint32_t AP_MotorsSingle::get_motor_mask()
{
uint32_t motor_mask =
1U << AP_MOTORS_MOT_1 |
@ -113,7 +113,7 @@ uint16_t AP_MotorsSingle::get_motor_mask()
1U << AP_MOTORS_MOT_5 |
1U << AP_MOTORS_MOT_6;
uint16_t mask = motor_mask_to_srv_channel_mask(motor_mask);
uint32_t mask = motor_mask_to_srv_channel_mask(motor_mask);
// add parent's mask
mask |= AP_MotorsMulticopter::get_motor_mask();

View File

@ -42,7 +42,7 @@ public:
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
uint16_t get_motor_mask() override;
uint32_t get_motor_mask() override;
protected:
// output - sends commands to the motors

View File

@ -113,7 +113,7 @@ void AP_MotorsTailsitter::output_to_motors()
// 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
uint16_t AP_MotorsTailsitter::get_motor_mask()
uint32_t AP_MotorsTailsitter::get_motor_mask()
{
uint32_t motor_mask = 0;
uint8_t chan;

View File

@ -28,7 +28,7 @@ public:
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
uint16_t get_motor_mask() override;
uint32_t get_motor_mask() override;
// Set by tailsitters using diskloading minumum outflow velocity limit
void set_min_throttle(float val) {_external_min_throttle = val;}

View File

@ -127,13 +127,13 @@ void AP_MotorsTri::output_to_motors()
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
uint16_t AP_MotorsTri::get_motor_mask()
uint32_t AP_MotorsTri::get_motor_mask()
{
// tri copter uses channels 1,2,4 and 7
uint16_t motor_mask = (1U << AP_MOTORS_MOT_1) |
uint32_t motor_mask = (1U << AP_MOTORS_MOT_1) |
(1U << AP_MOTORS_MOT_2) |
(1U << AP_MOTORS_MOT_4);
uint16_t mask = motor_mask_to_srv_channel_mask(motor_mask);
uint32_t mask = motor_mask_to_srv_channel_mask(motor_mask);
// add parent's mask
mask |= AP_MotorsMulticopter::get_motor_mask();

View File

@ -37,7 +37,7 @@ public:
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
uint16_t get_motor_mask() override;
uint32_t get_motor_mask() override;
// output a thrust to all motors that match a given motor
// mask. This is used to control tiltrotor motors in forward

View File

@ -221,7 +221,7 @@ public:
// 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
virtual uint16_t get_motor_mask() = 0;
virtual uint32_t get_motor_mask() = 0;
// pilot input in the -1 ~ +1 range for roll, pitch and yaw. 0~1 range for throttle
void set_radio_passthrough(float roll_input, float pitch_input, float throttle_input, float yaw_input);