AP_NavEKF3: added two more EK3_OPTION bits

these allow for easier GPS-denied testing of EKF3, and allows for
replay testing without the SetLatLng code being active.

Note that the gaps in the bitmask are for pending range beacon
features, we don't want to fill in the gaps so that existing replay
logs for that feature remain valid
This commit is contained in:
Andrew Tridgell 2024-11-27 11:01:34 +11:00
parent 5ca1e48040
commit 4296bdb416
2 changed files with 19 additions and 2 deletions

View File

@ -738,8 +738,8 @@ const AP_Param::GroupInfo NavEKF3::var_info2[] = {
// @Param: OPTIONS
// @DisplayName: Optional EKF behaviour
// @Description: This controls optional EKF behaviour. Setting JammingExpected will change the EKF nehaviour such that if dead reckoning navigation is possible it will require the preflight alignment GPS quality checks controlled by EK3_GPS_CHECK and EK3_CHECK_SCALE to pass before resuming GPS use if GPS lock is lost for more than 2 seconds to prevent bad
// @Bitmask: 0:JammingExpected
// @Description: This controls optional EKF behaviour. Setting JammingExpected will change the EKF nehaviour such that if dead reckoning navigation is possible it will require the preflight alignment GPS quality checks controlled by EK3_GPS_CHECK and EK3_CHECK_SCALE to pass before resuming GPS use if GPS lock is lost for more than 2 seconds to prevent likely bad GPS data from being fused. The DisableSetLatLng option disables processing of SetLatLng commands provided by an external estimator. The DisableGPSAtStartup option allows for easier GPS denied testing to ensure that no GPS data is processed before an AUX function to disable GPS can be processed.
// @Bitmask: 0:JammingExpected,2:DisableSetLatLng,5:DisableGPSAtStartup
// @User: Advanced
AP_GROUPINFO("OPTIONS", 11, NavEKF3, _options, 0),
@ -787,6 +787,14 @@ bool NavEKF3::InitialiseFilter(void)
}
#endif
if (option_is_enabled(Option::DisableGPSAtStartup)) {
// this is equivalent to the auxillary function for GPS
// disable being active at startup. Useful for GPS-denied
// testing to ensure no use is made of the GPS while still
// allowing GPS on EKF2
_gps_disabled = true;
}
if (core == nullptr) {
// don't run multiple filters for 1 IMU
@ -1421,6 +1429,10 @@ bool NavEKF3::setLatLng(const Location &loc, float posAccuracy, uint32_t timesta
#if EK3_FEATURE_POSITION_RESET
dal.log_SetLatLng(loc, posAccuracy, timestamp_ms);
if (option_is_enabled(Option::DisableSetLatLng)) {
return false;
}
if (!core) {
return false;
}

View File

@ -455,6 +455,11 @@ private:
// enum for processing options
enum class Option {
JammingExpected = (1<<0),
// 1 reserved for DisableRangeFusion
DisableSetLatLng = (1<<2),
// 3 reserved for RangeToLocHgtOffset
// 4 reserved for LimitRngToLocUpdate
DisableGPSAtStartup = (1<<5),
};
bool option_is_enabled(Option option) const {
return (_options & (uint32_t)option) != 0;