Skip to content

Commit

Permalink
AP_InertialSensor: prevent a lockup in MPU6000 driver
Browse files Browse the repository at this point in the history
thanks to the VRBrain port for noticing this bug.

Failing to get the semaphore is an expected error with the MPU6000, as
we read data both from timer context and mainline code. That means
semaphore conflicts are inevitable. We shouldn't consider them an
error, and shouldn't panic when some arbitrary number of them have
happened since boot.

Instead the wait_for_sample() code checks that we receive new data at
least every 50ms. That is a much safer test.
  • Loading branch information
Andrew Tridgell committed Sep 23, 2013
1 parent c888f02 commit 770b7b5
Showing 1 changed file with 7 additions and 11 deletions.
18 changes: 7 additions & 11 deletions libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -419,18 +419,14 @@ void AP_InertialSensor_MPU6000::_poll_data(uint32_t now)
*/
void AP_InertialSensor_MPU6000::_read_data_from_timerprocess()
{
static uint8_t semfail_ctr = 0;
bool got = _spi_sem->take_nonblocking();
if (!got) {
semfail_ctr++;
if (semfail_ctr > 100) {
hal.scheduler->panic(PSTR("PANIC: failed to take SPI semaphore "
"100 times in AP_InertialSensor_MPU6000::"
"_read_data_from_timerprocess"));
}
if (!_spi_sem->take_nonblocking()) {
/*
the semaphore being busy is an expected condition when the
mainline code is calling num_samples_available() which will
grab the semaphore. We return now and rely on the mainline
code grabbing the latest sample.
*/
return;
} else {
semfail_ctr = 0;
}

_last_sample_time_micros = hal.scheduler->micros();
Expand Down

0 comments on commit 770b7b5

Please sign in to comment.