Copter: tighten accel and gyro pre-arm consistency check

Accel diff threshold to 0.7m/s/s (was 1.0 m/s/s)
Gyro diff threshold to 5deg/sec (was 20deg/sec)
This commit is contained in:
Randy Mackay 2015-01-20 12:44:02 +09:00
parent 765d833efa
commit 0065b3b224

View File

@ -335,12 +335,12 @@
// arming check's maximum acceptable accelerometer vector difference (in m/s/s) between primary and backup accelerometers
#ifndef PREARM_MAX_ACCEL_VECTOR_DIFF
#define PREARM_MAX_ACCEL_VECTOR_DIFF 1.0f // pre arm accel check will fail if primary and backup accelerometer vectors differ by 1m/s/s
#define PREARM_MAX_ACCEL_VECTOR_DIFF 0.70f // pre arm accel check will fail if primary and backup accelerometer vectors differ by 0.7m/s/s
#endif
// arming check's maximum acceptable rotation rate difference (in rad/sec) between primary and backup gyros
#ifndef PREARM_MAX_GYRO_VECTOR_DIFF
#define PREARM_MAX_GYRO_VECTOR_DIFF 0.35f // pre arm gyro check will fail if primary and backup gyro vectors differ by 0.35 rad/sec (=20deg/sec)
#define PREARM_MAX_GYRO_VECTOR_DIFF 0.0873f // pre arm gyro check will fail if primary and backup gyro vectors differ by 0.0873 rad/sec (=5deg/sec)
#endif
//////////////////////////////////////////////////////////////////////////////