mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Compass: publish raw and unfiltered field for HMC5843 compass
This commit is contained in:
parent
8cdc9748b3
commit
cdd8bae6ac
@ -178,6 +178,7 @@ void AP_Compass_HMC5843::accumulate(void)
|
||||
// have the right orientation!)
|
||||
return;
|
||||
}
|
||||
|
||||
uint32_t tnow = hal.scheduler->micros();
|
||||
if (_accum_count != 0 && (tnow - _last_accum_time) < 13333) {
|
||||
// the compass gets new data at 75Hz
|
||||
@ -197,6 +198,21 @@ void AP_Compass_HMC5843::accumulate(void)
|
||||
// for ease of calculation. We expect to do reads at 10Hz, and
|
||||
// we get new data at most 75Hz, so we don't expect to
|
||||
// accumulate more than 8 before a read
|
||||
// get raw_field - sensor frame, uncorrected
|
||||
Vector3f raw_field = Vector3f(_mag_x, _mag_y, _mag_z);
|
||||
|
||||
// rotate raw_field from sensor frame to body frame
|
||||
rotate_field(raw_field, _compass_instance);
|
||||
|
||||
// publish raw_field (uncorrected point sample) for calibration use
|
||||
publish_raw_field(raw_field, tnow, _compass_instance);
|
||||
|
||||
// correct raw_field for known errors
|
||||
correct_field(raw_field, _compass_instance);
|
||||
|
||||
// publish raw_field (corrected point sample) for EKF use
|
||||
publish_unfiltered_field(raw_field, tnow, _compass_instance);
|
||||
|
||||
_mag_x_accum += _mag_x;
|
||||
_mag_y_accum += _mag_y;
|
||||
_mag_z_accum += _mag_z;
|
||||
|
@ -1 +1 @@
|
||||
Subproject commit d447403a17ff7433ba99d65c5ce60324f5791ce2
|
||||
Subproject commit 7c5ef883fc3307b44bef9d5f7b51cb144cdf400a
|
Loading…
Reference in New Issue
Block a user