AP_Compass: loosen calibration acceptance tolerance
This commit is contained in:
parent
987f55387e
commit
0edf1df28e
@ -34,9 +34,9 @@ Compass::start_calibration(uint8_t i, bool retry, bool autosave, float delay)
|
||||
AP_Notify::events.initiated_compass_cal = 1;
|
||||
}
|
||||
if (i == get_primary()) {
|
||||
_calibrator[i].set_tolerance(5);
|
||||
_calibrator[i].set_tolerance(8);
|
||||
} else {
|
||||
_calibrator[i].set_tolerance(10);
|
||||
_calibrator[i].set_tolerance(16);
|
||||
}
|
||||
_calibrator[i].start(retry, autosave, delay);
|
||||
return true;
|
||||
|
@ -293,11 +293,11 @@ bool CompassCalibrator::accept_sample(const Vector3f& sample)
|
||||
return false;
|
||||
}
|
||||
|
||||
float max_distance = fabsf(5.38709f * _params.radius / sqrtf((float)COMPASS_CAL_NUM_SAMPLES)) / 3.0f;
|
||||
float min_distance = fabsf(5.38709f * _params.radius / sqrtf((float)COMPASS_CAL_NUM_SAMPLES)) / 3.0f;
|
||||
|
||||
for (uint16_t i = 0; i<_samples_collected; i++){
|
||||
float distance = (sample - _sample_buffer[i].get()).length();
|
||||
if(distance < max_distance) {
|
||||
if(distance < min_distance) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user