[AP_NavEKF3] Add EK3_Options bit: PlaneRequiresGPS

Setting the PlaneRequiresGPS bit to false enables fully GPS-denied takeoffs for non-VTOL Planes.
This commit is contained in:
Paul Erik Frivold 2024-10-15 12:08:37 +02:00 committed by Paul Erik Frivold
parent 145cc4bb26
commit 06fb9f605e
3 changed files with 7 additions and 5 deletions

View File

@ -738,10 +738,10 @@ 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 behaviour 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 GPS measurements from getting fused. If PlaneRequiresGPS is true, EKF3 will not initialize unless the preferred GPS has at least GPS_OK_FIX_3D.
// @Bitmask: 0:JammingExpected,1:PlaneRequiresGPS
// @User: Advanced
AP_GROUPINFO("OPTIONS", 11, NavEKF3, _options, 0),
AP_GROUPINFO("OPTIONS", 11, NavEKF3, _options, 2),
AP_GROUPEND
};

View File

@ -455,6 +455,7 @@ private:
// enum for processing options
enum class Options {
JammingExpected = (1<<0),
PlaneRequiresGPS = (1<<1),
};
// Possible values for _flowUse

View File

@ -472,8 +472,9 @@ bool NavEKF3_core::InitialiseFilterBootstrap(void)
// update sensor selection (for affinity)
update_sensor_selection();
// If we are a plane and don't have GPS lock then don't initialise
if (assume_zero_sideslip() && dal.gps().status(preferred_gps) < AP_DAL_GPS::GPS_OK_FIX_3D) {
// If PlaneRequiresGPS bit in EK3_OPTIONS is set, then don't initialise if we are a plane and don't have GPS lock
if ((frontend->_options & (int32_t)NavEKF3::Options::PlaneRequiresGPS) &&
assume_zero_sideslip() && dal.gps().status(preferred_gps) < AP_DAL_GPS::GPS_OK_FIX_3D) {
dal.snprintf(prearm_fail_string,
sizeof(prearm_fail_string),
"EKF3 init failure: No GPS lock");