Browse Source

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
master
Randy Mackay 11 years ago
parent
commit
c7ba44db2d
  1. 2
      ArduCopter/ekf_check.pde

2
ArduCopter/ekf_check.pde

@ -12,7 +12,7 @@ @@ -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

Loading…
Cancel
Save