Browse Source

AP_Compass: tidy constructor

zr-v5.1
Peter Barker 5 years ago committed by Peter Barker
parent
commit
880af0de4a
  1. 4
      libraries/AP_Compass/CompassCalibrator.cpp
  2. 3
      libraries/AP_Compass/CompassCalibrator.h

4
libraries/AP_Compass/CompassCalibrator.cpp

@ -73,9 +73,7 @@ extern const AP_HAL::HAL& hal; @@ -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();
}

3
libraries/AP_Compass/CompassCalibrator.h

@ -5,7 +5,6 @@ @@ -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: @@ -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

Loading…
Cancel
Save