mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
MPU6000: fixed minor timing bug
if we miss a sample due to SPI contention we shouldn't update last sample time
This commit is contained in:
parent
f93a7d50eb
commit
b39166b71a
@ -331,7 +331,6 @@ bool AP_InertialSensor_MPU6000::_data_ready()
|
|||||||
void AP_InertialSensor_MPU6000::_poll_data(uint32_t now)
|
void AP_InertialSensor_MPU6000::_poll_data(uint32_t now)
|
||||||
{
|
{
|
||||||
if (_data_ready()) {
|
if (_data_ready()) {
|
||||||
_last_sample_time_micros = now;
|
|
||||||
_read_data_from_timerprocess();
|
_read_data_from_timerprocess();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -358,6 +357,7 @@ void AP_InertialSensor_MPU6000::_read_data_from_timerprocess()
|
|||||||
semfail_ctr = 0;
|
semfail_ctr = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
_last_sample_time_micros = hal.scheduler->micros();
|
||||||
_read_data_transaction();
|
_read_data_transaction();
|
||||||
|
|
||||||
_spi_sem->give();
|
_spi_sem->give();
|
||||||
|
Loading…
Reference in New Issue
Block a user