mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: more changes for 32 bit servo mask
This commit is contained in:
parent
bb8ebeebe2
commit
f00a227b33
|
@ -215,7 +215,7 @@ void AP_MotorsHeli_Dual::set_update_rate( uint16_t speed_hz )
|
|||
_speed_hz = speed_hz;
|
||||
|
||||
// setup fast channels
|
||||
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);
|
||||
}
|
||||
|
|
|
@ -117,7 +117,7 @@ void AP_MotorsMatrix::set_update_rate(uint16_t speed_hz)
|
|||
// record requested speed
|
||||
_speed_hz = speed_hz;
|
||||
|
||||
uint16_t mask = 0;
|
||||
uint32_t mask = 0;
|
||||
for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
||||
if (motor_enabled[i]) {
|
||||
mask |= 1U << i;
|
||||
|
|
|
@ -309,10 +309,10 @@ protected:
|
|||
float _air_density_ratio; // air density / sea level density - decreases in altitude
|
||||
|
||||
// mask of what channels need fast output
|
||||
uint16_t _motor_fast_mask;
|
||||
uint32_t _motor_fast_mask;
|
||||
|
||||
// mask of what channels need to use SERVOn_MIN/MAX for output mapping
|
||||
uint16_t _motor_pwm_range_mask;
|
||||
uint32_t _motor_pwm_range_mask;
|
||||
|
||||
// pass through variables
|
||||
float _roll_radio_passthrough; // roll input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed
|
||||
|
|
Loading…
Reference in New Issue