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

AP_NavEKF3: add an option_is_enabled method #28425

Merged
merged 1 commit into from
Nov 12, 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: 4 additions & 1 deletion libraries/AP_NavEKF3/AP_NavEKF3.h
Original file line number Diff line number Diff line change
Expand Up @@ -453,9 +453,12 @@ class NavEKF3 {
AP_Int32 _options; // bit mask of processing options

// enum for processing options
enum class Options {
enum class Option {
JammingExpected = (1<<0),
};
bool option_is_enabled(Option option) const {
return (_options & (uint32_t)option) != 0;
}

// Possible values for _flowUse
#define FLOW_USE_NONE 0
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -638,7 +638,7 @@ void NavEKF3_core::readGpsData()
useGpsVertVel = false;
}

if ((frontend->_options & (int32_t)NavEKF3::Options::JammingExpected) &&
if (frontend->option_is_enabled(NavEKF3::Option::JammingExpected) &&
(lastTimeGpsReceived_ms - secondLastGpsTime_ms) > frontend->gpsNoFixTimeout_ms) {
const bool doingBodyVelNav = (imuSampleTime_ms - prevBodyVelFuseTime_ms < 1000);
const bool doingFlowNav = (imuSampleTime_ms - prevFlowFuseTime_ms < 1000);;
Expand Down
Loading