mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_NavEKF3: use set_and_defualt when changing imu mask
This commit is contained in:
parent
b95b51f1a1
commit
21df26de75
@ -781,7 +781,7 @@ bool NavEKF3::InitialiseFilter(void)
|
|||||||
|
|
||||||
// don't run multiple filters for 1 IMU
|
// don't run multiple filters for 1 IMU
|
||||||
uint8_t mask = (1U<<ins.get_accel_count())-1;
|
uint8_t mask = (1U<<ins.get_accel_count())-1;
|
||||||
_imuMask.set(_imuMask.get() & mask);
|
_imuMask.set_and_default(_imuMask.get() & mask);
|
||||||
|
|
||||||
// initialise the setup variables
|
// initialise the setup variables
|
||||||
for (uint8_t i=0; i<MAX_EKF_CORES; i++) {
|
for (uint8_t i=0; i<MAX_EKF_CORES; i++) {
|
||||||
|
Loading…
Reference in New Issue
Block a user