mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_Compass: tidy constructor
This commit is contained in:
parent
fcc490b68f
commit
76c275756b
@ -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();
|
||||
}
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user