diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.h b/libraries/AP_NavEKF3/AP_NavEKF3.h index 415d7424a4777..6bfba2ee17eb8 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3.h @@ -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 diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp index 9e1eab32eb29d..a7146dd06e71b 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp @@ -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);;