AP_Arming: add param for accel error threshold

This is the threshold error to determine inconsistent accelerometers.
This commit is contained in:
Tom Pittenger 2015-12-21 13:51:12 -08:00 committed by Andrew Tridgell
parent 72edfcd1f6
commit 841f34effa
2 changed files with 12 additions and 3 deletions

View File

@ -23,6 +23,7 @@
#define AP_ARMING_COMPASS_MAGFIELD_MAX 875 // 1.65 * 530 milligauss
#define AP_ARMING_BOARD_VOLTAGE_MIN 4.3f
#define AP_ARMING_BOARD_VOLTAGE_MAX 5.8f
#define AP_ARMING_ACCEL_ERROR_THRESHOLD 0.75f
extern const AP_HAL::HAL& hal;
@ -42,6 +43,14 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = {
// @User: Standard
AP_GROUPINFO("CHECK", 2, AP_Arming, checks_to_perform, ARMING_CHECK_ALL),
// @Param: ACCTHRESH
// @DisplayName: Accelerometer error threshold
// @Description: Accelerometer error threshold used to determine inconsistent accelerometers. Compares this error range to other accelerometers to detect a hardware or calibration error. Lower value means tighter check and harder to pass arming check. Not all accelerometers are created equal.
// @Units: m/s/s
// @Range: 0.25 3.0
// @User: Advanced
AP_GROUPINFO("ACCTHRESH", 3, AP_Arming, accel_error_threshold, AP_ARMING_ACCEL_ERROR_THRESHOLD),
AP_GROUPEND
};
@ -171,9 +180,8 @@ bool AP_Arming::ins_checks(bool report)
// get next accel vector
const Vector3f &accel_vec = ins.get_accel(i);
Vector3f vec_diff = accel_vec - prime_accel_vec;
// allow for up to 0.75 m/s/s difference. Has to pass
// in last 10 seconds
float threshold = 0.75f;
// allow for user-defined difference, typically 0.75 m/s/s. Has to pass in last 10 seconds
float threshold = accel_error_threshold;
if (i >= 2) {
/*
we allow for a higher threshold for IMU3 as it

View File

@ -69,6 +69,7 @@ protected:
AP_Int8 require;
AP_Int8 rudder_arming_value;
AP_Int16 checks_to_perform; // bitmask for which checks are required
AP_Float accel_error_threshold;
// references
const AP_AHRS &ahrs;