Skip to content

Commit

Permalink
add support for semaphores around allocate and freeing blocks of memory
Browse files Browse the repository at this point in the history
  • Loading branch information
bugobliterator authored and tridge committed Jun 7, 2023
1 parent b0ff748 commit dbae5c2
Show file tree
Hide file tree
Showing 2 changed files with 27 additions and 1 deletion.
16 changes: 15 additions & 1 deletion canard.c
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
Expand All @@ -1857,17 +1863,25 @@ 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;
allocator->free_list = block;

CANARD_ASSERT(allocator->statistics.current_usage_blocks > 0);
allocator->statistics.current_usage_blocks--;
#if CANARD_ALLOCATE_SEM
canard_allocate_sem_give(allocator);
#endif
}
12 changes: 12 additions & 0 deletions canard.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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
Expand Down

0 comments on commit dbae5c2

Please sign in to comment.