mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-23 22:58:10 +08:00
EKF2 update GPS and airspeed delay defaults (#7353)
* update ecl to latest * EKF2_GPS_DELAY change default 200ms -> 110ms - 110msec is more representative of what most users are flying * EKF2_ASP_DELAY change default 200ms -> 100ms The EKF is relatively insensitive to airspeed sensor delays and the effective delay is installation specific, so it has been set to a value that does not cause the data buffers to be longer than is required to accomodate GPS delays.
This commit is contained in:
committed by
Paul Riseborough
parent
6fbf09d8da
commit
833cdc9236
+1
-1
Submodule src/lib/ecl updated: 9dee57f9ca...d0b4f1e225
@@ -82,7 +82,7 @@ PARAM_DEFINE_FLOAT(EKF2_BARO_DELAY, 0);
|
||||
* @unit ms
|
||||
* @decimal 1
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(EKF2_GPS_DELAY, 200);
|
||||
PARAM_DEFINE_FLOAT(EKF2_GPS_DELAY, 110);
|
||||
|
||||
/**
|
||||
* Optical flow measurement delay relative to IMU measurements
|
||||
@@ -116,7 +116,7 @@ PARAM_DEFINE_FLOAT(EKF2_RNG_DELAY, 5);
|
||||
* @unit ms
|
||||
* @decimal 1
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(EKF2_ASP_DELAY, 200);
|
||||
PARAM_DEFINE_FLOAT(EKF2_ASP_DELAY, 100);
|
||||
|
||||
/**
|
||||
* Vision Position Estimator delay relative to IMU measurements
|
||||
|
||||
Reference in New Issue
Block a user