Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_NavEKF3: define Yaw alignment min GPS speed per vehicle #24206

Merged
merged 1 commit into from Mar 25, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
7 changes: 7 additions & 0 deletions libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp
Expand Up @@ -6,6 +6,13 @@
#include <GCS_MAVLink/GCS.h>
#include <AP_DAL/AP_DAL.h>

// minimum GPS horizontal speed required to use GPS ground course for yaw alignment (m/s)
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
#define GPS_VEL_YAW_ALIGN_MIN_SPD 5.0F
#else
#define GPS_VEL_YAW_ALIGN_MIN_SPD 1.0F
#endif

/********************************************************
* RESET FUNCTIONS *
********************************************************/
Expand Down
3 changes: 0 additions & 3 deletions libraries/AP_NavEKF3/AP_NavEKF3_core.h
Expand Up @@ -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

Expand Down