AP_Compass: fixed last_update, using last_update_usec()

this broke use of compass in the EKF
This commit is contained in:
Andrew Tridgell 2015-03-14 12:31:23 +11:00
parent 9b29a9cd5d
commit 1962706a33
4 changed files with 6 additions and 5 deletions

View File

@ -34,6 +34,7 @@ void AP_Compass_Backend::publish_field(const Vector3f &mag, uint8_t instance)
apply_corrections(state.field, instance);
state.last_update_ms = hal.scheduler->millis();
_compass._last_update_usec = hal.scheduler->micros();
}
/*

View File

@ -389,8 +389,6 @@ void AP_Compass_HMC5843::read()
_accum_count = 0;
_mag_x_accum = _mag_y_accum = _mag_z_accum = 0;
_compass.last_update = hal.scheduler->micros(); // record time of update
// rotate to the desired orientation
if (_product_id == AP_COMPASS_TYPE_HMC5883L) {
field.rotate(ROTATION_YAW_90);

View File

@ -275,7 +275,7 @@ const AP_Param::GroupInfo Compass::var_info[] PROGMEM = {
// their values.
//
Compass::Compass(void) :
last_update(0),
_last_update_usec(0),
_null_init_done(false),
_thr_or_curr(0.0f),
_backend_count(0),

View File

@ -47,8 +47,6 @@ class Compass
{
friend class AP_Compass_Backend;
public:
uint32_t last_update; //< micros() time of last update
/// Constructor
///
Compass();
@ -233,6 +231,8 @@ public:
// enable HIL mode
void set_hil_mode(void) { _hil_mode = true; }
// return last update time in microseconds
uint32_t last_update_usec(void) const { return _last_update_usec; }
static const struct AP_Param::GroupInfo var_info[];
@ -253,6 +253,8 @@ private:
void _add_backend(AP_Compass_Backend *(detect)(Compass &));
void _detect_backends(void);
//< micros() time of last update
uint32_t _last_update_usec;
// backend objects
AP_Compass_Backend *_backends[COMPASS_MAX_BACKEND];