Browse Source

AP_InertialSensor: allow for 1,1,1 accel scaling

this supports simple accel calibration
mission-4.1.18
Andrew Tridgell 8 years ago
parent
commit
6a6f9681ab
  1. 5
      libraries/AP_InertialSensor/AP_InertialSensor.cpp

5
libraries/AP_InertialSensor/AP_InertialSensor.cpp

@ -981,11 +981,6 @@ bool AP_InertialSensor::accel_calibrated_ok_all() const @@ -981,11 +981,6 @@ bool AP_InertialSensor::accel_calibrated_ok_all() const
if (_accel_offset[i].get().is_zero()) {
return false;
}
// exactly 1.0 scaling is extremely unlikely
const Vector3f &scaling = _accel_scale[i].get();
if (is_equal(scaling.x,1.0f) && is_equal(scaling.y,1.0f) && is_equal(scaling.z,1.0f)) {
return false;
}
// zero scaling also indicates not calibrated
if (_accel_scale[i].get().is_zero()) {
return false;

Loading…
Cancel
Save