AP_Compass: don't update last_update_usec for raw fields

this fixes a problem where the EKF gets compass samples at 50Hz
instead of the expected 10Hz
This commit is contained in:
Andrew Tridgell 2015-10-21 13:22:24 +11:00
parent 695efb8df3
commit 4a8a24a1a2
1 changed files with 5 additions and 1 deletions

View File

@ -44,7 +44,11 @@ void AP_Compass_Backend::publish_raw_field(const Vector3f &mag, uint32_t time_us
Compass::mag_state &state = _compass._state[instance];
state.last_update_ms = hal.scheduler->millis();
state.last_update_usec = hal.scheduler->micros();
// note that we do not set last_update_usec here as otherwise the
// EKF and DCM would end up consuming compass data at the full
// sensor rate. We want them to consume only the filtered fields
state.raw_field = mag;
state.raw_meas_time_us = time_us;
state.updated_raw_field = true;