mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Compass: add last_update_usec per instance
This commit is contained in:
parent
69cfe11455
commit
cedc9a8670
@ -34,7 +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();
|
||||
state.last_update_usec = hal.scheduler->micros();
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -275,7 +275,6 @@ const AP_Param::GroupInfo Compass::var_info[] PROGMEM = {
|
||||
// their values.
|
||||
//
|
||||
Compass::Compass(void) :
|
||||
_last_update_usec(0),
|
||||
_backend_count(0),
|
||||
_compass_count(0),
|
||||
_board_orientation(ROTATION_NONE),
|
||||
@ -286,6 +285,7 @@ Compass::Compass(void) :
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
for (uint8_t i=0; i<COMPASS_MAX_BACKEND; i++) {
|
||||
_backends[i] = NULL;
|
||||
_state[i].last_update_usec = 0;
|
||||
}
|
||||
|
||||
#if COMPASS_MAX_INSTANCES > 1
|
||||
@ -604,7 +604,7 @@ void Compass::setHIL(uint8_t instance, const Vector3f &mag)
|
||||
{
|
||||
_hil.field[instance] = mag;
|
||||
_hil.healthy[instance] = true;
|
||||
_last_update_usec = hal.scheduler->micros();
|
||||
_state[instance].last_update_usec = hal.scheduler->micros();
|
||||
}
|
||||
|
||||
const Vector3f& Compass::getHIL(uint8_t instance) const
|
||||
|
@ -233,7 +233,7 @@ public:
|
||||
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; }
|
||||
uint32_t last_update_usec(void) const { return _state[get_primary()].last_update_usec; }
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
@ -255,9 +255,6 @@ 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];
|
||||
uint8_t _backend_count;
|
||||
@ -321,6 +318,7 @@ private:
|
||||
|
||||
// when we last got data
|
||||
uint32_t last_update_ms;
|
||||
uint32_t last_update_usec;
|
||||
} _state[COMPASS_MAX_INSTANCES];
|
||||
|
||||
// if we want HIL only
|
||||
|
Loading…
Reference in New Issue
Block a user