diff --git a/libraries/AP_Motors/AP_MotorsCoax.cpp b/libraries/AP_Motors/AP_MotorsCoax.cpp index f79b4f4c9a..82cc47511d 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.cpp +++ b/libraries/AP_Motors/AP_MotorsCoax.cpp @@ -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(); diff --git a/libraries/AP_Motors/AP_MotorsCoax.h b/libraries/AP_Motors/AP_MotorsCoax.h index cd6ab2944f..81ca9551f7 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.h +++ b/libraries/AP_Motors/AP_MotorsCoax.h @@ -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 diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index 8b83ff7e2b..2a8f1808bb 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -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) {} diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp index fd66aed249..5310e528e2 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp @@ -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= 0 && gain <= 1000) { _ext_gyro_gain_std = gain; }} diff --git a/libraries/AP_Motors/AP_MotorsMatrix.cpp b/libraries/AP_Motors/AP_MotorsMatrix.cpp index 3b647570ae..8de27cd3a7 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrix.cpp @@ -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(); diff --git a/libraries/AP_Motors/AP_MotorsMatrix.h b/libraries/AP_Motors/AP_MotorsMatrix.h index e21311ff8b..352b169dd7 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.h +++ b/libraries/AP_Motors/AP_MotorsMatrix.h @@ -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; } diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 2b6aebef15..e2ac056fdd 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -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); } diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.h b/libraries/AP_Motors/AP_MotorsMulticopter.h index 7cbc53dcd9..5c3e583fce 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.h +++ b/libraries/AP_Motors/AP_MotorsMulticopter.h @@ -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; } diff --git a/libraries/AP_Motors/AP_MotorsSingle.cpp b/libraries/AP_Motors/AP_MotorsSingle.cpp index 30801e54d5..c693e53b05 100644 --- a/libraries/AP_Motors/AP_MotorsSingle.cpp +++ b/libraries/AP_Motors/AP_MotorsSingle.cpp @@ -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(); diff --git a/libraries/AP_Motors/AP_MotorsSingle.h b/libraries/AP_Motors/AP_MotorsSingle.h index 2de4866011..bb8f39b2e9 100644 --- a/libraries/AP_Motors/AP_MotorsSingle.h +++ b/libraries/AP_Motors/AP_MotorsSingle.h @@ -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 diff --git a/libraries/AP_Motors/AP_MotorsTailsitter.cpp b/libraries/AP_Motors/AP_MotorsTailsitter.cpp index 7fca4cab2b..c19092d957 100644 --- a/libraries/AP_Motors/AP_MotorsTailsitter.cpp +++ b/libraries/AP_Motors/AP_MotorsTailsitter.cpp @@ -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; diff --git a/libraries/AP_Motors/AP_MotorsTailsitter.h b/libraries/AP_Motors/AP_MotorsTailsitter.h index 53f1d7a2a2..a456be765b 100644 --- a/libraries/AP_Motors/AP_MotorsTailsitter.h +++ b/libraries/AP_Motors/AP_MotorsTailsitter.h @@ -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;} diff --git a/libraries/AP_Motors/AP_MotorsTri.cpp b/libraries/AP_Motors/AP_MotorsTri.cpp index 1fffd7bec4..bc94fb0f70 100644 --- a/libraries/AP_Motors/AP_MotorsTri.cpp +++ b/libraries/AP_Motors/AP_MotorsTri.cpp @@ -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(); diff --git a/libraries/AP_Motors/AP_MotorsTri.h b/libraries/AP_Motors/AP_MotorsTri.h index 893fb174b8..90b5f25b6c 100644 --- a/libraries/AP_Motors/AP_MotorsTri.h +++ b/libraries/AP_Motors/AP_MotorsTri.h @@ -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 diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index 3b337f86ce..0f0cca18c5 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -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);