mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-23 08:07:35 +08:00
STM32: Fixed race condition in clock driver
This commit is contained in:
@@ -119,12 +119,12 @@ uavcan::MonotonicTime getMonotonic()
|
||||
{
|
||||
CriticalSectionLock locker;
|
||||
usec = sampleFromCriticalSection(&time_mono);
|
||||
}
|
||||
#if !NDEBUG
|
||||
static uavcan::uint64_t prev_usec = 0; // Self-test
|
||||
assert(prev_usec <= usec);
|
||||
prev_usec = usec;
|
||||
static uavcan::uint64_t prev_usec = 0; // Self-test
|
||||
assert(prev_usec <= usec);
|
||||
prev_usec = usec;
|
||||
#endif
|
||||
}
|
||||
return uavcan::MonotonicTime::fromUSec(usec);
|
||||
}
|
||||
|
||||
@@ -239,7 +239,7 @@ UAVCAN_STM32_IRQ_HANDLER(TIMX_IRQHandler)
|
||||
{
|
||||
UAVCAN_STM32_IRQ_PROLOGUE();
|
||||
|
||||
TIMX->SR = ~TIM_SR_UIF;
|
||||
TIMX->SR = 0;
|
||||
|
||||
using namespace uavcan_stm32::clock;
|
||||
assert(initialized);
|
||||
|
||||
Reference in New Issue
Block a user