5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-13 11:28:30 -04:00

Copter: increase ekf check threshold for inav

This increases the accel correction from 60cm/s to 80cm/s before the ekf
check will trigger a land
This commit is contained in:
Randy Mackay 2014-08-04 15:06:37 +09:00
parent 009f42b2e1
commit c7ba44db2d

View File

@ -12,7 +12,7 @@
#endif
#ifndef EKF_CHECK_COMPASS_INAV_CONVERSION
# define EKF_CHECK_COMPASS_INAV_CONVERSION 0.01f // converts the inertial nav's acceleration corrections to a form that is comparable to the ekf variance
# define EKF_CHECK_COMPASS_INAV_CONVERSION 0.0075f // converts the inertial nav's acceleration corrections to a form that is comparable to the ekf variance
#endif
#ifndef EKF_CHECK_WARNING_TIME