diff --git a/libraries/AP_Compass/AP_Compass_HMC5843.cpp b/libraries/AP_Compass/AP_Compass_HMC5843.cpp index adcf941a73..dc452baad7 100644 --- a/libraries/AP_Compass/AP_Compass_HMC5843.cpp +++ b/libraries/AP_Compass/AP_Compass_HMC5843.cpp @@ -138,9 +138,6 @@ AP_Compass_HMC5843::init() uint16_t expected_yz = 715; float gain_multiple = 1.0; - // call the parent class init for common code - Compass::init(); - delay(10); // determine if we are using 5843 or 5883L diff --git a/libraries/AP_Compass/Compass.cpp b/libraries/AP_Compass/Compass.cpp index c9d4a4e7be..9a9ef77569 100644 --- a/libraries/AP_Compass/Compass.cpp +++ b/libraries/AP_Compass/Compass.cpp @@ -18,6 +18,8 @@ Compass::Compass(void) : _declination (0.0), _null_init_done(false), _null_enable(false), + _learn(1), + _use_for_yaw(1), product_id(AP_COMPASS_TYPE_UNKNOWN) { // Default the orientation matrix to none - will be overridden at group load time @@ -25,21 +27,11 @@ Compass::Compass(void) : _orientation_matrix.set(ROTATION_NONE); } -//_group - // Default init method, just returns success. // bool Compass::init() { - // enable learning by default - if (!_learn.load()) { - _learn.set(1); - } - // enable use for yaw calculation by default - if (!_use_for_yaw.load()) { - _use_for_yaw.set(1); - } return true; }