@@ -153,28 +153,24 @@ static void send(State* const state,
153
153
const CanardMicrosecond tx_deadline_usec ,
154
154
const CanardTransferMetadata * const metadata ,
155
155
const size_t payload_size ,
156
- const void * const payload )
156
+ const void * const payload_data )
157
157
{
158
158
for (uint8_t ifidx = 0 ; ifidx < CAN_REDUNDANCY_FACTOR ; ifidx ++ )
159
159
{
160
- (void ) canardTxPush (& state -> canard_tx_queues [ifidx ],
161
- & state -> canard ,
162
- tx_deadline_usec ,
163
- metadata ,
164
- payload_size ,
165
- payload );
160
+ const struct CanardPayload payload = {.size = payload_size , .data = payload_data };
161
+ (void ) canardTxPush (& state -> canard_tx_queues [ifidx ], & state -> canard , tx_deadline_usec , metadata , payload );
166
162
}
167
163
}
168
164
169
165
static void sendResponse (State * const state ,
170
166
const CanardMicrosecond tx_deadline_usec ,
171
167
const CanardTransferMetadata * const request_metadata ,
172
168
const size_t payload_size ,
173
- const void * const payload )
169
+ const void * const payload_data )
174
170
{
175
171
CanardTransferMetadata meta = * request_metadata ;
176
172
meta .transfer_kind = CanardTransferKindResponse ;
177
- send (state , tx_deadline_usec , & meta , payload_size , payload );
173
+ send (state , tx_deadline_usec , & meta , payload_size , payload_data );
178
174
}
179
175
180
176
/// Invoked at the rate of the fastest loop.
@@ -524,11 +520,11 @@ static void processReceivedTransfer(State* const state, const CanardRxTransfer*
524
520
{
525
521
if (transfer -> metadata .transfer_kind == CanardTransferKindMessage )
526
522
{
527
- size_t size = transfer -> payload_size ;
523
+ size_t size = transfer -> payload . size ;
528
524
if (transfer -> metadata .port_id == uavcan_pnp_NodeIDAllocationData_2_0_FIXED_PORT_ID_ )
529
525
{
530
526
uavcan_pnp_NodeIDAllocationData_2_0 msg = {0 };
531
- if (uavcan_pnp_NodeIDAllocationData_2_0_deserialize_ (& msg , transfer -> payload , & size ) >= 0 )
527
+ if (uavcan_pnp_NodeIDAllocationData_2_0_deserialize_ (& msg , transfer -> payload . data , & size ) >= 0 )
532
528
{
533
529
processMessagePlugAndPlayNodeIDAllocation (state , & msg );
534
530
}
@@ -563,8 +559,8 @@ static void processReceivedTransfer(State* const state, const CanardRxTransfer*
563
559
else if (transfer -> metadata .port_id == uavcan_register_Access_1_0_FIXED_PORT_ID_ )
564
560
{
565
561
uavcan_register_Access_Request_1_0 req = {0 };
566
- size_t size = transfer -> payload_size ;
567
- if (uavcan_register_Access_Request_1_0_deserialize_ (& req , transfer -> payload , & size ) >= 0 )
562
+ size_t size = transfer -> payload . size ;
563
+ if (uavcan_register_Access_Request_1_0_deserialize_ (& req , transfer -> payload . data , & size ) >= 0 )
568
564
{
569
565
const uavcan_register_Access_Response_1_0 resp = processRequestRegisterAccess (& req );
570
566
uint8_t serialized [uavcan_register_Access_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ ];
@@ -582,8 +578,8 @@ static void processReceivedTransfer(State* const state, const CanardRxTransfer*
582
578
else if (transfer -> metadata .port_id == uavcan_register_List_1_0_FIXED_PORT_ID_ )
583
579
{
584
580
uavcan_register_List_Request_1_0 req = {0 };
585
- size_t size = transfer -> payload_size ;
586
- if (uavcan_register_List_Request_1_0_deserialize_ (& req , transfer -> payload , & size ) >= 0 )
581
+ size_t size = transfer -> payload . size ;
582
+ if (uavcan_register_List_Request_1_0_deserialize_ (& req , transfer -> payload . data , & size ) >= 0 )
587
583
{
588
584
const uavcan_register_List_Response_1_0 resp = {.name = registerGetNameByIndex (req .index )};
589
585
uint8_t serialized [uavcan_register_List_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ ];
@@ -601,8 +597,8 @@ static void processReceivedTransfer(State* const state, const CanardRxTransfer*
601
597
else if (transfer -> metadata .port_id == uavcan_node_ExecuteCommand_1_1_FIXED_PORT_ID_ )
602
598
{
603
599
uavcan_node_ExecuteCommand_Request_1_1 req = {0 };
604
- size_t size = transfer -> payload_size ;
605
- if (uavcan_node_ExecuteCommand_Request_1_1_deserialize_ (& req , transfer -> payload , & size ) >= 0 )
600
+ size_t size = transfer -> payload . size ;
601
+ if (uavcan_node_ExecuteCommand_Request_1_1_deserialize_ (& req , transfer -> payload . data , & size ) >= 0 )
606
602
{
607
603
const uavcan_node_ExecuteCommand_Response_1_1 resp = processRequestExecuteCommand (& req );
608
604
uint8_t serialized [uavcan_node_ExecuteCommand_Response_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ ];
@@ -628,16 +624,17 @@ static void processReceivedTransfer(State* const state, const CanardRxTransfer*
628
624
}
629
625
}
630
626
631
- static void * canardAllocate (CanardInstance * const ins , const size_t amount )
627
+ static void * canardAllocate (void * const user_reference , const size_t amount )
632
628
{
633
- O1HeapInstance * const heap = ((State * ) ins -> user_reference )-> heap ;
629
+ O1HeapInstance * const heap = ((State * ) user_reference )-> heap ;
634
630
assert (o1heapDoInvariantsHold (heap ));
635
631
return o1heapAllocate (heap , amount );
636
632
}
637
633
638
- static void canardFree ( CanardInstance * const ins , void * const pointer )
634
+ static void canardDeallocate ( void * const user_reference , const size_t amount , void * const pointer )
639
635
{
640
- O1HeapInstance * const heap = ((State * ) ins -> user_reference )-> heap ;
636
+ (void ) amount ;
637
+ O1HeapInstance * const heap = ((State * ) user_reference )-> heap ;
641
638
o1heapFree (heap , pointer );
642
639
}
643
640
@@ -659,9 +656,14 @@ int main(const int argc, char* const argv[])
659
656
_Alignas(O1HEAP_ALIGNMENT ) static uint8_t heap_arena [1024 * 16 ] = {0 };
660
657
state .heap = o1heapInit (heap_arena , sizeof (heap_arena ));
661
658
assert (NULL != state .heap );
659
+ struct CanardMemoryResource canard_memory = {
660
+ .user_reference = & state ,
661
+ .deallocate = canardDeallocate ,
662
+ .allocate = canardAllocate ,
663
+ };
662
664
663
665
// The libcanard instance requires the allocator for managing protocol states.
664
- state .canard = canardInit (& canardAllocate , & canardFree );
666
+ state .canard = canardInit (canard_memory );
665
667
state .canard .user_reference = & state ; // Make the state reachable from the canard instance.
666
668
667
669
// Restore the node-ID from the corresponding standard register. Default to anonymous.
@@ -712,7 +714,8 @@ int main(const int argc, char* const argv[])
712
714
{
713
715
return - sock [ifidx ];
714
716
}
715
- state .canard_tx_queues [ifidx ] = canardTxInit (CAN_TX_QUEUE_CAPACITY , val .natural16 .value .elements [0 ]);
717
+ state .canard_tx_queues [ifidx ] =
718
+ canardTxInit (CAN_TX_QUEUE_CAPACITY , val .natural16 .value .elements [0 ], canard_memory );
716
719
}
717
720
718
721
// Load the port-IDs from the registers. You can implement hot-reloading at runtime if desired.
@@ -848,7 +851,8 @@ int main(const int argc, char* const argv[])
848
851
return - result ; // SocketCAN interface failure (link down?)
849
852
}
850
853
}
851
- state .canard .memory_free (& state .canard , canardTxPop (que , tqi ));
854
+ CanardTxQueueItem * const mut_tqi = canardTxPop (que , tqi );
855
+ que -> memory .deallocate (que -> memory .user_reference , mut_tqi -> allocated_size , mut_tqi );
852
856
tqi = canardTxPeek (que );
853
857
}
854
858
}
@@ -878,7 +882,9 @@ int main(const int argc, char* const argv[])
878
882
if (canard_result > 0 )
879
883
{
880
884
processReceivedTransfer (& state , & transfer );
881
- state .canard .memory_free (& state .canard , (void * ) transfer .payload );
885
+ state .canard .memory .deallocate (state .canard .memory .user_reference ,
886
+ transfer .payload .allocated_size ,
887
+ transfer .payload .data );
882
888
}
883
889
else if ((canard_result == 0 ) || (canard_result == - CANARD_ERROR_OUT_OF_MEMORY ))
884
890
{
0 commit comments