From 8fac70149dc1a649d7397171af4f64d04bcc74b7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 22 Nov 2019 17:24:29 +1100 Subject: [PATCH] AP_Compass: tidy constructor --- libraries/AP_Compass/CompassCalibrator.cpp | 4 +--- libraries/AP_Compass/CompassCalibrator.h | 3 +-- 2 files changed, 2 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Compass/CompassCalibrator.cpp b/libraries/AP_Compass/CompassCalibrator.cpp index cdd4c74160..633a5a0541 100644 --- a/libraries/AP_Compass/CompassCalibrator.cpp +++ b/libraries/AP_Compass/CompassCalibrator.cpp @@ -73,9 +73,7 @@ extern const AP_HAL::HAL& hal; ///////////////////// PUBLIC INTERFACE ///////////////////// //////////////////////////////////////////////////////////// -CompassCalibrator::CompassCalibrator(): - _tolerance(COMPASS_CAL_DEFAULT_TOLERANCE), - _sample_buffer(nullptr) +CompassCalibrator::CompassCalibrator() { stop(); } diff --git a/libraries/AP_Compass/CompassCalibrator.h b/libraries/AP_Compass/CompassCalibrator.h index 4b795a6c24..e4b3774d9d 100644 --- a/libraries/AP_Compass/CompassCalibrator.h +++ b/libraries/AP_Compass/CompassCalibrator.h @@ -5,7 +5,6 @@ #define COMPASS_CAL_NUM_SPHERE_PARAMS 4 #define COMPASS_CAL_NUM_ELLIPSOID_PARAMS 9 #define COMPASS_CAL_NUM_SAMPLES 300 // number of samples required before fitting begins -#define COMPASS_CAL_DEFAULT_TOLERANCE 5.0f // default RMS tolerance #define COMPASS_MIN_SCALE_FACTOR 0.85 #define COMPASS_MAX_SCALE_FACTOR 1.3 @@ -170,7 +169,7 @@ private: // values provided by caller float _delay_start_sec; // seconds to delay start of calibration (provided by caller) bool _retry; // true if calibration should be restarted on failured (provided by caller) - float _tolerance; // worst acceptable tolerance (aka fitness). see set_tolerance() + float _tolerance = 5.0; // worst acceptable RMS tolerance (aka fitness). see set_tolerance() uint16_t _offset_max; // maximum acceptable offsets (provided by caller) // behavioral state