diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp index 330befc9d1d2b4..0df3aea18b75f6 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp @@ -6,6 +6,16 @@ #include #include +// minimum GPS horizontal speed required to use GPS ground course for yaw alignment (m/s) +#if APM_BUILD_TYPE(APM_BUILD_Rover) + #define GPS_VEL_YAW_ALIGN_MIN_SPD 0.5F +#elif APM_BUILD_TYPE(APM_BUILD_ArduPlane) + #define GPS_VEL_YAW_ALIGN_MIN_SPD 5.0F +#else + // copter, heli or undefined + #define GPS_VEL_YAW_ALIGN_MIN_SPD 2.0F +#endif + /******************************************************** * RESET FUNCTIONS * ********************************************************/ diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.h b/libraries/AP_NavEKF3/AP_NavEKF3_core.h index 8ba964b7e88fda..48284e136cb2e0 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.h @@ -118,9 +118,6 @@ // number of continuous valid GPS velocity samples required to reset yaw #define GPS_VEL_YAW_ALIGN_COUNT_THRESHOLD 5 -// minimum GPS horizontal speed required to use GPS ground course for yaw alignment (m/s) -#define GPS_VEL_YAW_ALIGN_MIN_SPD 5.0F - // maximum GPs ground course uncertainty allowed for yaw alignment (deg) #define GPS_VEL_YAW_ALIGN_MAX_ANG_ERR 15.0F