AP_AHRS: Add accessor function for EKF yaw reset request

AP_AHRS: Send yaw reset request to EKF2
This commit is contained in:
Paul Riseborough 2020-03-11 14:46:52 +11:00 committed by Andrew Tridgell
parent 9cf75bf22e
commit 22c2ea7cbf
3 changed files with 32 additions and 0 deletions

View File

@ -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;

View File

@ -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

View File

@ -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