mirror of https://github.com/ArduPilot/ardupilot
INS: set the acceptable calibration error equal on all axes
This commit is contained in:
parent
b9fb683236
commit
bbb2bbc721
|
@ -392,11 +392,11 @@ bool AP_InertialSensor::_calibrate_accel( Vector3f accel_sample[6], Vector3f& ac
|
|||
accel_offsets.z = beta[2] * accel_scale.z;
|
||||
|
||||
// sanity check scale
|
||||
if( accel_scale.is_nan() || fabs(accel_scale.x-1.0) > 0.1 || fabs(accel_scale.y-1.0) > 1.1 || fabs(accel_scale.z-1.0) > 1.1 ) {
|
||||
if( accel_scale.is_nan() || fabs(accel_scale.x-1.0) > 0.1 || fabs(accel_scale.y-1.0) > 0.1 || fabs(accel_scale.z-1.0) > 0.1 ) {
|
||||
success = false;
|
||||
}
|
||||
// sanity check offsets (2.0 is roughly 2/10th of a G, 5.0 is roughly half a G)
|
||||
if( accel_offsets.is_nan() || fabs(accel_offsets.x) > 2.0 || fabs(accel_offsets.y) > 2.0 || fabs(accel_offsets.z) > 5.0 ) {
|
||||
if( accel_offsets.is_nan() || fabs(accel_offsets.x) > 2.0 || fabs(accel_offsets.y) > 2.0 || fabs(accel_offsets.z) > 2.0 ) {
|
||||
success = false;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue