diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 0b3684af40..5c655c07d5 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -186,6 +186,9 @@ public: // check whether external navigation is providing yaw. Allows compass pre-arm checks to be bypassed virtual bool is_ext_nav_used_for_yaw(void) const { return false; } + + // request EKF yaw reset to try and avoid the need for an EKF lane switch or failsafe + virtual void request_yaw_reset(void) {} // Euler angles (radians) float roll; diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp index 15451228e3..02e4e5117c 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp @@ -2196,6 +2196,32 @@ void AP_AHRS_NavEKF::check_lane_switch(void) } } +// request EKF yaw reset to try and avoid the need for an EKF lane switch or failsafe +void AP_AHRS_NavEKF::request_yaw_reset(void) +{ + switch (active_EKF_type()) { + case EKFType::NONE: + break; + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + case EKFType::SITL: + break; +#endif + +#if HAL_NAVEKF2_AVAILABLE + case EKFType::TWO: + EKF2.requestYawReset(); + break; +#endif + +#if HAL_NAVEKF3_AVAILABLE + case EKFType::THREE: + EKF3.requestYawReset(); + break; +#endif + } +} + void AP_AHRS_NavEKF::Log_Write() { #if HAL_NAVEKF2_AVAILABLE diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.h b/libraries/AP_AHRS/AP_AHRS_NavEKF.h index f2ca6b61fc..e94fb0334d 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.h +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.h @@ -287,6 +287,9 @@ public: // see if EKF lane switching is possible to avoid EKF failsafe void check_lane_switch(void) override; + // request EKF yaw reset to try and avoid the need for an EKF lane switch or failsafe + void request_yaw_reset(void) override; + void Log_Write(); // check whether external navigation is providing yaw. Allows compass pre-arm checks to be bypassed