mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SMAACM: Add timeout for SPI transfers.
- Detects lockup in the lower level SPI driver. - Add scheduler task tags for FreeRTOS debugging.
This commit is contained in:
parent
eca1417858
commit
bb4474fa6d
|
@ -14,6 +14,8 @@
|
|||
|
||||
using namespace SMACCM;
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// SPI Device Driver
|
||||
|
||||
|
@ -34,7 +36,9 @@ AP_HAL::Semaphore* SMACCMSPIDeviceDriver::get_semaphore()
|
|||
|
||||
void SMACCMSPIDeviceDriver::transaction(const uint8_t *tx, uint8_t *rx, uint16_t len)
|
||||
{
|
||||
spi_transfer(_bus, _device, portMAX_DELAY, tx, rx, len);
|
||||
if (spi_transfer(_bus, _device, 1000, tx, rx, len) < 0) {
|
||||
hal.scheduler->panic("PANIC: SPI transaction timeout.");
|
||||
}
|
||||
}
|
||||
|
||||
// XXX these methods are not implemented
|
||||
|
|
|
@ -55,6 +55,7 @@ static void scheduler_task(void *arg)
|
|||
portTickType last_wake_time;
|
||||
portTickType now;
|
||||
|
||||
vTaskSetApplicationTaskTag(NULL, (pdTASK_HOOK_CODE)3);
|
||||
last_wake_time = xTaskGetTickCount();
|
||||
|
||||
for (;;) {
|
||||
|
@ -97,6 +98,7 @@ static void delay_cb_task(void *arg)
|
|||
portTickType last_wake_time;
|
||||
portTickType now;
|
||||
|
||||
vTaskSetApplicationTaskTag(NULL, (pdTASK_HOOK_CODE)4);
|
||||
last_wake_time = xTaskGetTickCount();
|
||||
|
||||
for (;;) {
|
||||
|
@ -256,8 +258,9 @@ void SMACCMScheduler::run_callbacks()
|
|||
portEXIT_CRITICAL();
|
||||
|
||||
for (int i = 0; i < num_procs; ++i) {
|
||||
if (m_procs[i] != NULL)
|
||||
if (m_procs[i] != NULL) {
|
||||
m_procs[i](now);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue