Skip to content

Commit

Permalink
AP_NavEKF3: add an option_is_enabled method
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Oct 17, 2024
1 parent 145cc4b commit a8c69ee
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 2 deletions.
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

0 comments on commit a8c69ee

Please sign in to comment.