Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

EKF: use set_and_default when changing IMU mask #26608

Merged
merged 3 commits into from
Mar 26, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions libraries/AP_DAL/examples/AP_DAL_Standalone/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,11 @@

void AP_Param::setup_object_defaults(void const*, AP_Param::GroupInfo const*) {}

template<typename T, ap_var_type PT>
void AP_ParamT<T, PT>::set_and_default(const T &v) {}
template class AP_ParamT<int8_t, AP_PARAM_INT8>;


int AP_HAL::Util::vsnprintf(char*, size_t, char const*, va_list) { return -1; }

void *nologger = nullptr;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_NavEKF2/AP_NavEKF2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -643,7 +643,7 @@ bool NavEKF2::InitialiseFilter(void)

// don't allow more filters than IMUs
uint8_t mask = (1U<<ins.get_accel_count())-1;
_imuMask.set(_imuMask.get() & mask);
_imuMask.set_and_default(_imuMask.get() & mask);

// count IMUs from mask
num_cores = __builtin_popcount(_imuMask);
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_NavEKF3/AP_NavEKF3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -781,7 +781,7 @@ bool NavEKF3::InitialiseFilter(void)

// don't run multiple filters for 1 IMU
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
for (uint8_t i=0; i<MAX_EKF_CORES; i++) {
Expand Down
Loading