diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 22da4dd995..c31003e27c 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -183,7 +183,10 @@ public: // see if EKF lane switching is possible to avoid EKF failsafe virtual void check_lane_switch(void) {} - + + // 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; } + // Euler angles (radians) float roll; float pitch; diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.h b/libraries/AP_AHRS/AP_AHRS_NavEKF.h index 197f1eb8bc..7101f1ca8c 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.h +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.h @@ -280,8 +280,8 @@ public: void Log_Write(); - // check whether compass can be bypassed for arming check in case when external navigation data is available - bool is_ext_nav_used_for_yaw(void) const; + // check whether external navigation is providing yaw. Allows compass pre-arm checks to be bypassed + bool is_ext_nav_used_for_yaw(void) const override; // these are only out here so vehicles can reference them for parameters #if HAL_NAVEKF2_AVAILABLE