AP_Compass: use board defined compass ofs max in calibrator

This commit is contained in:
Andrew Tridgell 2016-09-17 19:02:02 +10:00
parent e7656fb7ac
commit 36ea946cf5
1 changed files with 11 additions and 3 deletions

View File

@ -68,6 +68,14 @@ extern const AP_HAL::HAL& hal;
///////////////////// PUBLIC INTERFACE /////////////////////
////////////////////////////////////////////////////////////
#ifdef AP_ARMING_COMPASS_OFFSETS_MAX
#define COMPASS_CALIBRATOR_OFS_MAX AP_ARMING_COMPASS_OFFSETS_MAX
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
#define COMPASS_CALIBRATOR_OFS_MAX 2000
#else
#define COMPASS_CALIBRATOR_OFS_MAX 1000
#endif
CompassCalibrator::CompassCalibrator():
_tolerance(COMPASS_CAL_DEFAULT_TOLERANCE),
_sample_buffer(NULL)
@ -341,9 +349,9 @@ bool CompassCalibrator::set_status(compass_cal_status_t status) {
bool CompassCalibrator::fit_acceptable() {
if( !isnan(_fitness) &&
_params.radius > 150 && _params.radius < 950 && //Earth's magnetic field strength range: 250-850mG
fabsf(_params.offset.x) < 1000 &&
fabsf(_params.offset.y) < 1000 &&
fabsf(_params.offset.z) < 1000 &&
fabsf(_params.offset.x) < COMPASS_CALIBRATOR_OFS_MAX &&
fabsf(_params.offset.y) < COMPASS_CALIBRATOR_OFS_MAX &&
fabsf(_params.offset.z) < COMPASS_CALIBRATOR_OFS_MAX &&
_params.diag.x > 0.2f && _params.diag.x < 5.0f &&
_params.diag.y > 0.2f && _params.diag.y < 5.0f &&
_params.diag.z > 0.2f && _params.diag.z < 5.0f &&