mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-29 20:18:31 -04:00
HAL_ChibiOS: lock all DMA channels on reboot
this fixes a problem with the ICM-20789 on I2C where a reboot while the bus is active leaves the IMU in a dead state where it can't be recovered without a power cycle.
This commit is contained in:
parent
32ddbca428
commit
875008f2a6
@ -29,6 +29,7 @@
|
|||||||
|
|
||||||
#include <AP_Scheduler/AP_Scheduler.h>
|
#include <AP_Scheduler/AP_Scheduler.h>
|
||||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||||
|
#include "shared_dma.h"
|
||||||
|
|
||||||
using namespace ChibiOS;
|
using namespace ChibiOS;
|
||||||
|
|
||||||
@ -207,6 +208,10 @@ void Scheduler::reboot(bool hold_in_bootloader)
|
|||||||
hal.rcout->force_safety_on();
|
hal.rcout->force_safety_on();
|
||||||
hal.rcout->force_safety_no_wait();
|
hal.rcout->force_safety_no_wait();
|
||||||
|
|
||||||
|
// lock all shared DMA channels. This has the effect of waiting
|
||||||
|
// till the sensor buses are idle
|
||||||
|
Shared_DMA::lock_all();
|
||||||
|
|
||||||
// delay to ensure the async force_saftey operation completes
|
// delay to ensure the async force_saftey operation completes
|
||||||
delay(500);
|
delay(500);
|
||||||
|
|
||||||
|
@ -136,3 +136,14 @@ void Shared_DMA::unlock_from_IRQ(void)
|
|||||||
have_lock = false;
|
have_lock = false;
|
||||||
chSysUnlockFromISR();
|
chSysUnlockFromISR();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
lock all channels - used on reboot to ensure no sensor DMA is in
|
||||||
|
progress
|
||||||
|
*/
|
||||||
|
void Shared_DMA::lock_all(void)
|
||||||
|
{
|
||||||
|
for (uint8_t i=0; i<SHARED_DMA_MAX_STREAM_ID; i++) {
|
||||||
|
chBSemWait(&locks[i].semaphore);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
@ -55,6 +55,9 @@ public:
|
|||||||
//should be called inside the destructor of Shared DMA participants
|
//should be called inside the destructor of Shared DMA participants
|
||||||
void unregister(void);
|
void unregister(void);
|
||||||
|
|
||||||
|
// lock all shared DMA channels. Used on reboot
|
||||||
|
static void lock_all(void);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
dma_allocate_fn_t allocate;
|
dma_allocate_fn_t allocate;
|
||||||
dma_allocate_fn_t deallocate;
|
dma_allocate_fn_t deallocate;
|
||||||
|
Loading…
Reference in New Issue
Block a user