mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_NavEKF3: define Yaw alignment min GPS speed per vehicle
This commit is contained in:
parent
3e68167263
commit
ce448c4228
@ -6,6 +6,13 @@
|
|||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <AP_DAL/AP_DAL.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 *
|
* RESET FUNCTIONS *
|
||||||
********************************************************/
|
********************************************************/
|
||||||
|
@ -118,9 +118,6 @@
|
|||||||
// number of continuous valid GPS velocity samples required to reset yaw
|
// number of continuous valid GPS velocity samples required to reset yaw
|
||||||
#define GPS_VEL_YAW_ALIGN_COUNT_THRESHOLD 5
|
#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)
|
// maximum GPs ground course uncertainty allowed for yaw alignment (deg)
|
||||||
#define GPS_VEL_YAW_ALIGN_MAX_ANG_ERR 15.0F
|
#define GPS_VEL_YAW_ALIGN_MAX_ANG_ERR 15.0F
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user