mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: add an option_is_enabled method
This commit is contained in:
parent
601d9ef430
commit
1e17278bda
|
@ -453,9 +453,12 @@ private:
|
||||||
AP_Int32 _options; // bit mask of processing options
|
AP_Int32 _options; // bit mask of processing options
|
||||||
|
|
||||||
// enum for processing options
|
// enum for processing options
|
||||||
enum class Options {
|
enum class Option {
|
||||||
JammingExpected = (1<<0),
|
JammingExpected = (1<<0),
|
||||||
};
|
};
|
||||||
|
bool option_is_enabled(Option option) const {
|
||||||
|
return (_options & (uint32_t)option) != 0;
|
||||||
|
}
|
||||||
|
|
||||||
// Possible values for _flowUse
|
// Possible values for _flowUse
|
||||||
#define FLOW_USE_NONE 0
|
#define FLOW_USE_NONE 0
|
||||||
|
|
|
@ -638,7 +638,7 @@ void NavEKF3_core::readGpsData()
|
||||||
useGpsVertVel = false;
|
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) {
|
(lastTimeGpsReceived_ms - secondLastGpsTime_ms) > frontend->gpsNoFixTimeout_ms) {
|
||||||
const bool doingBodyVelNav = (imuSampleTime_ms - prevBodyVelFuseTime_ms < 1000);
|
const bool doingBodyVelNav = (imuSampleTime_ms - prevBodyVelFuseTime_ms < 1000);
|
||||||
const bool doingFlowNav = (imuSampleTime_ms - prevFlowFuseTime_ms < 1000);;
|
const bool doingFlowNav = (imuSampleTime_ms - prevFlowFuseTime_ms < 1000);;
|
||||||
|
|
Loading…
Reference in New Issue