mirror of https://github.com/ArduPilot/ardupilot
AP_DroneCAN: add support for semaphore around allocate/free blocks in libcanard
This commit is contained in:
parent
8ac9480e3d
commit
5a967fd597
|
@ -8,6 +8,7 @@
|
|||
#include <dronecan_msgs.h>
|
||||
extern const AP_HAL::HAL& hal;
|
||||
#define LOG_TAG "DroneCANIface"
|
||||
#include <canard.h>
|
||||
|
||||
#define DEBUG_PKTS 0
|
||||
|
||||
|
@ -26,6 +27,27 @@ uint8_t test_node_mem_area[1024];
|
|||
HAL_Semaphore test_iface_sem;
|
||||
#endif
|
||||
|
||||
void canard_allocate_sem_take(CanardPoolAllocator *allocator) {
|
||||
if (allocator->semaphore == nullptr) {
|
||||
allocator->semaphore = new HAL_Semaphore;
|
||||
if (allocator->semaphore == nullptr) {
|
||||
// out of memory
|
||||
CANARD_ASSERT(0);
|
||||
return;
|
||||
}
|
||||
}
|
||||
((HAL_Semaphore*)allocator->semaphore)->take_blocking();
|
||||
}
|
||||
|
||||
void canard_allocate_sem_give(CanardPoolAllocator *allocator) {
|
||||
if (allocator->semaphore == nullptr) {
|
||||
// it should have been allocated by canard_allocate_sem_take
|
||||
CANARD_ASSERT(0);
|
||||
return;
|
||||
}
|
||||
((HAL_Semaphore*)allocator->semaphore)->give();
|
||||
}
|
||||
|
||||
CanardInterface::CanardInterface(uint8_t iface_index) :
|
||||
Interface(iface_index) {
|
||||
#if AP_TEST_DRONECAN_DRIVERS
|
||||
|
|
Loading…
Reference in New Issue