From dbae5c29917fec23ae75a34672d36eadef68e5a8 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 7 Jun 2023 19:59:25 +1000 Subject: [PATCH] add support for semaphores around allocate and freeing blocks of memory --- canard.c | 16 +++++++++++++++- canard.h | 12 ++++++++++++ 2 files changed, 27 insertions(+), 1 deletion(-) diff --git a/canard.c b/canard.c index c9f210b..3463a8d 100644 --- a/canard.c +++ b/canard.c @@ -1837,10 +1837,16 @@ CANARD_INTERNAL void initPoolAllocator(CanardPoolAllocator* allocator, allocator->statistics.capacity_blocks = buf_len; allocator->statistics.current_usage_blocks = 0; allocator->statistics.peak_usage_blocks = 0; + // user should initialize semaphore after the canardInit + // or at first call of canard_allocate_sem_take + allocator->semaphore = NULL; } CANARD_INTERNAL void* allocateBlock(CanardPoolAllocator* allocator) { +#if CANARD_ALLOCATE_SEM + canard_allocate_sem_take(allocator); +#endif // Check if there are any blocks available in the free list. if (allocator->free_list == NULL) { @@ -1857,12 +1863,17 @@ CANARD_INTERNAL void* allocateBlock(CanardPoolAllocator* allocator) { allocator->statistics.peak_usage_blocks = allocator->statistics.current_usage_blocks; } - +#if CANARD_ALLOCATE_SEM + canard_allocate_sem_give(allocator); +#endif return result; } CANARD_INTERNAL void freeBlock(CanardPoolAllocator* allocator, void* p) { +#if CANARD_ALLOCATE_SEM + canard_allocate_sem_take(allocator); +#endif CanardPoolAllocatorBlock* block = (CanardPoolAllocatorBlock*) p; block->next = allocator->free_list; @@ -1870,4 +1881,7 @@ CANARD_INTERNAL void freeBlock(CanardPoolAllocator* allocator, void* p) CANARD_ASSERT(allocator->statistics.current_usage_blocks > 0); allocator->statistics.current_usage_blocks--; +#if CANARD_ALLOCATE_SEM + canard_allocate_sem_give(allocator); +#endif } diff --git a/canard.h b/canard.h index 676ecca..fa59694 100644 --- a/canard.h +++ b/canard.h @@ -90,6 +90,9 @@ extern "C" { # endif #endif +#ifndef CANARD_ALLOCATE_SEM +#define CANARD_ALLOCATE_SEM 0 +#endif /// Error code definitions; inverse of these values may be returned from API calls. #define CANARD_OK 0 // Value 1 is omitted intentionally, since -1 is often used in 3rd party code @@ -335,6 +338,9 @@ typedef struct CanardBufferBlock */ typedef struct { + // user should initialize semaphore after the canardInit + // or at first call of canard_allocate_sem_take + void *semaphore; CanardPoolAllocatorBlock* free_list; CanardPoolAllocatorStatistics statistics; void *arena; @@ -717,6 +723,12 @@ CANARD_STATIC_ASSERT(((uint32_t)CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE) < 32, "Please define CANARD_64_BIT=1 for 64 bit builds"); #endif +#if CANARD_ALLOCATE_SEM +// user implemented functions for taking and freeing semaphores +void canard_allocate_sem_take(CanardPoolAllocator *allocator); +void canard_allocate_sem_give(CanardPoolAllocator *allocator); +#endif + #ifdef __cplusplus } #endif