mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
HAL_ChibiOS: fixed build on F4
This commit is contained in:
parent
d6bedc3bdf
commit
bd27d7fc26
@ -122,11 +122,14 @@ void Shared_DMA::lock_core(void)
|
|||||||
locks[stream_id2].deallocate = deallocate;
|
locks[stream_id2].deallocate = deallocate;
|
||||||
locks[stream_id2].obj = this;
|
locks[stream_id2].obj = this;
|
||||||
}
|
}
|
||||||
} else if (stream_id1 == STM32_DMA_STREAM_ID_ANY ||
|
}
|
||||||
stream_id2 == STM32_DMA_STREAM_ID_ANY) {
|
#ifdef STM32_DMA_STREAM_ID_ANY
|
||||||
|
else if (stream_id1 == STM32_DMA_STREAM_ID_ANY ||
|
||||||
|
stream_id2 == STM32_DMA_STREAM_ID_ANY) {
|
||||||
// call allocator without needing locking
|
// call allocator without needing locking
|
||||||
allocate(this);
|
allocate(this);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
have_lock = true;
|
have_lock = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user