AP_Compass: HMC5843: fix _calibrate()
The use of _gain_multiple is not necessary because the values of expected_{x,yz} and _mag_{x,y,z} are both in sensor raw unit (i.e., lsbs). That wasn't fixed before in order not to make APM users to recalibrate their compasses.
This commit is contained in:
parent
88a1a928e9
commit
814442563e
@ -417,20 +417,9 @@ bool AP_Compass_HMC5843::_calibrate(uint8_t calibration_gain,
|
||||
}
|
||||
|
||||
if (good_count >= 5) {
|
||||
/*
|
||||
The use of _gain_multiple below is incorrect, as the gain
|
||||
difference between 2.5Ga mode and 1Ga mode is already taken
|
||||
into account by the expected_x and expected_yz values. We
|
||||
are not going to fix it however as it would mean all
|
||||
APM1/APM2 users redoing their compass calibration. The
|
||||
impact is that the values we report on APM1/APM2 are lower
|
||||
than they should be (by a multiple of about 0.6). This
|
||||
doesn't have any impact other than the learned compass
|
||||
offsets
|
||||
*/
|
||||
_scaling[0] = _scaling[0] * _gain_multiple / good_count;
|
||||
_scaling[1] = _scaling[1] * _gain_multiple / good_count;
|
||||
_scaling[2] = _scaling[2] * _gain_multiple / good_count;
|
||||
_scaling[0] = _scaling[0] / good_count;
|
||||
_scaling[1] = _scaling[1] / good_count;
|
||||
_scaling[2] = _scaling[2] / good_count;
|
||||
success = true;
|
||||
} else {
|
||||
/* best guess */
|
||||
|
@ -31,7 +31,9 @@ private:
|
||||
bool read_register(uint8_t address, uint8_t *value);
|
||||
bool write_register(uint8_t address, uint8_t value);
|
||||
|
||||
bool _calibrate(uint8_t calibration_gain, uint16_t expected_x, uint16_t expected_yz);
|
||||
bool _calibrate(uint8_t calibration_gain,
|
||||
uint16_t expected_x,
|
||||
uint16_t expected_yz);
|
||||
bool _detect_version();
|
||||
|
||||
uint32_t _retry_time; // when unhealthy the millis() value to retry at
|
||||
|
Loading…
Reference in New Issue
Block a user