mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_Motors: fix mask passed to rc_set_freq
the full motor mask must be supplied to work correctly for oneshot and dshot
This commit is contained in:
parent
610a6a6c88
commit
e55d3a0834
@ -43,9 +43,13 @@ void AP_MotorsMatrix::set_update_rate( uint16_t speed_hz )
|
||||
// record requested speed
|
||||
_speed_hz = speed_hz;
|
||||
|
||||
// we can use a mask of 0xFF here as rc_set_freq masks with actual
|
||||
// motor mask
|
||||
rc_set_freq(0xFF, _speed_hz );
|
||||
uint16_t mask = 0;
|
||||
for (uint8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
||||
if (motor_enabled[i]) {
|
||||
mask |= 1U << i;
|
||||
}
|
||||
}
|
||||
rc_set_freq(mask, _speed_hz );
|
||||
}
|
||||
|
||||
// set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
|
||||
|
Loading…
Reference in New Issue
Block a user