diff --git a/README.md b/README.md index 1d55e9a..576b14a 100644 --- a/README.md +++ b/README.md @@ -57,9 +57,6 @@ reused in the target application to speed up the design of the media IO layer (d ## Example -## TODO: Update to show how to use the new sized de-allocations, and how not to confuse payload_size and allocated_size. -☝ todo will be addressed as soon as the new API is stable (tx, rx, and "zero copy" aspects). - The example augments the documentation but does not replace it. The library requires a constant-complexity deterministic dynamic memory allocator. @@ -68,16 +65,16 @@ so let's suppose that we're using [O1Heap](https://github.com/pavel-kirienko/o1h We are going to need basic wrappers: ```c -static void* memAllocate(CanardInstance* const canard, const size_t amount) +static void* memAllocate(void* const user_reference, const size_t size) { - (void) canard; - return o1heapAllocate(my_allocator, amount); + (void) user_reference; + return o1heapAllocate(my_allocator, size); } -static void memFree(CanardInstance* const canard, void* const pointer, const size_t amount) +static void memFree(void* const user_reference, const size_t size, void* const pointer) { - (void) canard; - (void) amount; + (void) user_reference; + (void) size; o1heapFree(my_allocator, pointer); } ``` @@ -85,22 +82,26 @@ static void memFree(CanardInstance* const canard, void* const pointer, const siz Init a library instance: ```c -CanardInstance canard = canardInit(&memAllocate, &memFree); +const struct CanardMemoryResource memory{nullptr, &memAllocate, &memFree}; +struct CanardInstance canard = canardInit(memory); canard.node_id = 42; // Defaults to anonymous; can be set up later at any point. ``` In order to be able to send transfers over the network, we will need one transmission queue per redundant CAN interface: ```c -CanardTxQueue queue = canardTxInit(100, // Limit the size of the queue at 100 frames. - CANARD_MTU_CAN_FD); // Set MTU = 64 bytes. There is also CANARD_MTU_CAN_CLASSIC. +const struct CanardMemoryResource tx_memory{nullptr, memAllocate, memFree}; +struct CanardTxQueue queue = canardTxInit( + 100, // Limit the size of the queue at 100 frames. + CANARD_MTU_CAN_FD, // Set MTU = 64 bytes. There is also CANARD_MTU_CAN_CLASSIC. + tx_memory); ``` Publish a message (message serialization not shown): ```c static uint8_t my_message_transfer_id; // Must be static or heap-allocated to retain state between calls. -const CanardTransferMetadata transfer_metadata = { +const struct CanardTransferMetadata transfer_metadata = { .priority = CanardPriorityNominal, .transfer_kind = CanardTransferKindMessage, .port_id = 1234, // This is the subject-ID. @@ -131,7 +132,7 @@ Normally, the following fragment should be invoked periodically to unload the CA prioritized transmission queue (or several, if redundant network interfaces are used) into the CAN driver: ```c -for (const CanardTxQueueItem* ti = NULL; (ti = canardTxPeek(&queue)) != NULL;) // Peek at the top of the queue. +for (struct CanardTxQueueItem* ti = NULL; (ti = canardTxPeek(&queue)) != NULL;) // Peek at the top of the queue. { if ((0U == ti->tx_deadline_usec) || (ti->tx_deadline_usec > getCurrentMicroseconds())) // Check the deadline. { @@ -141,7 +142,7 @@ for (const CanardTxQueueItem* ti = NULL; (ti = canardTxPeek(&queue)) != NULL;) } } // After the frame is transmitted or if it has timed out while waiting, pop it from the queue and deallocate: - canard.memory_free(&canard, canardTxPop(&queue, ti)); + canardTxFree(&queue, &canard, canardTxPop(&queue, ti)); } ``` @@ -150,7 +151,7 @@ from any of the redundant interfaces. But first, we need to subscribe: ```c -CanardRxSubscription heartbeat_subscription; +struct CanardRxSubscription heartbeat_subscription; (void) canardRxSubscribe(&canard, // Subscribe to messages uavcan.node.Heartbeat. CanardTransferKindMessage, 7509, // The fixed Subject-ID of the Heartbeat message type (see DSDL definition). @@ -158,7 +159,7 @@ CanardRxSubscription heartbeat_subscription; CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC, &heartbeat_subscription); -CanardRxSubscription my_service_subscription; +struct CanardRxSubscription my_service_subscription; (void) canardRxSubscribe(&canard, // Subscribe to an arbitrary service response. CanardTransferKindResponse, // Specify that we want service responses, not requests. 123, // The Service-ID whose responses we will receive. @@ -183,7 +184,7 @@ Normally, however, an embedded application would subscribe once and roll with it Okay, this is how we receive transfers: ```c -CanardRxTransfer transfer; +struct CanardRxTransfer transfer; const int8_t result = canardRxAccept(&canard, rx_timestamp_usec, // When the frame was received, in microseconds. &received_frame, // The CAN frame received from the bus. @@ -216,15 +217,15 @@ the number of irrelevant transfers processed in software. ```c // Generate an acceptance filter to receive only uavcan.node.Heartbeat.1.0 messages (fixed port-ID 7509): -CanardFilter heartbeat_config = canardMakeFilterForSubject(7509); +struct CanardFilter heartbeat_config = canardMakeFilterForSubject(7509); // And to receive only uavcan.register.Access.1.0 service transfers (fixed port-ID 384): -CanardFilter register_access_config = canardMakeFilterForService(384, ins.node_id); +struct CanardFilter register_access_config = canardMakeFilterForService(384, ins.node_id); // You can also combine the two filter configurations into one (may also accept irrelevant messages). // This allows consolidating a large set of configurations to fit the number of hardware filters. // For more information on the optimal subset of configurations to consolidate to minimize wasted CPU, // see the Cyphal specification. -CanardFilter combined_config = +struct CanardFilter combined_config = canardConsolidateFilters(&heartbeat_config, ®ister_access_config); configureHardwareFilters(combined_config.extended_can_id, combined_config.extended_mask); ``` @@ -234,6 +235,10 @@ If you find the examples to be unclear or incorrect, please, open a ticket. ## Revisions +### v4.0 + +#### TODO: Highlight the most important changes. Mention migration guide doc. + ### v3.2 - Added new `canardRxGetSubscription`. diff --git a/libcanard/_canard_cavl.h b/libcanard/_canard_cavl.h index 79f89d9..95d5a06 100644 --- a/libcanard/_canard_cavl.h +++ b/libcanard/_canard_cavl.h @@ -43,7 +43,7 @@ extern "C" { // ---------------------------------------- PUBLIC API SECTION ---------------------------------------- /// Modified for use with Libcanard: expose the Cavl structure via public API as CanardTreeNode. -typedef CanardTreeNode Cavl; +typedef struct CanardTreeNode Cavl; /// Returns POSITIVE if the search target is GREATER than the provided node, negative if smaller, zero on match (found). /// Values other than {-1, 0, +1} are not recommended to avoid overflow during the narrowing conversion of the result. diff --git a/libcanard/canard.c b/libcanard/canard.c index f267805..95d8280 100644 --- a/libcanard/canard.c +++ b/libcanard/canard.c @@ -71,9 +71,9 @@ #define INITIAL_TOGGLE_STATE true /// Used for inserting new items into AVL trees. -CANARD_PRIVATE CanardTreeNode* avlTrivialFactory(void* const user_reference) +CANARD_PRIVATE struct CanardTreeNode* avlTrivialFactory(void* const user_reference) { - return (CanardTreeNode*) user_reference; + return (struct CanardTreeNode*) user_reference; } // --------------------------------------------- TRANSFER CRC --------------------------------------------- @@ -150,9 +150,9 @@ CANARD_PRIVATE TransferCRC crcAdd(const TransferCRC crc, const struct CanardPayl /// Chain of TX frames prepared for insertion into a TX queue. typedef struct { - CanardTxQueueItem* head; - CanardTxQueueItem* tail; - size_t size; + struct CanardTxQueueItem* head; + struct CanardTxQueueItem* tail; + size_t size; } TxChain; CANARD_PRIVATE uint32_t txMakeMessageSessionSpecifier(const CanardPortID subject_id, const CanardNodeID src_node_id) @@ -196,10 +196,10 @@ CANARD_PRIVATE size_t adjustPresentationLayerMTU(const size_t mtu_bytes) return mtu - 1U; } -CANARD_PRIVATE int32_t txMakeCANID(const CanardTransferMetadata* const tr, - const struct CanardPayload payload, - const CanardNodeID local_node_id, - const size_t presentation_layer_mtu) +CANARD_PRIVATE int32_t txMakeCANID(const struct CanardTransferMetadata* const tr, + const struct CanardPayload payload, + const CanardNodeID local_node_id, + const size_t presentation_layer_mtu) { CANARD_ASSERT(tr != NULL); CANARD_ASSERT(presentation_layer_mtu > 0); @@ -284,11 +284,11 @@ CANARD_PRIVATE size_t txRoundFramePayloadSizeUp(const size_t x) } /// The item is only allocated and initialized, but NOT included into the queue! The caller needs to do that. -CANARD_PRIVATE CanardTxQueueItem* txAllocateQueueItem(CanardTxQueue* const que, - const CanardInstance* const ins, - const uint32_t id, - const CanardMicrosecond deadline_usec, - const size_t payload_size) +CANARD_PRIVATE struct CanardTxQueueItem* txAllocateQueueItem(struct CanardTxQueue* const que, + const struct CanardInstance* const ins, + const uint32_t id, + const CanardMicrosecond deadline_usec, + const size_t payload_size) { CANARD_ASSERT(que != NULL); CANARD_ASSERT(payload_size > 0U); @@ -296,7 +296,7 @@ CANARD_PRIVATE CanardTxQueueItem* txAllocateQueueItem(CanardTxQueue* const // TX queue items are allocated in the memory pool of the instance. // These items are just TX pipeline support structures, they are not directly transfer payload data. // In contrast, see below allocation of the payload buffer from a different memory pool. - CanardTxQueueItem* out = ins->memory.allocate(ins->memory.user_reference, sizeof(CanardTxQueueItem)); + struct CanardTxQueueItem* out = ins->memory.allocate(ins->memory.user_reference, sizeof(struct CanardTxQueueItem)); if (out != NULL) { out->base.up = NULL; @@ -319,7 +319,7 @@ CANARD_PRIVATE CanardTxQueueItem* txAllocateQueueItem(CanardTxQueue* const } else { - ins->memory.deallocate(ins->memory.user_reference, sizeof(CanardTxQueueItem), out); + ins->memory.deallocate(ins->memory.user_reference, sizeof(struct CanardTxQueueItem), out); out = NULL; } } @@ -330,21 +330,21 @@ CANARD_PRIVATE CanardTxQueueItem* txAllocateQueueItem(CanardTxQueue* const /// This ensures that CAN frames with the same CAN ID are transmitted in the FIFO order. /// Frames that should be transmitted earlier compare smaller (i.e., put on the left side of the tree). CANARD_PRIVATE int8_t txAVLPredicate(void* const user_reference, // NOSONAR Cavl API requires pointer to non-const. - const CanardTreeNode* const node) + const struct CanardTreeNode* const node) { - const CanardTxQueueItem* const target = (const CanardTxQueueItem*) user_reference; - const CanardTxQueueItem* const other = (const CanardTxQueueItem*) (const void*) node; + const struct CanardTxQueueItem* const target = (const struct CanardTxQueueItem*) user_reference; + const struct CanardTxQueueItem* const other = (const struct CanardTxQueueItem*) (const void*) node; CANARD_ASSERT((target != NULL) && (other != NULL)); return (target->frame.extended_can_id >= other->frame.extended_can_id) ? +1 : -1; } /// Returns the number of frames enqueued or error (i.e., =1 or <0). -CANARD_PRIVATE int32_t txPushSingleFrame(CanardTxQueue* const que, - const CanardInstance* const ins, - const CanardMicrosecond deadline_usec, - const uint32_t can_id, - const CanardTransferID transfer_id, - const struct CanardPayload payload) +CANARD_PRIVATE int32_t txPushSingleFrame(struct CanardTxQueue* const que, + const struct CanardInstance* const ins, + const CanardMicrosecond deadline_usec, + const uint32_t can_id, + const CanardTransferID transfer_id, + const struct CanardPayload payload) { CANARD_ASSERT((que != NULL) && (ins != NULL)); CANARD_ASSERT((payload.data != NULL) || (payload.size == 0)); @@ -352,8 +352,8 @@ CANARD_PRIVATE int32_t txPushSingleFrame(CanardTxQueue* const que, CANARD_ASSERT(frame_payload_size > payload.size); const size_t padding_size = frame_payload_size - payload.size - 1U; CANARD_ASSERT((padding_size + payload.size + 1U) == frame_payload_size); - int32_t out = 0; - CanardTxQueueItem* const tqi = + int32_t out = 0; + struct CanardTxQueueItem* const tqi = (que->size < que->capacity) ? txAllocateQueueItem(que, ins, can_id, deadline_usec, frame_payload_size) : NULL; if (tqi != NULL) { @@ -370,7 +370,8 @@ CANARD_PRIVATE int32_t txPushSingleFrame(CanardTxQueue* const que, (void) memset(frame_bytes + payload.size, PADDING_BYTE_VALUE, padding_size); // NOLINT *(frame_bytes + (frame_payload_size - 1U)) = txMakeTailByte(true, true, true, transfer_id); // Insert the newly created TX item into the queue. - const CanardTreeNode* const res = cavlSearch(&que->root, &tqi->base, &txAVLPredicate, &avlTrivialFactory); + const struct CanardTreeNode* const res = + cavlSearch(&que->root, &tqi->base, &txAVLPredicate, &avlTrivialFactory); (void) res; CANARD_ASSERT(res == &tqi->base); que->size++; @@ -386,13 +387,13 @@ CANARD_PRIVATE int32_t txPushSingleFrame(CanardTxQueue* const que, } /// Produces a chain of Tx queue items for later insertion into the Tx queue. The tail is NULL if OOM. -CANARD_PRIVATE TxChain txGenerateMultiFrameChain(CanardTxQueue* const que, - const CanardInstance* const ins, - const size_t presentation_layer_mtu, - const CanardMicrosecond deadline_usec, - const uint32_t can_id, - const CanardTransferID transfer_id, - const struct CanardPayload payload) +CANARD_PRIVATE TxChain txGenerateMultiFrameChain(struct CanardTxQueue* const que, + const struct CanardInstance* const ins, + const size_t presentation_layer_mtu, + const CanardMicrosecond deadline_usec, + const uint32_t can_id, + const CanardTransferID transfer_id, + const struct CanardPayload payload) { CANARD_ASSERT(que != NULL); CANARD_ASSERT(presentation_layer_mtu > 0U); @@ -412,7 +413,7 @@ CANARD_PRIVATE TxChain txGenerateMultiFrameChain(CanardTxQueue* const que ((payload_size_with_crc - offset) < presentation_layer_mtu) ? txRoundFramePayloadSizeUp((payload_size_with_crc - offset) + 1U) // Padding in the last frame only. : (presentation_layer_mtu + 1U); - CanardTxQueueItem* const tqi = + struct CanardTxQueueItem* const tqi = txAllocateQueueItem(que, ins, can_id, deadline_usec, frame_payload_size_with_tail); if (NULL == out.head) { @@ -488,13 +489,13 @@ CANARD_PRIVATE TxChain txGenerateMultiFrameChain(CanardTxQueue* const que } /// Returns the number of frames enqueued or error. -CANARD_PRIVATE int32_t txPushMultiFrame(CanardTxQueue* const que, - const CanardInstance* const ins, - const size_t presentation_layer_mtu, - const CanardMicrosecond deadline_usec, - const uint32_t can_id, - const CanardTransferID transfer_id, - const struct CanardPayload payload) +CANARD_PRIVATE int32_t txPushMultiFrame(struct CanardTxQueue* const que, + const struct CanardInstance* const ins, + const size_t presentation_layer_mtu, + const CanardMicrosecond deadline_usec, + const uint32_t can_id, + const CanardTransferID transfer_id, + const struct CanardPayload payload) { CANARD_ASSERT(que != NULL); CANARD_ASSERT(presentation_layer_mtu > 0U); @@ -510,10 +511,10 @@ CANARD_PRIVATE int32_t txPushMultiFrame(CanardTxQueue* const que, txGenerateMultiFrameChain(que, ins, presentation_layer_mtu, deadline_usec, can_id, transfer_id, payload); if (sq.tail != NULL) { - CanardTxQueueItem* next = sq.head; + struct CanardTxQueueItem* next = sq.head; do { - const CanardTreeNode* const res = + const struct CanardTreeNode* const res = cavlSearch(&que->root, &next->base, &txAVLPredicate, &avlTrivialFactory); (void) res; CANARD_ASSERT(res == &next->base); @@ -528,11 +529,11 @@ CANARD_PRIVATE int32_t txPushMultiFrame(CanardTxQueue* const que, } else { - out = -CANARD_ERROR_OUT_OF_MEMORY; - CanardTxQueueItem* head = sq.head; + out = -CANARD_ERROR_OUT_OF_MEMORY; + struct CanardTxQueueItem* head = sq.head; while (head != NULL) { - CanardTxQueueItem* const next = head->next_in_transfer; + struct CanardTxQueueItem* const next = head->next_in_transfer; canardTxFree(que, ins, head); head = next; } @@ -569,23 +570,23 @@ typedef struct CanardInternalRxSession /// High-level transport frame model. typedef struct { - CanardMicrosecond timestamp_usec; - CanardPriority priority; - CanardTransferKind transfer_kind; - CanardPortID port_id; - CanardNodeID source_node_id; - CanardNodeID destination_node_id; - CanardTransferID transfer_id; - bool start_of_transfer; - bool end_of_transfer; - bool toggle; - struct CanardPayload payload; + CanardMicrosecond timestamp_usec; + enum CanardPriority priority; + enum CanardTransferKind transfer_kind; + CanardPortID port_id; + CanardNodeID source_node_id; + CanardNodeID destination_node_id; + CanardTransferID transfer_id; + bool start_of_transfer; + bool end_of_transfer; + bool toggle; + struct CanardPayload payload; } RxFrameModel; /// Returns truth if the frame is valid and parsed successfully. False if the frame is not a valid Cyphal/CAN frame. -CANARD_PRIVATE bool rxTryParseFrame(const CanardMicrosecond timestamp_usec, - const CanardFrame* const frame, - RxFrameModel* const out) +CANARD_PRIVATE bool rxTryParseFrame(const CanardMicrosecond timestamp_usec, + const struct CanardFrame* const frame, + RxFrameModel* const out) { CANARD_ASSERT(frame != NULL); CANARD_ASSERT(frame->extended_can_id <= CAN_EXT_ID_MASK); @@ -598,7 +599,7 @@ CANARD_PRIVATE bool rxTryParseFrame(const CanardMicrosecond timestamp_usec, // CAN ID parsing. const uint32_t can_id = frame->extended_can_id; - out->priority = (CanardPriority) ((can_id >> OFFSET_PRIORITY) & CANARD_PRIORITY_MAX); + out->priority = (enum CanardPriority)((can_id >> OFFSET_PRIORITY) & CANARD_PRIORITY_MAX); out->source_node_id = (CanardNodeID) (can_id & CANARD_NODE_ID_MAX); if (0 == (can_id & FLAG_SERVICE_NOT_MESSAGE)) { @@ -649,8 +650,8 @@ CANARD_PRIVATE bool rxTryParseFrame(const CanardMicrosecond timestamp_usec, return valid; } -CANARD_PRIVATE void rxInitTransferMetadataFromFrame(const RxFrameModel* const frame, - CanardTransferMetadata* const out_transfer) +CANARD_PRIVATE void rxInitTransferMetadataFromFrame(const RxFrameModel* const frame, + struct CanardTransferMetadata* const out_transfer) { CANARD_ASSERT(frame != NULL); CANARD_ASSERT(frame->payload.data != NULL); @@ -676,7 +677,7 @@ CANARD_PRIVATE uint8_t rxComputeTransferIDDifference(const uint8_t a, const uint return (uint8_t) diff; } -CANARD_PRIVATE int8_t rxSessionWritePayload(CanardInstance* const ins, +CANARD_PRIVATE int8_t rxSessionWritePayload(struct CanardInstance* const ins, CanardInternalRxSession* const rxs, const size_t extent, const struct CanardPayload payload) @@ -731,7 +732,7 @@ CANARD_PRIVATE int8_t rxSessionWritePayload(CanardInstance* const ins, return out; } -CANARD_PRIVATE void rxSessionRestart(CanardInstance* const ins, CanardInternalRxSession* const rxs) +CANARD_PRIVATE void rxSessionRestart(struct CanardInstance* const ins, CanardInternalRxSession* const rxs) { CANARD_ASSERT(ins != NULL); CANARD_ASSERT(rxs != NULL); @@ -747,11 +748,11 @@ CANARD_PRIVATE void rxSessionRestart(CanardInstance* const ins, CanardInternalRx rxs->toggle = INITIAL_TOGGLE_STATE; } -CANARD_PRIVATE int8_t rxSessionAcceptFrame(CanardInstance* const ins, +CANARD_PRIVATE int8_t rxSessionAcceptFrame(struct CanardInstance* const ins, CanardInternalRxSession* const rxs, const RxFrameModel* const frame, const size_t extent, - CanardRxTransfer* const out_transfer) + struct CanardRxTransfer* const out_transfer) { CANARD_ASSERT(ins != NULL); CANARD_ASSERT(rxs != NULL); @@ -877,13 +878,13 @@ CANARD_PRIVATE void rxSessionSynchronize(CanardInternalRxSession* const rxs, /// are given and the particular algorithms are left to be implementation-defined. Such abstract approach is much /// advantageous because it allows implementers to choose whatever solution works best for the specific application at /// hand, while the wire compatibility is still guaranteed by the high-level requirements given in the specification. -CANARD_PRIVATE int8_t rxSessionUpdate(CanardInstance* const ins, +CANARD_PRIVATE int8_t rxSessionUpdate(struct CanardInstance* const ins, CanardInternalRxSession* const rxs, const RxFrameModel* const frame, const uint8_t redundant_iface_index, const CanardMicrosecond transfer_id_timeout_usec, const size_t extent, - CanardRxTransfer* const out_transfer) + struct CanardRxTransfer* const out_transfer) { CANARD_ASSERT(ins != NULL); CANARD_ASSERT(rxs != NULL); @@ -915,11 +916,11 @@ CANARD_PRIVATE int8_t rxSessionUpdate(CanardInstance* const ins, return out; } -CANARD_PRIVATE int8_t rxAcceptFrame(CanardInstance* const ins, - CanardRxSubscription* const subscription, - const RxFrameModel* const frame, - const uint8_t redundant_iface_index, - CanardRxTransfer* const out_transfer) +CANARD_PRIVATE int8_t rxAcceptFrame(struct CanardInstance* const ins, + struct CanardRxSubscription* const subscription, + const RxFrameModel* const frame, + const uint8_t redundant_iface_index, + struct CanardRxTransfer* const out_transfer) { CANARD_ASSERT(ins != NULL); CANARD_ASSERT(subscription != NULL); @@ -1002,10 +1003,10 @@ CANARD_PRIVATE int8_t rxAcceptFrame(CanardInstance* const ins, CANARD_PRIVATE int8_t rxSubscriptionPredicateOnPortID(void* const user_reference, // NOSONAR Cavl API requires pointer to non-const. - const CanardTreeNode* const node) + const struct CanardTreeNode* const node) { const CanardPortID sought = *((const CanardPortID*) user_reference); - const CanardPortID other = ((const CanardRxSubscription*) (const void*) node)->port_id; + const CanardPortID other = ((const struct CanardRxSubscription*) (const void*) node)->port_id; static const int8_t NegPos[2] = {-1, +1}; // Clang-Tidy mistakenly identifies a narrowing cast to int8_t here, which is incorrect. return (sought == other) ? 0 : NegPos[sought > other]; // NOLINT no narrowing conversion is taking place here @@ -1013,9 +1014,9 @@ rxSubscriptionPredicateOnPortID(void* const user_reference, // NOSONAR Cavl API CANARD_PRIVATE int8_t rxSubscriptionPredicateOnStruct(void* const user_reference, // NOSONAR Cavl API requires pointer to non-const. - const CanardTreeNode* const node) + const struct CanardTreeNode* const node) { - return rxSubscriptionPredicateOnPortID(&((CanardRxSubscription*) user_reference)->port_id, node); + return rxSubscriptionPredicateOnPortID(&((struct CanardRxSubscription*) user_reference)->port_id, node); } // --------------------------------------------- PUBLIC API --------------------------------------------- @@ -1032,11 +1033,11 @@ const uint8_t CanardCANLengthToDLC[65] = { 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, // 49-64 }; -CanardInstance canardInit(const struct CanardMemoryResource memory) +struct CanardInstance canardInit(const struct CanardMemoryResource memory) { CANARD_ASSERT(memory.allocate != NULL); CANARD_ASSERT(memory.deallocate != NULL); - const CanardInstance out = { + const struct CanardInstance out = { .user_reference = NULL, .node_id = CANARD_NODE_ID_UNSET, .memory = memory, @@ -1045,11 +1046,13 @@ CanardInstance canardInit(const struct CanardMemoryResource memory) return out; } -CanardTxQueue canardTxInit(const size_t capacity, const size_t mtu_bytes, const struct CanardMemoryResource memory) +struct CanardTxQueue canardTxInit(const size_t capacity, + const size_t mtu_bytes, + const struct CanardMemoryResource memory) { CANARD_ASSERT(memory.allocate != NULL); CANARD_ASSERT(memory.deallocate != NULL); - CanardTxQueue out = { + struct CanardTxQueue out = { .capacity = capacity, .mtu_bytes = mtu_bytes, .size = 0, @@ -1060,11 +1063,11 @@ CanardTxQueue canardTxInit(const size_t capacity, const size_t mtu_bytes, const return out; } -int32_t canardTxPush(CanardTxQueue* const que, - const CanardInstance* const ins, - const CanardMicrosecond tx_deadline_usec, - const CanardTransferMetadata* const metadata, - const struct CanardPayload payload) +int32_t canardTxPush(struct CanardTxQueue* const que, + const struct CanardInstance* const ins, + const CanardMicrosecond tx_deadline_usec, + const struct CanardTransferMetadata* const metadata, + const struct CanardPayload payload) { int32_t out = -CANARD_ERROR_INVALID_ARGUMENT; if ((ins != NULL) && (que != NULL) && (metadata != NULL) && ((payload.data != NULL) || (0U == payload.size))) @@ -1104,27 +1107,22 @@ int32_t canardTxPush(CanardTxQueue* const que, return out; } -CanardTxQueueItem* canardTxPeek(const CanardTxQueue* const que) +struct CanardTxQueueItem* canardTxPeek(const struct CanardTxQueue* const que) { - CanardTxQueueItem* out = NULL; + struct CanardTxQueueItem* out = NULL; if (que != NULL) { // Paragraph 6.7.2.1.15 of the C standard says: // A pointer to a structure object, suitably converted, points to its initial member, and vice versa. - out = (CanardTxQueueItem*) (void*) cavlFindExtremum(que->root, false); + out = (struct CanardTxQueueItem*) (void*) cavlFindExtremum(que->root, false); } return out; } -CanardTxQueueItem* canardTxPop(CanardTxQueue* const que, const CanardTxQueueItem* const item) +struct CanardTxQueueItem* canardTxPop(struct CanardTxQueue* const que, struct CanardTxQueueItem* const item) { - CanardTxQueueItem* out = NULL; if ((que != NULL) && (item != NULL)) { - // Intentional violation of MISRA: casting away const qualifier. This is considered safe because the API - // contract dictates that the pointer shall point to a mutable entity in RAM previously allocated by the - // memory manager. It is difficult to avoid this cast in this context. - out = (CanardTxQueueItem*) item; // NOSONAR casting away const qualifier. // Paragraph 6.7.2.1.15 of the C standard says: // A pointer to a structure object, suitably converted, points to its initial member, and vice versa. // Note that the highest-priority frame is always a leaf node in the AVL tree, which means that it is very @@ -1132,10 +1130,12 @@ CanardTxQueueItem* canardTxPop(CanardTxQueue* const que, const CanardTxQueueItem cavlRemove(&que->root, &item->base); que->size--; } - return out; + return item; } -void canardTxFree(CanardTxQueue* const que, const CanardInstance* const ins, CanardTxQueueItem* item) +void canardTxFree(struct CanardTxQueue* const que, + const struct CanardInstance* const ins, + struct CanardTxQueueItem* item) { if (item != NULL) { @@ -1146,16 +1146,16 @@ void canardTxFree(CanardTxQueue* const que, const CanardInstance* const ins, Can item->frame.payload.data); } - ins->memory.deallocate(ins->memory.user_reference, sizeof(CanardTxQueueItem), item); + ins->memory.deallocate(ins->memory.user_reference, sizeof(struct CanardTxQueueItem), item); } } -int8_t canardRxAccept(CanardInstance* const ins, - const CanardMicrosecond timestamp_usec, - const CanardFrame* const frame, - const uint8_t redundant_iface_index, - CanardRxTransfer* const out_transfer, - CanardRxSubscription** const out_subscription) +int8_t canardRxAccept(struct CanardInstance* const ins, + const CanardMicrosecond timestamp_usec, + const struct CanardFrame* const frame, + const uint8_t redundant_iface_index, + struct CanardRxTransfer* const out_transfer, + struct CanardRxSubscription** const out_subscription) { int8_t out = -CANARD_ERROR_INVALID_ARGUMENT; if ((ins != NULL) && (out_transfer != NULL) && (frame != NULL) && (frame->extended_can_id <= CAN_EXT_ID_MASK) && @@ -1169,11 +1169,11 @@ int8_t canardRxAccept(CanardInstance* const ins, // This is the reason the function has a logarithmic time complexity of the number of subscriptions. // Note also that this one of the two variable-complexity operations in the RX pipeline; the other one // is memcpy(). Excepting these two cases, the entire RX pipeline contains neither loops nor recursion. - CanardRxSubscription* const sub = - (CanardRxSubscription*) (void*) cavlSearch(&ins->rx_subscriptions[(size_t) model.transfer_kind], - &model.port_id, - &rxSubscriptionPredicateOnPortID, - NULL); + struct CanardRxSubscription* const sub = (struct CanardRxSubscription*) (void*) + cavlSearch(&ins->rx_subscriptions[(size_t) model.transfer_kind], + &model.port_id, + &rxSubscriptionPredicateOnPortID, + NULL); if (out_subscription != NULL) { *out_subscription = sub; // Expose selected instance to the caller. @@ -1202,12 +1202,12 @@ int8_t canardRxAccept(CanardInstance* const ins, return out; } -int8_t canardRxSubscribe(CanardInstance* const ins, - const CanardTransferKind transfer_kind, - const CanardPortID port_id, - const size_t extent, - const CanardMicrosecond transfer_id_timeout_usec, - CanardRxSubscription* const out_subscription) +int8_t canardRxSubscribe(struct CanardInstance* const ins, + const enum CanardTransferKind transfer_kind, + const CanardPortID port_id, + const size_t extent, + const CanardMicrosecond transfer_id_timeout_usec, + struct CanardRxSubscription* const out_subscription) { int8_t out = -CANARD_ERROR_INVALID_ARGUMENT; const size_t tk = (size_t) transfer_kind; @@ -1229,10 +1229,10 @@ int8_t canardRxSubscribe(CanardInstance* const ins, // We could accept an extra argument that would instruct us to pre-allocate sessions here? out_subscription->sessions[i] = NULL; } - const CanardTreeNode* const res = cavlSearch(&ins->rx_subscriptions[tk], - out_subscription, - &rxSubscriptionPredicateOnStruct, - &avlTrivialFactory); + const struct CanardTreeNode* const res = cavlSearch(&ins->rx_subscriptions[tk], + out_subscription, + &rxSubscriptionPredicateOnStruct, + &avlTrivialFactory); (void) res; CANARD_ASSERT(res == &out_subscription->base); out = (out > 0) ? 0 : 1; @@ -1241,16 +1241,16 @@ int8_t canardRxSubscribe(CanardInstance* const ins, return out; } -int8_t canardRxUnsubscribe(CanardInstance* const ins, - const CanardTransferKind transfer_kind, - const CanardPortID port_id) +int8_t canardRxUnsubscribe(struct CanardInstance* const ins, + const enum CanardTransferKind transfer_kind, + const CanardPortID port_id) { int8_t out = -CANARD_ERROR_INVALID_ARGUMENT; const size_t tk = (size_t) transfer_kind; if ((ins != NULL) && (tk < CANARD_NUM_TRANSFER_KINDS)) { - CanardPortID port_id_mutable = port_id; - CanardRxSubscription* const sub = (CanardRxSubscription*) (void*) + CanardPortID port_id_mutable = port_id; + struct CanardRxSubscription* const sub = (struct CanardRxSubscription*) (void*) cavlSearch(&ins->rx_subscriptions[tk], &port_id_mutable, &rxSubscriptionPredicateOnPortID, NULL); if (sub != NULL) { @@ -1278,17 +1278,17 @@ int8_t canardRxUnsubscribe(CanardInstance* const ins, return out; } -int8_t canardRxGetSubscription(CanardInstance* const ins, - const CanardTransferKind transfer_kind, - const CanardPortID port_id, - CanardRxSubscription** const out_subscription) +int8_t canardRxGetSubscription(struct CanardInstance* const ins, + const enum CanardTransferKind transfer_kind, + const CanardPortID port_id, + struct CanardRxSubscription** const out_subscription) { int8_t out = -CANARD_ERROR_INVALID_ARGUMENT; const size_t tk = (size_t) transfer_kind; if ((ins != NULL) && (tk < CANARD_NUM_TRANSFER_KINDS)) { - CanardPortID port_id_mutable = port_id; - CanardRxSubscription* const sub = (CanardRxSubscription*) (void*) + CanardPortID port_id_mutable = port_id; + struct CanardRxSubscription* const sub = (struct CanardRxSubscription*) (void*) cavlSearch(&ins->rx_subscriptions[tk], &port_id_mutable, &rxSubscriptionPredicateOnPortID, NULL); if (sub != NULL) { @@ -1307,9 +1307,9 @@ int8_t canardRxGetSubscription(CanardInstance* const ins, return out; } -CanardFilter canardMakeFilterForSubject(const CanardPortID subject_id) +struct CanardFilter canardMakeFilterForSubject(const CanardPortID subject_id) { - CanardFilter out = {0}; + struct CanardFilter out = {0}; out.extended_can_id = ((uint32_t) subject_id) << OFFSET_SUBJECT_ID; out.extended_mask = FLAG_SERVICE_NOT_MESSAGE | FLAG_RESERVED_07 | (CANARD_SUBJECT_ID_MAX << OFFSET_SUBJECT_ID); @@ -1317,9 +1317,9 @@ CanardFilter canardMakeFilterForSubject(const CanardPortID subject_id) return out; } -CanardFilter canardMakeFilterForService(const CanardPortID service_id, const CanardNodeID local_node_id) +struct CanardFilter canardMakeFilterForService(const CanardPortID service_id, const CanardNodeID local_node_id) { - CanardFilter out = {0}; + struct CanardFilter out = {0}; out.extended_can_id = FLAG_SERVICE_NOT_MESSAGE | (((uint32_t) service_id) << OFFSET_SERVICE_ID) | (((uint32_t) local_node_id) << OFFSET_DST_NODE_ID); @@ -1329,9 +1329,9 @@ CanardFilter canardMakeFilterForService(const CanardPortID service_id, const Can return out; } -CanardFilter canardMakeFilterForServices(const CanardNodeID local_node_id) +struct CanardFilter canardMakeFilterForServices(const CanardNodeID local_node_id) { - CanardFilter out = {0}; + struct CanardFilter out = {0}; out.extended_can_id = FLAG_SERVICE_NOT_MESSAGE | (((uint32_t) local_node_id) << OFFSET_DST_NODE_ID); out.extended_mask = FLAG_SERVICE_NOT_MESSAGE | FLAG_RESERVED_23 | (CANARD_NODE_ID_MAX << OFFSET_DST_NODE_ID); @@ -1339,9 +1339,9 @@ CanardFilter canardMakeFilterForServices(const CanardNodeID local_node_id) return out; } -CanardFilter canardConsolidateFilters(const CanardFilter* a, const CanardFilter* b) +struct CanardFilter canardConsolidateFilters(const struct CanardFilter* a, const struct CanardFilter* b) { - CanardFilter out = {0}; + struct CanardFilter out = {0}; out.extended_mask = a->extended_mask & b->extended_mask & ~(a->extended_can_id ^ b->extended_can_id); out.extended_can_id = a->extended_can_id & out.extended_mask; diff --git a/libcanard/canard.h b/libcanard/canard.h index 4f075d4..443ccf2 100644 --- a/libcanard/canard.h +++ b/libcanard/canard.h @@ -132,16 +132,13 @@ extern "C" { #define CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC 2000000UL // Forward declarations. -typedef struct CanardInstance CanardInstance; -typedef struct CanardTreeNode CanardTreeNode; -typedef struct CanardTxQueueItem CanardTxQueueItem; -typedef uint64_t CanardMicrosecond; -typedef uint16_t CanardPortID; -typedef uint8_t CanardNodeID; -typedef uint8_t CanardTransferID; +typedef uint64_t CanardMicrosecond; +typedef uint16_t CanardPortID; +typedef uint8_t CanardNodeID; +typedef uint8_t CanardTransferID; /// Transfer priority level mnemonics per the recommendations given in the Cyphal Specification. -typedef enum +enum CanardPriority { CanardPriorityExceptional = 0, CanardPriorityImmediate = 1, @@ -151,24 +148,24 @@ typedef enum CanardPriorityLow = 5, CanardPrioritySlow = 6, CanardPriorityOptional = 7, -} CanardPriority; +}; /// Transfer kinds as defined by the Cyphal Specification. -typedef enum +enum CanardTransferKind { CanardTransferKindMessage = 0, ///< Multicast, from publisher to all subscribers. CanardTransferKindResponse = 1, ///< Point-to-point, from server to client. CanardTransferKindRequest = 2, ///< Point-to-point, from client to server. -} CanardTransferKind; +}; #define CANARD_NUM_TRANSFER_KINDS 3 /// The AVL tree node structure is exposed here to avoid pointer casting/arithmetics inside the library. /// The user code is not expected to interact with this type except if advanced introspection is required. struct CanardTreeNode { - CanardTreeNode* up; ///< Do not access this field. - CanardTreeNode* lr[2]; ///< Left and right children of this node may be accessed for tree traversal. - int8_t bf; ///< Do not access this field. + struct CanardTreeNode* up; ///< Do not access this field. + struct CanardTreeNode* lr[2]; ///< Left and right children of this node may be accessed for tree traversal. + int8_t bf; ///< Do not access this field. }; struct CanardPayload @@ -200,7 +197,7 @@ struct CanardMutablePayload /// CAN data frame with an extended 29-bit ID. RTR/Error frames are not used and therefore not modeled here. /// CAN frames with 11-bit ID are not used by Cyphal/CAN and so they are not supported by the library. -typedef struct +struct CanardFrame { /// 29-bit extended ID. The bits above 29-th shall be zero. uint32_t extended_can_id; @@ -213,7 +210,7 @@ typedef struct /// lifetimes are identical; when the frame is freed, the payload is invalidated. /// A more detailed overview of the dataflow and related resource management issues is provided in the API docs. struct CanardPayload payload; -} CanardFrame; +}; /// Similar to the `CanardFrame` structure, but with a mutable payload (including `allocated_size` of the payload). /// In use when payload memory ownership might be transferred. @@ -233,13 +230,13 @@ extern const uint8_t CanardCANLengthToDLC[65]; /// Per Specification, a transfer is represented on the wire as a non-empty set of transport frames (i.e., CAN frames). /// The library is responsible for serializing transfers into transport frames when transmitting, and reassembling /// transfers from an incoming stream of frames (possibly duplicated if redundant interfaces are used) during reception. -typedef struct +struct CanardTransferMetadata { /// Per the Specification, all frames belonging to a given transfer shall share the same priority level. /// If this is not the case, then this field contains the priority level of the last frame to arrive. - CanardPriority priority; + enum CanardPriority priority; - CanardTransferKind transfer_kind; + enum CanardTransferKind transfer_kind; /// Subject-ID for message publications; service-ID for service requests/responses. CanardPortID port_id; @@ -266,7 +263,7 @@ typedef struct /// A simple and robust way of managing transfer-ID counters is to keep a separate static variable per subject-ID /// and per (service-ID, server-node-ID) pair. CanardTransferID transfer_id; -} CanardTransferMetadata; +}; /// A pointer to the memory allocation function. The semantics are similar to malloc(): /// - The returned pointer shall point to an uninitialized block of memory that is at least `size` bytes large. @@ -316,7 +313,7 @@ struct CanardMemoryResource /// - the first for bookkeeping purposes (CanardTxQueueItem) /// - second for payload storage (the frame data) /// API functions that work with this type are named "canardTx*()", find them below. -typedef struct CanardTxQueue +struct CanardTxQueue { /// The maximum number of frames this queue is allowed to contain. An attempt to push more will fail with an /// out-of-memory error even if the memory is not exhausted. This value can be changed by the user at any moment. @@ -338,7 +335,7 @@ typedef struct CanardTxQueue size_t size; /// The root of the priority queue is NULL if the queue is empty. Do not modify this field! - CanardTreeNode* root; + struct CanardTreeNode* root; /// The memory resource used by this queue for allocating the payload data (CAN frames). /// There is exactly one allocation of payload buffer per enqueued item (not considering the item itself @@ -357,20 +354,20 @@ typedef struct CanardTxQueue /// This field can be arbitrarily mutated by the user. It is never accessed by the library. /// Its purpose is to simplify integration with OOP interfaces. void* user_reference; -} CanardTxQueue; +}; /// One frame stored in the transmission queue along with its metadata. struct CanardTxQueueItem { /// Internal use only; do not access this field. - CanardTreeNode base; + struct CanardTreeNode base; /// Points to the next frame in this transfer or NULL. This field is mostly intended for own needs of the library. /// Normally, the application would not use it because transfer frame ordering is orthogonal to global TX ordering. /// It can be useful though for pulling pending frames from the TX queue if at least one frame of their transfer /// failed to transmit; the idea is that if at least one frame is missing, the transfer will not be received by /// remote nodes anyway, so all its remaining frames can be dropped from the queue at once using canardTxPop(). - CanardTxQueueItem* next_in_transfer; + struct CanardTxQueueItem* next_in_transfer; /// This is the same value that is passed to canardTxPush(). /// Frames whose transmission deadline is in the past shall be dropped. @@ -389,9 +386,9 @@ struct CanardTxQueueItem /// /// The memory footprint of a subscription is large. On a 32-bit platform it slightly exceeds half a KiB. /// This is an intentional time-memory trade-off: use a large look-up table to ensure predictable temporal properties. -typedef struct CanardRxSubscription +struct CanardRxSubscription { - CanardTreeNode base; ///< Read-only DO NOT MODIFY THIS + struct CanardTreeNode base; ///< Read-only DO NOT MODIFY THIS CanardMicrosecond transfer_id_timeout_usec; size_t extent; ///< Read-only DO NOT MODIFY THIS @@ -412,12 +409,12 @@ typedef struct CanardRxSubscription /// system. Since this is a general-purpose library, we have to pick a middle ground so we use the more complex /// but more memory-efficient approach. struct CanardInternalRxSession* sessions[CANARD_NODE_ID_MAX + 1U]; ///< Read-only DO NOT MODIFY THIS -} CanardRxSubscription; +}; /// Reassembled incoming transfer returned by canardRxAccept(). -typedef struct CanardRxTransfer +struct CanardRxTransfer { - CanardTransferMetadata metadata; + struct CanardTransferMetadata metadata; /// The timestamp of the first received CAN frame of this transfer. /// The time system may be arbitrary as long as the clock is monotonic (steady). @@ -425,7 +422,7 @@ typedef struct CanardRxTransfer /// The application is required to deallocate the payload after the transfer is processed. struct CanardMutablePayload payload; -} CanardRxTransfer; +}; /// This is the core structure that keeps all of the states and allocated resources of the library instance. struct CanardInstance @@ -451,13 +448,13 @@ struct CanardInstance struct CanardMemoryResource memory; /// Read-only DO NOT MODIFY THIS - CanardTreeNode* rx_subscriptions[CANARD_NUM_TRANSFER_KINDS]; + struct CanardTreeNode* rx_subscriptions[CANARD_NUM_TRANSFER_KINDS]; }; /// CAN acceptance filter configuration with an extended 29-bit ID utilizing an ID + mask filter scheme. /// Filter configuration can be programmed into a CAN controller to filter out irrelevant messages in hardware. /// This allows the software application to reduce CPU load spent on processing irrelevant messages. -typedef struct CanardFilter +struct CanardFilter { /// 29-bit extended ID. Defines the extended CAN ID to filter incoming frames against. /// The bits above 29-th shall be zero. @@ -466,7 +463,7 @@ typedef struct CanardFilter /// Only bits that are enabled are compared to the extended_can_id for filtering. /// The bits above 29-th shall be zero. uint32_t extended_mask; -} CanardFilter; +}; /// Construct a new library instance. /// The default values will be assigned as specified in the structure field documentation. @@ -476,7 +473,7 @@ typedef struct CanardFilter /// To safely discard it, simply remove all existing subscriptions, and don't forget about the TX queues. /// /// The time complexity is constant. This function does not invoke the dynamic memory manager. -CanardInstance canardInit(const struct CanardMemoryResource memory); +struct CanardInstance canardInit(const struct CanardMemoryResource memory); /// Construct a new transmission queue instance with the specified values for capacity and mtu_bytes. /// No memory allocation is going to take place until the queue is actually pushed to. @@ -486,7 +483,9 @@ CanardInstance canardInit(const struct CanardMemoryResource memory); /// To safely discard it, simply pop all items from the queue and free them. /// /// The time complexity is constant. This function does not invoke the dynamic memory manager. -CanardTxQueue canardTxInit(const size_t capacity, const size_t mtu_bytes, const struct CanardMemoryResource memory); +struct CanardTxQueue canardTxInit(const size_t capacity, + const size_t mtu_bytes, + const struct CanardMemoryResource memory); /// This function serializes a transfer into a sequence of transport frames and inserts them into the prioritized /// transmission queue at the appropriate position. Afterwards, the application is supposed to take the enqueued frames @@ -536,11 +535,11 @@ CanardTxQueue canardTxInit(const size_t capacity, const size_t mtu_bytes, const /// the Canard instance memory resource is used for this allocation (and later for deallocation); /// - the second allocation is for payload storage (the frame data) - size is normally MTU but could be less for /// the last frame of the transfer; the TX queue memory resource is used for this allocation. -int32_t canardTxPush(CanardTxQueue* const que, - const CanardInstance* const ins, - const CanardMicrosecond tx_deadline_usec, - const CanardTransferMetadata* const metadata, - const struct CanardPayload payload); +int32_t canardTxPush(struct CanardTxQueue* const que, + const struct CanardInstance* const ins, + const CanardMicrosecond tx_deadline_usec, + const struct CanardTransferMetadata* const metadata, + const struct CanardPayload payload); /// This function accesses the top element of the prioritized transmission queue. The queue itself is not modified /// (i.e., the accessed element is not removed). The application should invoke this function to collect the transport @@ -563,7 +562,7 @@ int32_t canardTxPush(CanardTxQueue* const que, /// The payload buffer is allocated in the dynamic storage of the queue. The application may transfer ownership of /// the payload to a different application component (f.e. to transmission media) by copying the pointer and then /// (if the ownership transfer was accepted) by nullifying payload fields of the frame (`data` & `allocated_size`). -/// If these fields stay with their original values, the `canardTxFree` (after proper `canardTxPop of course) will +/// If these fields stay with their original values, the `canardTxFree` (after proper `canardTxPop` of course) will /// deallocate the payload buffer. In any case, the payload has to be eventually deallocated by the TX queue memory /// resource. It will be automatically done by the `canardTxFree` (if the payload still stays in the item), /// OR if moved, it is the responsibility of the application to eventually (f.e. at the end of transmission) deallocate @@ -572,25 +571,27 @@ int32_t canardTxPush(CanardTxQueue* const que, /// but it was changed to be mutable to allow the payload ownership transfer. /// /// The time complexity is logarithmic of the queue size. This function does not invoke the dynamic memory manager. -CanardTxQueueItem* canardTxPeek(const CanardTxQueue* const que); +struct CanardTxQueueItem* canardTxPeek(const struct CanardTxQueue* const que); /// This function transfers the ownership of the specified element of the prioritized transmission queue from the queue /// to the application. The element does not necessarily need to be the top one -- it is safe to dequeue any element. /// The element is dequeued but not invalidated; it is the responsibility of the application to deallocate the /// memory used by the object later (use `canardTxFree` helper). The memory SHALL NOT be deallocated UNTIL this function -/// is invoked. The function returns the same pointer that it is given except that it becomes mutable. +/// is invoked. The function returns the same pointer that it is given. /// /// If any of the arguments are NULL, the function has no effect and returns NULL. /// /// The time complexity is logarithmic of the queue size. This function does not invoke the dynamic memory manager. -CanardTxQueueItem* canardTxPop(CanardTxQueue* const que, const CanardTxQueueItem* const item); +struct CanardTxQueueItem* canardTxPop(struct CanardTxQueue* const que, struct CanardTxQueueItem* const item); /// This is a helper that frees the memory allocated (from the instance memory) for the item, /// as well as the internal frame payload buffer (if any) associated with it (using TX queue memory). /// If the item argument is NULL, the function has no effect. The time complexity is constant. /// If the item frame payload is NULL then it is assumed that the payload buffer was already freed, /// or moved to a different owner (f.e. to media layer). -void canardTxFree(CanardTxQueue* const que, const CanardInstance* const ins, CanardTxQueueItem* const item); +void canardTxFree(struct CanardTxQueue* const que, + const struct CanardInstance* const ins, + struct CanardTxQueueItem* const item); /// This function implements the transfer reassembly logic. It accepts a transport frame from any of the redundant /// interfaces, locates the appropriate subscription state, and, if found, updates it. If the frame completed a @@ -678,12 +679,12 @@ void canardTxFree(CanardTxQueue* const que, const CanardInstance* const ins, Can /// - The received frame is a valid Cyphal/CAN transport frame, but there is no matching subscription, /// the frame did not complete a transfer, the frame forms an invalid frame sequence, the frame is a duplicate, /// the frame is unicast to a different node (address mismatch). -int8_t canardRxAccept(CanardInstance* const ins, - const CanardMicrosecond timestamp_usec, - const CanardFrame* const frame, - const uint8_t redundant_iface_index, - CanardRxTransfer* const out_transfer, - CanardRxSubscription** const out_subscription); +int8_t canardRxAccept(struct CanardInstance* const ins, + const CanardMicrosecond timestamp_usec, + const struct CanardFrame* const frame, + const uint8_t redundant_iface_index, + struct CanardRxTransfer* const out_transfer, + struct CanardRxSubscription** const out_subscription); /// This function creates a new subscription, allowing the application to register its interest in a particular /// category of transfers. The library will reject all transport frames for which there is no active subscription. @@ -716,12 +717,12 @@ int8_t canardRxAccept(CanardInstance* const ins, /// Subscription instances have large look-up tables to ensure that the temporal properties of the algorithms are /// invariant to the network configuration (i.e., a node that is validated on a network containing one other node /// will provably perform identically on a network that contains X nodes). This is a conscious time-memory trade-off. -int8_t canardRxSubscribe(CanardInstance* const ins, - const CanardTransferKind transfer_kind, - const CanardPortID port_id, - const size_t extent, - const CanardMicrosecond transfer_id_timeout_usec, - CanardRxSubscription* const out_subscription); +int8_t canardRxSubscribe(struct CanardInstance* const ins, + const enum CanardTransferKind transfer_kind, + const CanardPortID port_id, + const size_t extent, + const CanardMicrosecond transfer_id_timeout_usec, + struct CanardRxSubscription* const out_subscription); /// This function reverses the effect of canardRxSubscribe(). /// If the subscription is found, all its memory is de-allocated (session states and payload buffers); to determine @@ -733,9 +734,9 @@ int8_t canardRxSubscribe(CanardInstance* const ins, /// /// The time complexity is logarithmic from the number of current subscriptions under the specified transfer kind. /// This function does not allocate new memory. -int8_t canardRxUnsubscribe(CanardInstance* const ins, - const CanardTransferKind transfer_kind, - const CanardPortID port_id); +int8_t canardRxUnsubscribe(struct CanardInstance* const ins, + const enum CanardTransferKind transfer_kind, + const CanardPortID port_id); /// This function allows to check the effect of canardRxSubscribe() and canardRxUnsubscribe(). /// @@ -747,10 +748,10 @@ int8_t canardRxUnsubscribe(CanardInstance* const ins, /// /// The time complexity is logarithmic from the number of current subscriptions under the specified transfer kind. /// This function does not allocate new memory. -int8_t canardRxGetSubscription(CanardInstance* const ins, - const CanardTransferKind transfer_kind, - const CanardPortID port_id, - CanardRxSubscription** const out_subscription); +int8_t canardRxGetSubscription(struct CanardInstance* const ins, + const enum CanardTransferKind transfer_kind, + const CanardPortID port_id, + struct CanardRxSubscription** const out_subscription); /// Utilities for generating CAN controller hardware acceptance filter configurations /// to accept specific subjects, services, or nodes. @@ -761,14 +762,14 @@ int8_t canardRxGetSubscription(CanardInstance* const ins, /// as well as the Cyphal specification for details. /// Generate an acceptance filter configuration to accept a specific subject ID. -CanardFilter canardMakeFilterForSubject(const CanardPortID subject_id); +struct CanardFilter canardMakeFilterForSubject(const CanardPortID subject_id); /// Generate an acceptance filter configuration to accept both requests and responses for a specific service. /// /// Users may prefer to instead use a catch-all acceptance filter configuration for accepting /// all service requests and responses targeted at the specified local node ID. /// See canardMakeFilterForServices() for this. -CanardFilter canardMakeFilterForService(const CanardPortID service_id, const CanardNodeID local_node_id); +struct CanardFilter canardMakeFilterForService(const CanardPortID service_id, const CanardNodeID local_node_id); /// Generate an acceptance filter configuration to accept all service /// requests and responses targeted to the specified local node ID. @@ -777,7 +778,7 @@ CanardFilter canardMakeFilterForService(const CanardPortID service_id, const Can /// and the fact that a service directed at a specific node is not likely to be rejected by that node, /// a user may prefer to use this over canardMakeFilterForService() /// in order to simplify the API usage and reduce the number of required hardware CAN acceptance filters. -CanardFilter canardMakeFilterForServices(const CanardNodeID local_node_id); +struct CanardFilter canardMakeFilterForServices(const CanardNodeID local_node_id); /// Consolidate two acceptance filter configurations into a single configuration. /// @@ -794,7 +795,7 @@ CanardFilter canardMakeFilterForServices(const CanardNodeID local_node_id); /// if information about the frequency of occurrence of different transfers is not known. /// For details, see the "Automatic hardware acceptance filter configuration" note under the Cyphal/CAN section /// in the Transport Layer chapter of the Cyphal specification. -CanardFilter canardConsolidateFilters(const CanardFilter* const a, const CanardFilter* const b); +struct CanardFilter canardConsolidateFilters(const struct CanardFilter* const a, const struct CanardFilter* const b); #ifdef __cplusplus } diff --git a/tests/helpers.hpp b/tests/helpers.hpp index d6f2dd6..12fdd33 100644 --- a/tests/helpers.hpp +++ b/tests/helpers.hpp @@ -317,7 +317,7 @@ class TxQueue return static_cast(ret); // NOLINT static downcast } - [[nodiscard]] auto pop(const CanardTxQueueItem* const which) -> exposed::TxItem* + [[nodiscard]] auto pop(CanardTxQueueItem* const which) -> exposed::TxItem* { checkInvariants(); const auto size_before = que_.size; diff --git a/tests/test_public_tx.cpp b/tests/test_public_tx.cpp index 918ff67..416816b 100644 --- a/tests/test_public_tx.cpp +++ b/tests/test_public_tx.cpp @@ -127,8 +127,8 @@ TEST_CASE("TxBasic0") // Pop the queue. // hex(pycyphal.transport.commons.crc.CRC16CCITT.new(list(range(8))).value) - constexpr std::uint16_t CRC8 = 0x178DU; - const CanardTxQueueItem* ti = que.peek(); + constexpr std::uint16_t CRC8 = 0x178DU; + CanardTxQueueItem* ti = que.peek(); REQUIRE(nullptr != ti); REQUIRE(ti->frame.payload.size == 12); REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data(), 8)); @@ -453,8 +453,8 @@ TEST_CASE("TxBasic1") // Pop the queue. // hex(pycyphal.transport.commons.crc.CRC16CCITT.new(list(range(8))).value) - constexpr std::uint16_t CRC8 = 0x178DU; - const CanardTxQueueItem* ti = que.peek(); + constexpr std::uint16_t CRC8 = 0x178DU; + CanardTxQueueItem* ti = que.peek(); REQUIRE(nullptr != ti); REQUIRE(ti->frame.payload.size == 12); REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data(), 8));