Skip to content

Commit

Permalink
AP_NavEKF3: define Yaw alignment min GPS speed per vehicle
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Nov 19, 2023
1 parent 2d465a5 commit 8536878
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 3 deletions.
10 changes: 10 additions & 0 deletions libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp
Expand Up @@ -6,6 +6,16 @@
#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_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 *
********************************************************/
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

0 comments on commit 8536878

Please sign in to comment.