From dc19e935bbe0d95d8c1c6d2b357750dacb7b3b95 Mon Sep 17 00:00:00 2001 From: Sergei Date: Thu, 21 Nov 2024 12:10:35 +0200 Subject: [PATCH] Introduce `CanardPayload` etc (#235) - added `struct CanardPayload` to combine payload size and data. - added `struct CanardMutablePayload` to combine payload size, data and `allocated_size`. --- libcanard/canard.c | 302 +++++++++++++------------- libcanard/canard.h | 50 +++-- tests/exposed.hpp | 44 ++-- tests/helpers.hpp | 5 +- tests/test_private_rx.cpp | 366 +++++++++++++++++--------------- tests/test_public_roundtrip.cpp | 18 +- tests/test_public_rx.cpp | 117 +++++----- tests/test_public_tx.cpp | 276 ++++++++++++------------ 8 files changed, 596 insertions(+), 582 deletions(-) diff --git a/libcanard/canard.c b/libcanard/canard.c index 86df60c..accd90a 100644 --- a/libcanard/canard.c +++ b/libcanard/canard.c @@ -132,12 +132,12 @@ CANARD_PRIVATE TransferCRC crcAddByte(const TransferCRC crc, const uint8_t byte) #endif } -CANARD_PRIVATE TransferCRC crcAdd(const TransferCRC crc, const size_t size, const void* const data) +CANARD_PRIVATE TransferCRC crcAdd(const TransferCRC crc, const struct CanardPayload payload) { - CANARD_ASSERT((data != NULL) || (size == 0U)); + CANARD_ASSERT((payload.data != NULL) || (payload.size == 0U)); TransferCRC out = crc; - const uint8_t* p = (const uint8_t*) data; - for (size_t i = 0; i < size; i++) + const uint8_t* p = (const uint8_t*) payload.data; + for (size_t i = 0; i < payload.size; i++) { out = crcAddByte(out, *p); ++p; @@ -208,8 +208,7 @@ CANARD_PRIVATE size_t adjustPresentationLayerMTU(const size_t mtu_bytes) } CANARD_PRIVATE int32_t txMakeCANID(const CanardTransferMetadata* const tr, - const size_t payload_size, - const void* const payload, + const struct CanardPayload payload, const CanardNodeID local_node_id, const size_t presentation_layer_mtu) { @@ -224,10 +223,10 @@ CANARD_PRIVATE int32_t txMakeCANID(const CanardTransferMetadata* const tr, out = (int32_t) txMakeMessageSessionSpecifier(tr->port_id, local_node_id); CANARD_ASSERT(out >= 0); } - else if (payload_size <= presentation_layer_mtu) + else if (payload.size <= presentation_layer_mtu) { - CANARD_ASSERT((payload != NULL) || (payload_size == 0U)); - const CanardNodeID c = (CanardNodeID) (crcAdd(CRC_INITIAL, payload_size, payload) & CANARD_NODE_ID_MAX); + CANARD_ASSERT((payload.data != NULL) || (payload.size == 0U)); + const CanardNodeID c = (CanardNodeID) (crcAdd(CRC_INITIAL, payload) & CANARD_NODE_ID_MAX); const uint32_t spec = txMakeMessageSessionSpecifier(tr->port_id, c) | FLAG_ANONYMOUS_MESSAGE; CANARD_ASSERT(spec <= CAN_EXT_ID_MASK); out = (int32_t) spec; @@ -317,8 +316,8 @@ CANARD_PRIVATE TxItem* txAllocateQueueItem(CanardTxQueue* const que, out->base.next_in_transfer = NULL; // Last by default. out->base.tx_deadline_usec = deadline_usec; - out->base.frame.payload_size = payload_size; - out->base.frame.payload = out->payload_buffer; + out->base.frame.payload.size = payload_size; + out->base.frame.payload.data = out->payload_buffer; out->base.frame.extended_can_id = id; } return out; @@ -337,34 +336,33 @@ CANARD_PRIVATE int8_t txAVLPredicate(void* const user_reference, // NOSONAR Cav } /// Returns the number of frames enqueued or error (i.e., =1 or <0). -CANARD_PRIVATE int32_t txPushSingleFrame(CanardTxQueue* const que, - const CanardMicrosecond deadline_usec, - const uint32_t can_id, - const CanardTransferID transfer_id, - const size_t payload_size, - const void* const payload) +CANARD_PRIVATE int32_t txPushSingleFrame(CanardTxQueue* const que, + const CanardMicrosecond deadline_usec, + const uint32_t can_id, + const CanardTransferID transfer_id, + const struct CanardPayload payload) { CANARD_ASSERT(que != NULL); - CANARD_ASSERT((payload != NULL) || (payload_size == 0)); - const size_t frame_payload_size = txRoundFramePayloadSizeUp(payload_size + 1U); - 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); + CANARD_ASSERT((payload.data != NULL) || (payload.size == 0)); + const size_t frame_payload_size = txRoundFramePayloadSizeUp(payload.size + 1U); + 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; TxItem* const tqi = (que->size < que->capacity) ? txAllocateQueueItem(que, can_id, deadline_usec, frame_payload_size) : NULL; if (tqi != NULL) { - if (payload_size > 0U) // The check is needed to avoid calling memcpy() with a NULL pointer, it's an UB. + if (payload.size > 0U) // The check is needed to avoid calling memcpy() with a NULL pointer, it's an UB. { - CANARD_ASSERT(payload != NULL); + CANARD_ASSERT(payload.data != NULL); // Clang-Tidy raises an error recommending the use of memcpy_s() instead. // We ignore it because the safe functions are poorly supported; reliance on them may limit the portability. - (void) memcpy(&tqi->payload_buffer[0], payload, payload_size); // NOLINT + (void) memcpy(&tqi->payload_buffer[0], payload.data, payload.size); // NOLINT } // Clang-Tidy raises an error recommending the use of memset_s() instead. // We ignore it because the safe functions are poorly supported; reliance on them may limit the portability. - (void) memset(&tqi->payload_buffer[payload_size], PADDING_BYTE_VALUE, padding_size); // NOLINT + (void) memset(&tqi->payload_buffer[payload.size], PADDING_BYTE_VALUE, padding_size); // NOLINT tqi->payload_buffer[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.base, &txAVLPredicate, &avlTrivialFactory); @@ -383,25 +381,24 @@ 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 size_t presentation_layer_mtu, - const CanardMicrosecond deadline_usec, - const uint32_t can_id, - const CanardTransferID transfer_id, - const size_t payload_size, - const void* const payload) +CANARD_PRIVATE TxChain txGenerateMultiFrameChain(CanardTxQueue* const que, + 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); - CANARD_ASSERT(payload_size > presentation_layer_mtu); // Otherwise, a single-frame transfer should be used. - CANARD_ASSERT(payload != NULL); + CANARD_ASSERT(payload.size > presentation_layer_mtu); // Otherwise, a single-frame transfer should be used. + CANARD_ASSERT(payload.data != NULL); TxChain out = {NULL, NULL, 0}; - const size_t payload_size_with_crc = payload_size + CRC_SIZE_BYTES; + const size_t payload_size_with_crc = payload.size + CRC_SIZE_BYTES; size_t offset = 0U; - TransferCRC crc = crcAdd(CRC_INITIAL, payload_size, payload); + TransferCRC crc = crcAdd(CRC_INITIAL, payload); bool toggle = INITIAL_TOGGLE_STATE; - const uint8_t* payload_ptr = (const uint8_t*) payload; + const uint8_t* payload_ptr = (const uint8_t*) payload.data; while (offset < payload_size_with_crc) { out.size++; @@ -429,9 +426,9 @@ CANARD_PRIVATE TxChain txGenerateMultiFrameChain(CanardTxQueue* const que, // Copy the payload into the frame. const size_t frame_payload_size = frame_payload_size_with_tail - 1U; size_t frame_offset = 0U; - if (offset < payload_size) + if (offset < payload.size) { - size_t move_size = payload_size - offset; + size_t move_size = payload.size - offset; if (move_size > frame_payload_size) { move_size = frame_payload_size; @@ -446,7 +443,7 @@ CANARD_PRIVATE TxChain txGenerateMultiFrameChain(CanardTxQueue* const que, } // Handle the last frame of the transfer: it is special because it also contains padding and CRC. - if (offset >= payload_size) + if (offset >= payload.size) { // Insert padding -- only in the last frame. Don't forget to include padding into the CRC. while ((frame_offset + CRC_SIZE_BYTES) < frame_payload_size) @@ -457,14 +454,14 @@ CANARD_PRIVATE TxChain txGenerateMultiFrameChain(CanardTxQueue* const que, } // Insert the CRC. - if ((frame_offset < frame_payload_size) && (offset == payload_size)) + if ((frame_offset < frame_payload_size) && (offset == payload.size)) { // SonarQube incorrectly detects a buffer overflow here. out.tail->payload_buffer[frame_offset] = (uint8_t) (crc >> BITS_PER_BYTE); // NOSONAR ++frame_offset; ++offset; } - if ((frame_offset < frame_payload_size) && (offset > payload_size)) + if ((frame_offset < frame_payload_size) && (offset > payload.size)) { out.tail->payload_buffer[frame_offset] = (uint8_t) (crc & BYTE_MAX); ++frame_offset; @@ -473,7 +470,7 @@ CANARD_PRIVATE TxChain txGenerateMultiFrameChain(CanardTxQueue* const que, } // Finalize the frame. - CANARD_ASSERT((frame_offset + 1U) == out.tail->base.frame.payload_size); + CANARD_ASSERT((frame_offset + 1U) == out.tail->base.frame.payload.size); // SonarQube incorrectly detects a buffer overflow here. out.tail->payload_buffer[frame_offset] = // NOSONAR txMakeTailByte(out.head == out.tail, offset >= payload_size_with_crc, toggle, transfer_id); @@ -483,31 +480,25 @@ CANARD_PRIVATE TxChain txGenerateMultiFrameChain(CanardTxQueue* const que, } /// Returns the number of frames enqueued or error. -CANARD_PRIVATE int32_t txPushMultiFrame(CanardTxQueue* const que, - const size_t presentation_layer_mtu, - const CanardMicrosecond deadline_usec, - const uint32_t can_id, - const CanardTransferID transfer_id, - const size_t payload_size, - const void* const payload) +CANARD_PRIVATE int32_t txPushMultiFrame(CanardTxQueue* const que, + 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); - CANARD_ASSERT(payload_size > presentation_layer_mtu); // Otherwise, a single-frame transfer should be used. + CANARD_ASSERT(payload.size > presentation_layer_mtu); // Otherwise, a single-frame transfer should be used. int32_t out = 0; // The number of frames enqueued or negated error. - const size_t payload_size_with_crc = payload_size + CRC_SIZE_BYTES; + const size_t payload_size_with_crc = payload.size + CRC_SIZE_BYTES; const size_t num_frames = ((payload_size_with_crc + presentation_layer_mtu) - 1U) / presentation_layer_mtu; CANARD_ASSERT(num_frames >= 2); if ((que->size + num_frames) <= que->capacity) // Bail early if we can see that we won't fit anyway. { - const TxChain sq = txGenerateMultiFrameChain(que, - presentation_layer_mtu, - deadline_usec, - can_id, - transfer_id, - payload_size, - payload); + const TxChain sq = + txGenerateMultiFrameChain(que, presentation_layer_mtu, deadline_usec, can_id, transfer_id, payload); if (sq.tail != NULL) { CanardTxQueueItem* next = &sq.head->base; @@ -559,29 +550,27 @@ typedef struct CanardInternalRxSession { CanardMicrosecond transfer_timestamp_usec; ///< Timestamp of the last received start-of-transfer. size_t total_payload_size; ///< The payload size before the implicit truncation, including the CRC. - size_t payload_size; ///< How many bytes received so far. - uint8_t* payload; ///< Dynamically allocated and handed off to the application when done. - TransferCRC calculated_crc; ///< Updated with the received payload in real time. - CanardTransferID transfer_id; - uint8_t redundant_iface_index; ///< Arbitrary value in [0, 255]. - bool toggle; + struct CanardMutablePayload payload; ///< Dynamically allocated and handed off to the application when done. + TransferCRC calculated_crc; ///< Updated with the received payload in real time. + CanardTransferID transfer_id; + uint8_t redundant_iface_index; ///< Arbitrary value in [0, 255]. + bool toggle; } 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; - size_t payload_size; - const void* payload; + 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; } RxFrameModel; /// Returns truth if the frame is valid and parsed successfully. False if the frame is not a valid Cyphal/CAN frame. @@ -593,9 +582,9 @@ CANARD_PRIVATE bool rxTryParseFrame(const CanardMicrosecond timestamp_usec, CANARD_ASSERT(frame->extended_can_id <= CAN_EXT_ID_MASK); CANARD_ASSERT(out != NULL); bool valid = false; - if (frame->payload_size > 0) + if (frame->payload.size > 0) { - CANARD_ASSERT(frame->payload != NULL); + CANARD_ASSERT(frame->payload.data != NULL); out->timestamp_usec = timestamp_usec; // CAN ID parsing. @@ -626,12 +615,12 @@ CANARD_PRIVATE bool rxTryParseFrame(const CanardMicrosecond timestamp_usec, } // Payload parsing. - out->payload_size = frame->payload_size - 1U; // Cut off the tail byte. - out->payload = frame->payload; + out->payload.size = frame->payload.size - 1U; // Cut off the tail byte. + out->payload.data = frame->payload.data; // Tail byte parsing. // Intentional violation of MISRA: pointer arithmetics is required to locate the tail byte. Unavoidable. - const uint8_t tail = *(((const uint8_t*) out->payload) + out->payload_size); // NOSONAR + const uint8_t tail = *(((const uint8_t*) out->payload.data) + out->payload.size); // NOSONAR out->transfer_id = tail & CANARD_TRANSFER_ID_MAX; out->start_of_transfer = ((tail & TAIL_START_OF_TRANSFER) != 0); out->end_of_transfer = ((tail & TAIL_END_OF_TRANSFER) != 0); @@ -644,9 +633,9 @@ CANARD_PRIVATE bool rxTryParseFrame(const CanardMicrosecond timestamp_usec, valid = valid && ((out->start_of_transfer && out->end_of_transfer) || (CANARD_NODE_ID_UNSET != out->source_node_id)); // Non-last frames of a multi-frame transfer shall utilize the MTU fully. - valid = valid && ((out->payload_size >= MFT_NON_LAST_FRAME_PAYLOAD_MIN) || out->end_of_transfer); + valid = valid && ((out->payload.size >= MFT_NON_LAST_FRAME_PAYLOAD_MIN) || out->end_of_transfer); // A frame that is a part of a multi-frame transfer cannot be empty (tail byte not included). - valid = valid && ((out->payload_size > 0) || (out->start_of_transfer && out->end_of_transfer)); + valid = valid && ((out->payload.size > 0) || (out->start_of_transfer && out->end_of_transfer)); } return valid; } @@ -655,7 +644,7 @@ CANARD_PRIVATE void rxInitTransferMetadataFromFrame(const RxFrameModel* const CanardTransferMetadata* const out_transfer) { CANARD_ASSERT(frame != NULL); - CANARD_ASSERT(frame->payload != NULL); + CANARD_ASSERT(frame->payload.data != NULL); CANARD_ASSERT(out_transfer != NULL); out_transfer->priority = frame->priority; out_transfer->transfer_kind = frame->transfer_kind; @@ -681,35 +670,35 @@ CANARD_PRIVATE uint8_t rxComputeTransferIDDifference(const uint8_t a, const uint CANARD_PRIVATE int8_t rxSessionWritePayload(CanardInstance* const ins, CanardInternalRxSession* const rxs, const size_t extent, - const size_t payload_size, - const void* const payload) + const struct CanardPayload payload) { CANARD_ASSERT(ins != NULL); CANARD_ASSERT(rxs != NULL); - CANARD_ASSERT((payload != NULL) || (payload_size == 0U)); - CANARD_ASSERT(rxs->payload_size <= extent); // This invariant is enforced by the subscription logic. - CANARD_ASSERT(rxs->payload_size <= rxs->total_payload_size); + CANARD_ASSERT((payload.data != NULL) || (payload.size == 0U)); + CANARD_ASSERT(rxs->payload.size <= extent); // This invariant is enforced by the subscription logic. + CANARD_ASSERT(rxs->payload.size <= rxs->total_payload_size); - rxs->total_payload_size += payload_size; + rxs->total_payload_size += payload.size; // Allocate the payload lazily, as late as possible. - if ((NULL == rxs->payload) && (extent > 0U)) + if ((NULL == rxs->payload.data) && (extent > 0U)) { - CANARD_ASSERT(rxs->payload_size == 0); - rxs->payload = ins->memory.allocate(ins->memory.user_reference, extent); + CANARD_ASSERT(rxs->payload.size == 0); + rxs->payload.data = ins->memory.allocate(ins->memory.user_reference, extent); + rxs->payload.allocated_size = extent; } int8_t out = 0; - if (rxs->payload != NULL) + if (rxs->payload.data != NULL) { // Copy the payload into the contiguous buffer. Apply the implicit truncation rule if necessary. - size_t bytes_to_copy = payload_size; - if ((rxs->payload_size + bytes_to_copy) > extent) + size_t bytes_to_copy = payload.size; + if ((rxs->payload.size + bytes_to_copy) > extent) { - CANARD_ASSERT(rxs->payload_size <= extent); - bytes_to_copy = extent - rxs->payload_size; - CANARD_ASSERT((rxs->payload_size + bytes_to_copy) == extent); - CANARD_ASSERT(bytes_to_copy < payload_size); + CANARD_ASSERT(rxs->payload.size <= extent); + bytes_to_copy = extent - rxs->payload.size; + CANARD_ASSERT((rxs->payload.size + bytes_to_copy) == extent); + CANARD_ASSERT(bytes_to_copy < payload.size); } // This memcpy() call here is one of the two variable-complexity operations in the RX pipeline; // the other one is the search of the matching subscription state. @@ -717,31 +706,34 @@ CANARD_PRIVATE int8_t rxSessionWritePayload(CanardInstance* const ins, // Intentional violation of MISRA: indexing on a pointer. This is done to avoid pointer arithmetics. // Clang-Tidy raises an error recommending the use of memcpy_s() instead. // We ignore it because the safe functions are poorly supported; reliance on them may limit the portability. - (void) memcpy(&rxs->payload[rxs->payload_size], payload, bytes_to_copy); // NOLINT NOSONAR - rxs->payload_size += bytes_to_copy; - CANARD_ASSERT(rxs->payload_size <= extent); + (void) memcpy(((uint8_t*) rxs->payload.data) + rxs->payload.size, // NOLINT NOSONAR + payload.data, + bytes_to_copy); + rxs->payload.size += bytes_to_copy; + CANARD_ASSERT(rxs->payload.size <= extent); + CANARD_ASSERT(rxs->payload.size <= rxs->payload.allocated_size); } else { - CANARD_ASSERT(rxs->payload_size == 0); + CANARD_ASSERT(rxs->payload.size == 0); out = (extent > 0U) ? -CANARD_ERROR_OUT_OF_MEMORY : 0; } CANARD_ASSERT(out <= 0); return out; } -CANARD_PRIVATE void rxSessionRestart(CanardInstance* const ins, - CanardInternalRxSession* const rxs, - const size_t allocated_size) +CANARD_PRIVATE void rxSessionRestart(CanardInstance* const ins, CanardInternalRxSession* const rxs) { CANARD_ASSERT(ins != NULL); CANARD_ASSERT(rxs != NULL); - ins->memory.deallocate(ins->memory.user_reference, allocated_size, rxs->payload); // May be NULL, which is OK. - rxs->total_payload_size = 0U; - rxs->payload_size = 0U; - rxs->payload = NULL; - rxs->calculated_crc = CRC_INITIAL; - rxs->transfer_id = (CanardTransferID) ((rxs->transfer_id + 1U) & CANARD_TRANSFER_ID_MAX); + // `rxs->payload.data` may be NULL, which is OK. + ins->memory.deallocate(ins->memory.user_reference, rxs->payload.allocated_size, rxs->payload.data); + rxs->total_payload_size = 0U; + rxs->payload.size = 0U; + rxs->payload.data = NULL; + rxs->payload.allocated_size = 0U; + rxs->calculated_crc = CRC_INITIAL; + rxs->transfer_id = (CanardTransferID) ((rxs->transfer_id + 1U) & CANARD_TRANSFER_ID_MAX); // The transport index is retained. rxs->toggle = INITIAL_TOGGLE_STATE; } @@ -755,7 +747,7 @@ CANARD_PRIVATE int8_t rxSessionAcceptFrame(CanardInstance* const ins, CANARD_ASSERT(ins != NULL); CANARD_ASSERT(rxs != NULL); CANARD_ASSERT(frame != NULL); - CANARD_ASSERT(frame->payload != NULL); + CANARD_ASSERT(frame->payload.data != NULL); CANARD_ASSERT(frame->transfer_id <= CANARD_TRANSFER_ID_MAX); CANARD_ASSERT(out_transfer != NULL); @@ -769,14 +761,14 @@ CANARD_PRIVATE int8_t rxSessionAcceptFrame(CanardInstance* const ins, { // Update the CRC. Observe that the implicit truncation rule may apply here: the payload may be // truncated, but its CRC is validated always anyway. - rxs->calculated_crc = crcAdd(rxs->calculated_crc, frame->payload_size, frame->payload); + rxs->calculated_crc = crcAdd(rxs->calculated_crc, frame->payload); } - int8_t out = rxSessionWritePayload(ins, rxs, extent, frame->payload_size, frame->payload); + int8_t out = rxSessionWritePayload(ins, rxs, extent, frame->payload); if (out < 0) { CANARD_ASSERT(-CANARD_ERROR_OUT_OF_MEMORY == out); - rxSessionRestart(ins, rxs, extent); // Out-of-memory. + rxSessionRestart(ins, rxs); // Out-of-memory. } else if (frame->end_of_transfer) { @@ -786,22 +778,23 @@ CANARD_PRIVATE int8_t rxSessionAcceptFrame(CanardInstance* const ins, out = 1; // One transfer received, notify the application. rxInitTransferMetadataFromFrame(frame, &out_transfer->metadata); out_transfer->timestamp_usec = rxs->transfer_timestamp_usec; - out_transfer->payload_size = rxs->payload_size; out_transfer->payload = rxs->payload; - out_transfer->allocated_size = (rxs->payload != NULL) ? extent : 0U; // Cut off the CRC from the payload if it's there -- we don't want to expose it to the user. - CANARD_ASSERT(rxs->total_payload_size >= rxs->payload_size); - const size_t truncated_amount = rxs->total_payload_size - rxs->payload_size; + CANARD_ASSERT(rxs->total_payload_size >= rxs->payload.size); + const size_t truncated_amount = rxs->total_payload_size - rxs->payload.size; if ((!single_frame) && (CRC_SIZE_BYTES > truncated_amount)) // Single-frame transfers don't have CRC. { - CANARD_ASSERT(out_transfer->payload_size >= (CRC_SIZE_BYTES - truncated_amount)); - out_transfer->payload_size -= CRC_SIZE_BYTES - truncated_amount; + CANARD_ASSERT(out_transfer->payload.size >= (CRC_SIZE_BYTES - truncated_amount)); + out_transfer->payload.size -= CRC_SIZE_BYTES - truncated_amount; } - rxs->payload = NULL; // Ownership passed over to the application, nullify to prevent freeing. + // Ownership passed over to the application, nullify to prevent freeing. + rxs->payload.size = 0U; + rxs->payload.data = NULL; + rxs->payload.allocated_size = 0U; } - rxSessionRestart(ins, rxs, extent); // Successful completion. + rxSessionRestart(ins, rxs); // Successful completion. } else { @@ -860,7 +853,7 @@ CANARD_PRIVATE void rxSessionSynchronize(CanardInternalRxSession* const rxs, { CANARD_ASSERT(frame->start_of_transfer); rxs->total_payload_size = 0U; - rxs->payload_size = 0U; // The buffer is not released because we still need it. + rxs->payload.size = 0U; // The buffer is not released because we still need it. rxs->calculated_crc = CRC_INITIAL; rxs->transfer_id = frame->transfer_id; rxs->toggle = INITIAL_TOGGLE_STATE; @@ -923,7 +916,7 @@ CANARD_PRIVATE int8_t rxAcceptFrame(CanardInstance* const ins, CANARD_ASSERT(subscription != NULL); CANARD_ASSERT(subscription->port_id == frame->port_id); CANARD_ASSERT(frame != NULL); - CANARD_ASSERT(frame->payload != NULL); + CANARD_ASSERT(frame->payload.data != NULL); CANARD_ASSERT(frame->transfer_id <= CANARD_TRANSFER_ID_MAX); CANARD_ASSERT((CANARD_NODE_ID_UNSET == frame->destination_node_id) || (ins->node_id == frame->destination_node_id)); CANARD_ASSERT(out_transfer != NULL); @@ -943,8 +936,9 @@ CANARD_PRIVATE int8_t rxAcceptFrame(CanardInstance* const ins, { rxs->transfer_timestamp_usec = frame->timestamp_usec; rxs->total_payload_size = 0U; - rxs->payload_size = 0U; - rxs->payload = NULL; + rxs->payload.size = 0U; + rxs->payload.data = NULL; + rxs->payload.allocated_size = 0U; rxs->calculated_crc = CRC_INITIAL; rxs->transfer_id = frame->transfer_id; rxs->redundant_iface_index = redundant_iface_index; @@ -975,18 +969,18 @@ CANARD_PRIVATE int8_t rxAcceptFrame(CanardInstance* const ins, // We have to copy the data into an allocated storage because the API expects it: the lifetime shall be // independent of the input data and the memory shall be free-able. const size_t payload_size = - (subscription->extent < frame->payload_size) ? subscription->extent : frame->payload_size; - void* const payload = ins->memory.allocate(ins->memory.user_reference, payload_size); - if (payload != NULL) + (subscription->extent < frame->payload.size) ? subscription->extent : frame->payload.size; + void* const payload_data = ins->memory.allocate(ins->memory.user_reference, payload_size); + if (payload_data != NULL) { rxInitTransferMetadataFromFrame(frame, &out_transfer->metadata); - out_transfer->timestamp_usec = frame->timestamp_usec; - out_transfer->payload_size = payload_size; - out_transfer->payload = payload; - out_transfer->allocated_size = payload_size; + out_transfer->timestamp_usec = frame->timestamp_usec; + out_transfer->payload.size = payload_size; + out_transfer->payload.data = payload_data; + out_transfer->payload.allocated_size = payload_size; // Clang-Tidy raises an error recommending the use of memcpy_s() instead. // We ignore it because the safe functions are poorly supported; reliance on them may limit the portability. - (void) memcpy(payload, frame->payload, payload_size); // NOLINT + (void) memcpy(payload_data, frame->payload.data, payload_size); // NOLINT out = 1; } else @@ -1061,24 +1055,18 @@ int32_t canardTxPush(CanardTxQueue* const que, const CanardInstance* const ins, const CanardMicrosecond tx_deadline_usec, const CanardTransferMetadata* const metadata, - const size_t payload_size, - const void* const payload) + const struct CanardPayload payload) { int32_t out = -CANARD_ERROR_INVALID_ARGUMENT; - if ((ins != NULL) && (que != NULL) && (metadata != NULL) && ((payload != NULL) || (0U == payload_size))) + if ((ins != NULL) && (que != NULL) && (metadata != NULL) && ((payload.data != NULL) || (0U == payload.size))) { const size_t pl_mtu = adjustPresentationLayerMTU(que->mtu_bytes); - const int32_t maybe_can_id = txMakeCANID(metadata, payload_size, payload, ins->node_id, pl_mtu); + const int32_t maybe_can_id = txMakeCANID(metadata, payload, ins->node_id, pl_mtu); if (maybe_can_id >= 0) { - if (payload_size <= pl_mtu) + if (payload.size <= pl_mtu) { - out = txPushSingleFrame(que, - tx_deadline_usec, - (uint32_t) maybe_can_id, - metadata->transfer_id, - payload_size, - payload); + out = txPushSingleFrame(que, tx_deadline_usec, (uint32_t) maybe_can_id, metadata->transfer_id, payload); CANARD_ASSERT((out < 0) || (out == 1)); } else @@ -1088,7 +1076,6 @@ int32_t canardTxPush(CanardTxQueue* const que, tx_deadline_usec, (uint32_t) maybe_can_id, metadata->transfer_id, - payload_size, payload); CANARD_ASSERT((out < 0) || (out >= 2)); } @@ -1142,7 +1129,7 @@ int8_t canardRxAccept(CanardInstance* const ins, { int8_t out = -CANARD_ERROR_INVALID_ARGUMENT; if ((ins != NULL) && (out_transfer != NULL) && (frame != NULL) && (frame->extended_can_id <= CAN_EXT_ID_MASK) && - ((frame->payload != NULL) || (0 == frame->payload_size))) + ((frame->payload.data != NULL) || (0 == frame->payload.size))) { RxFrameModel model = {0}; if (rxTryParseFrame(timestamp_usec, frame, &model)) @@ -1242,12 +1229,15 @@ int8_t canardRxUnsubscribe(CanardInstance* const ins, out = 1; for (size_t i = 0; i < RX_SESSIONS_PER_SUBSCRIPTION; i++) { - if (sub->sessions[i] != NULL) + CanardInternalRxSession* const session = sub->sessions[i]; + if (session != NULL) { - ins->memory.deallocate(ins->memory.user_reference, sub->extent, sub->sessions[i]->payload); + ins->memory.deallocate(ins->memory.user_reference, + session->payload.allocated_size, + session->payload.data); + ins->memory.deallocate(ins->memory.user_reference, sizeof(*session), session); + sub->sessions[i] = NULL; } - ins->memory.deallocate(ins->memory.user_reference, sizeof(*sub->sessions[i]), sub->sessions[i]); - sub->sessions[i] = NULL; } } else diff --git a/libcanard/canard.h b/libcanard/canard.h index 143ea4a..051286a 100644 --- a/libcanard/canard.h +++ b/libcanard/canard.h @@ -171,6 +171,33 @@ struct CanardTreeNode int8_t bf; ///< Do not access this field. }; +struct CanardPayload +{ + /// Size of the payload data in bytes. + /// If the payload is empty (size = 0), the payload pointer may be NULL. + size_t size; + + /// Pointer to the payload data buffer. + const void* data; +}; + +struct CanardMutablePayload +{ + /// Size of the payload data in bytes. + /// The value is always less than or equal to the extent specified in the subscription. + /// If the payload is empty (`size` = 0), the `data` pointer may be NULL. + size_t size; + + /// The application is required to deallocate the payload buffer after the transfer is processed. + /// Allocated buffer size (`allocated_size`, not `size`) should be used to deallocate the buffer. + void* data; + + /// Size of the allocated data buffer in bytes. + /// Normally equal to the extent specified in the subscription, but could be less (equal to `size`) + /// in case of single frame transfer, or even zero if the `data` pointer is NULL. + size_t allocated_size; +}; + /// 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 @@ -179,14 +206,13 @@ typedef struct uint32_t extended_can_id; /// The useful data in the frame. The length value is not to be confused with DLC! - /// If the payload is empty (payload_size = 0), the payload pointer may be NULL. + /// If the payload is empty (payload.size = 0), the payload.data pointer may be NULL. /// For RX frames: the library does not expect the lifetime of the pointee to extend beyond the point of return /// from the API function. That is, the pointee can be invalidated immediately after the frame has been processed. /// For TX frames: the frame and the payload are allocated within the same dynamic memory fragment, so their /// 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. - size_t payload_size; - const void* payload; + struct CanardPayload payload; } CanardFrame; /// Conversion look-up table from CAN DLC to data length. @@ -384,19 +410,8 @@ typedef struct CanardRxTransfer /// The time system may be arbitrary as long as the clock is monotonic (steady). CanardMicrosecond timestamp_usec; - /// Size of the payload data in bytes. - /// The value is always less than or equal to the extent specified in the subscription. - /// If the payload is empty (payload_size = 0), the payload pointer may be NULL. - size_t payload_size; - - /// The application is required to deallocate the payload buffer after the transfer is processed. - /// Allocated buffer size (`allocated_size`, not `payload_size`) should be used to deallocate the buffer. - void* payload; - - /// Size of the allocated payload buffer in bytes. - /// Normally equal to the extent specified in the subscription, but could be less (equal to `payload_size`) - /// in case of single frame transfer, or even zero if the payload pointer is NULL. - size_t allocated_size; + /// 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. @@ -509,8 +524,7 @@ int32_t canardTxPush(CanardTxQueue* const que, const CanardInstance* const ins, const CanardMicrosecond tx_deadline_usec, const CanardTransferMetadata* const metadata, - const size_t payload_size, - const void* const payload); + 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 diff --git a/tests/exposed.hpp b/tests/exposed.hpp index d5f4105..aa4ffdb 100644 --- a/tests/exposed.hpp +++ b/tests/exposed.hpp @@ -19,17 +19,17 @@ struct TxItem final : CanardTxQueueItem { [[nodiscard]] auto getPayloadByte(const std::size_t offset) const -> std::uint8_t { - return reinterpret_cast(frame.payload)[offset]; + return static_cast(frame.payload.data)[offset]; } [[nodiscard]] auto getTailByte() const { - if (frame.payload_size < 1U) + if (frame.payload.size < 1U) { // Can't use REQUIRE because it is not thread-safe. throw std::logic_error("Can't get the tail byte because the frame payload is empty."); } - return getPayloadByte(frame.payload_size - 1U); + return getPayloadByte(frame.payload.size - 1U); } [[nodiscard]] auto isStartOfTransfer() const { return (getTailByte() & 128U) != 0; } @@ -45,30 +45,28 @@ struct TxItem final : CanardTxQueueItem struct RxSession { - CanardMicrosecond transfer_timestamp_usec = std::numeric_limits::max(); - std::size_t total_payload_size = 0U; - std::size_t payload_size = 0U; - std::uint8_t* payload = nullptr; - TransferCRC calculated_crc = 0U; - CanardTransferID transfer_id = std::numeric_limits::max(); - std::uint8_t redundant_iface_index = std::numeric_limits::max(); - bool toggle = false; + CanardMicrosecond transfer_timestamp_usec = std::numeric_limits::max(); + std::size_t total_payload_size = 0U; + CanardMutablePayload payload = {0U, nullptr, 0U}; + TransferCRC calculated_crc = 0U; + CanardTransferID transfer_id = std::numeric_limits::max(); + std::uint8_t redundant_iface_index = std::numeric_limits::max(); + bool toggle = false; }; struct RxFrameModel { - CanardMicrosecond timestamp_usec = std::numeric_limits::max(); - CanardPriority priority = CanardPriorityOptional; - CanardTransferKind transfer_kind = CanardTransferKindMessage; - CanardPortID port_id = std::numeric_limits::max(); - CanardNodeID source_node_id = CANARD_NODE_ID_UNSET; - CanardNodeID destination_node_id = CANARD_NODE_ID_UNSET; - CanardTransferID transfer_id = std::numeric_limits::max(); - bool start_of_transfer = false; - bool end_of_transfer = false; - bool toggle = false; - std::size_t payload_size = 0U; - const std::uint8_t* payload = nullptr; + CanardMicrosecond timestamp_usec = std::numeric_limits::max(); + CanardPriority priority = CanardPriorityOptional; + CanardTransferKind transfer_kind = CanardTransferKindMessage; + CanardPortID port_id = std::numeric_limits::max(); + CanardNodeID source_node_id = CANARD_NODE_ID_UNSET; + CanardNodeID destination_node_id = CANARD_NODE_ID_UNSET; + CanardTransferID transfer_id = std::numeric_limits::max(); + bool start_of_transfer = false; + bool end_of_transfer = false; + bool toggle = false; + CanardPayload payload = {0U, nullptr}; }; // Extern C effectively discards the outer namespaces. diff --git a/tests/helpers.hpp b/tests/helpers.hpp index 06672b4..6ae15fb 100644 --- a/tests/helpers.hpp +++ b/tests/helpers.hpp @@ -288,12 +288,11 @@ class TxQueue [[nodiscard]] auto push(CanardInstance* const ins, const CanardMicrosecond transmission_deadline_usec, const CanardTransferMetadata& metadata, - const std::size_t payload_size, - const void* const payload) + const struct CanardPayload payload) { checkInvariants(); const auto size_before = que_.size; - const auto ret = canardTxPush(&que_, ins, transmission_deadline_usec, &metadata, payload_size, payload); + const auto ret = canardTxPush(&que_, ins, transmission_deadline_usec, &metadata, payload); const auto num_added = static_cast(ret); enforce((ret < 0) || ((size_before + num_added) == que_.size), "Unexpected size change after push"); checkInvariants(); diff --git a/tests/test_private_rx.cpp b/tests/test_private_rx.cpp index aed4109..efa45bd 100644 --- a/tests/test_private_rx.cpp +++ b/tests/test_private_rx.cpp @@ -6,6 +6,18 @@ #include "catch.hpp" #include +namespace +{ +auto bytes(const CanardPayload& payload) +{ + return static_cast(payload.data); +} +auto bytes(const CanardMutablePayload& payload) +{ + return static_cast(payload.data); +} +} // namespace + TEST_CASE("rxTryParseFrame") { using exposed::RxFrameModel; @@ -20,8 +32,7 @@ TEST_CASE("rxTryParseFrame") payload_storage = payload; CanardFrame frame{}; frame.extended_can_id = extended_can_id; - frame.payload_size = std::size(payload); - frame.payload = payload_storage.data(); + frame.payload = {payload_storage.size(), payload_storage.data()}; model = RxFrameModel{}; return rxTryParseFrame(timestamp_usec, &frame, &model); }; @@ -38,14 +49,14 @@ TEST_CASE("rxTryParseFrame") REQUIRE(!model.start_of_transfer); REQUIRE(!model.end_of_transfer); REQUIRE(!model.toggle); - REQUIRE(model.payload_size == 7); - REQUIRE(model.payload[0] == 0); - REQUIRE(model.payload[1] == 1); - REQUIRE(model.payload[2] == 2); - REQUIRE(model.payload[3] == 3); - REQUIRE(model.payload[4] == 4); - REQUIRE(model.payload[5] == 5); - REQUIRE(model.payload[6] == 6); + REQUIRE(model.payload.size == 7); + REQUIRE(bytes(model.payload)[0] == 0); + REQUIRE(bytes(model.payload)[1] == 1); + REQUIRE(bytes(model.payload)[2] == 2); + REQUIRE(bytes(model.payload)[3] == 3); + REQUIRE(bytes(model.payload)[4] == 4); + REQUIRE(bytes(model.payload)[5] == 5); + REQUIRE(bytes(model.payload)[6] == 6); // SIMILAR BUT INVALID REQUIRE(!parse(543210U, 0U, {})); // NO TAIL BYTE REQUIRE(!parse(543210U, 0U, {0})); // MFT FRAMES REQUIRE PAYLOAD @@ -63,14 +74,14 @@ TEST_CASE("rxTryParseFrame") REQUIRE(model.start_of_transfer); REQUIRE(!model.end_of_transfer); REQUIRE(model.toggle); - REQUIRE(model.payload_size == 7); - REQUIRE(model.payload[0] == 0); - REQUIRE(model.payload[1] == 1); - REQUIRE(model.payload[2] == 2); - REQUIRE(model.payload[3] == 3); - REQUIRE(model.payload[4] == 4); - REQUIRE(model.payload[5] == 5); - REQUIRE(model.payload[6] == 6); + REQUIRE(model.payload.size == 7); + REQUIRE(bytes(model.payload)[0] == 0); + REQUIRE(bytes(model.payload)[1] == 1); + REQUIRE(bytes(model.payload)[2] == 2); + REQUIRE(bytes(model.payload)[3] == 3); + REQUIRE(bytes(model.payload)[4] == 4); + REQUIRE(bytes(model.payload)[5] == 5); + REQUIRE(bytes(model.payload)[6] == 6); // SIMILAR BUT INVALID // NO TAIL BYTE REQUIRE(!parse(123456U, 0b001'00'0'11'0110011001100'0'0100111U, {})); @@ -97,7 +108,7 @@ TEST_CASE("rxTryParseFrame") REQUIRE(model.start_of_transfer); REQUIRE(model.end_of_transfer); REQUIRE(model.toggle); - REQUIRE(model.payload_size == 0); + REQUIRE(model.payload.size == 0); // SAME BUT RESERVED 21 22 SET (and ignored) REQUIRE(parse(12345U, 0b010'01'0'11'0110011001101'0'0100111U, {0b111'00000U | 0U})); REQUIRE(model.port_id == 0b0110011001101U); @@ -120,11 +131,11 @@ TEST_CASE("rxTryParseFrame") REQUIRE(!model.start_of_transfer); REQUIRE(model.end_of_transfer); REQUIRE(model.toggle); - REQUIRE(model.payload_size == 4); - REQUIRE(model.payload[0] == 0); - REQUIRE(model.payload[1] == 1); - REQUIRE(model.payload[2] == 2); - REQUIRE(model.payload[3] == 3); + REQUIRE(model.payload.size == 4); + REQUIRE(bytes(model.payload)[0] == 0); + REQUIRE(bytes(model.payload)[1] == 1); + REQUIRE(bytes(model.payload)[2] == 2); + REQUIRE(bytes(model.payload)[3] == 3); // SIMILAR BUT INVALID REQUIRE(!parse(999'999U, 0b011'11'0000110011'0011010'0100111U, {})); // NO TAIL BYTE REQUIRE(!parse(999'999U, 0b011'11'0000110011'0011010'0100111U, {0, 1, 2, 3, 0b110'00000U | 31U})); // BAD TOGGLE @@ -143,8 +154,8 @@ TEST_CASE("rxTryParseFrame") REQUIRE(!model.start_of_transfer); REQUIRE(model.end_of_transfer); REQUIRE(!model.toggle); - REQUIRE(model.payload_size == 1); - REQUIRE(model.payload[0] == 255); + REQUIRE(model.payload.size == 1); + REQUIRE(bytes(model.payload)[0] == 255); // SIMILAR BUT INVALID REQUIRE(!parse(888'888U, 0b100'10'0000110011'0100111'0011010U, {})); // NO TAIL BYTE REQUIRE(!parse(888'888U, 0b100'10'0000110011'0100111'0011010U, {255, 0b100'00000U | 1U})); // BAD TOGGLE @@ -170,70 +181,70 @@ TEST_CASE("rxSessionWritePayload") REQUIRE(0 == rxSessionWritePayload(&ins.getInstance(), &rxs, 10, 5, "\x00\x01\x02\x03\x04")); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == 10); - REQUIRE(rxs.payload_size == 5); - REQUIRE(rxs.payload != nullptr); - REQUIRE(rxs.payload[0] == 0); - REQUIRE(rxs.payload[1] == 1); - REQUIRE(rxs.payload[2] == 2); - REQUIRE(rxs.payload[3] == 3); - REQUIRE(rxs.payload[4] == 4); + REQUIRE(rxs.payload.size == 5); + REQUIRE(rxs.payload.data != nullptr); + REQUIRE(bytes(rxs.payload)[0] == 0); + REQUIRE(bytes(rxs.payload)[1] == 1); + REQUIRE(bytes(rxs.payload)[2] == 2); + REQUIRE(bytes(rxs.payload)[3] == 3); + REQUIRE(bytes(rxs.payload)[4] == 4); // Appending the pre-allocated storage. REQUIRE(0 == rxSessionWritePayload(&ins.getInstance(), &rxs, 10, 4, "\x05\x06\x07\x08")); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == 10); - REQUIRE(rxs.payload_size == 9); - REQUIRE(rxs.payload != nullptr); - REQUIRE(rxs.payload[0] == 0); - REQUIRE(rxs.payload[1] == 1); - REQUIRE(rxs.payload[2] == 2); - REQUIRE(rxs.payload[3] == 3); - REQUIRE(rxs.payload[4] == 4); - REQUIRE(rxs.payload[5] == 5); - REQUIRE(rxs.payload[6] == 6); - REQUIRE(rxs.payload[7] == 7); - REQUIRE(rxs.payload[8] == 8); + REQUIRE(rxs.payload.size == 9); + REQUIRE(rxs.payload.data != nullptr); + REQUIRE(bytes(rxs.payload)[0] == 0); + REQUIRE(bytes(rxs.payload)[1] == 1); + REQUIRE(bytes(rxs.payload)[2] == 2); + REQUIRE(bytes(rxs.payload)[3] == 3); + REQUIRE(bytes(rxs.payload)[4] == 4); + REQUIRE(bytes(rxs.payload)[5] == 5); + REQUIRE(bytes(rxs.payload)[6] == 6); + REQUIRE(bytes(rxs.payload)[7] == 7); + REQUIRE(bytes(rxs.payload)[8] == 8); // Implicit truncation -- too much payload, excess ignored. REQUIRE(0 == rxSessionWritePayload(&ins.getInstance(), &rxs, 10, 3, "\x09\x0A\x0B")); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == 10); - REQUIRE(rxs.payload_size == 10); - REQUIRE(rxs.payload != nullptr); - REQUIRE(rxs.payload[0] == 0); - REQUIRE(rxs.payload[1] == 1); - REQUIRE(rxs.payload[2] == 2); - REQUIRE(rxs.payload[3] == 3); - REQUIRE(rxs.payload[4] == 4); - REQUIRE(rxs.payload[5] == 5); - REQUIRE(rxs.payload[6] == 6); - REQUIRE(rxs.payload[7] == 7); - REQUIRE(rxs.payload[8] == 8); - REQUIRE(rxs.payload[9] == 9); + REQUIRE(rxs.payload.size == 10); + REQUIRE(rxs.payload.data != nullptr); + REQUIRE(bytes(rxs.payload)[0] == 0); + REQUIRE(bytes(rxs.payload)[1] == 1); + REQUIRE(bytes(rxs.payload)[2] == 2); + REQUIRE(bytes(rxs.payload)[3] == 3); + REQUIRE(bytes(rxs.payload)[4] == 4); + REQUIRE(bytes(rxs.payload)[5] == 5); + REQUIRE(bytes(rxs.payload)[6] == 6); + REQUIRE(bytes(rxs.payload)[7] == 7); + REQUIRE(bytes(rxs.payload)[8] == 8); + REQUIRE(bytes(rxs.payload)[9] == 9); // Storage is already full, write ignored. REQUIRE(0 == rxSessionWritePayload(&ins.getInstance(), &rxs, 10, 3, "\x0C\x0D\x0E")); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == 10); - REQUIRE(rxs.payload_size == 10); - REQUIRE(rxs.payload != nullptr); - REQUIRE(rxs.payload[0] == 0); - REQUIRE(rxs.payload[1] == 1); - REQUIRE(rxs.payload[2] == 2); - REQUIRE(rxs.payload[3] == 3); - REQUIRE(rxs.payload[4] == 4); - REQUIRE(rxs.payload[5] == 5); - REQUIRE(rxs.payload[6] == 6); - REQUIRE(rxs.payload[7] == 7); - REQUIRE(rxs.payload[8] == 8); - REQUIRE(rxs.payload[9] == 9); + REQUIRE(rxs.payload.size == 10); + REQUIRE(rxs.payload.data != nullptr); + REQUIRE(bytes(rxs.payload)[0] == 0); + REQUIRE(bytes(rxs.payload)[1] == 1); + REQUIRE(bytes(rxs.payload)[2] == 2); + REQUIRE(bytes(rxs.payload)[3] == 3); + REQUIRE(bytes(rxs.payload)[4] == 4); + REQUIRE(bytes(rxs.payload)[5] == 5); + REQUIRE(bytes(rxs.payload)[6] == 6); + REQUIRE(bytes(rxs.payload)[7] == 7); + REQUIRE(bytes(rxs.payload)[8] == 8); + REQUIRE(bytes(rxs.payload)[9] == 9); // Restart frees the buffer. The transfer-ID will be incremented, too. rxSessionRestart(&ins.getInstance(), &rxs, 10); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 0); REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == 0); - REQUIRE(rxs.payload_size == 0); - REQUIRE(rxs.payload == nullptr); + REQUIRE(rxs.payload.size == 0); + REQUIRE(rxs.payload.data == nullptr); REQUIRE(rxs.calculated_crc == 0xFFFFU); REQUIRE(rxs.transfer_id == 1); REQUIRE(rxs.toggle); @@ -245,8 +256,8 @@ TEST_CASE("rxSessionWritePayload") rxSessionRestart(&ins.getInstance(), &rxs, 10); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 0); REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == 0); - REQUIRE(rxs.payload_size == 0); - REQUIRE(rxs.payload == nullptr); + REQUIRE(rxs.payload.size == 0); + REQUIRE(rxs.payload.data == nullptr); REQUIRE(rxs.calculated_crc == 0xFFFFU); REQUIRE(rxs.transfer_id == 24U); REQUIRE(rxs.toggle); @@ -258,8 +269,8 @@ TEST_CASE("rxSessionWritePayload") rxSessionRestart(&ins.getInstance(), &rxs, 10); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 0); REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == 0); - REQUIRE(rxs.payload_size == 0); - REQUIRE(rxs.payload == nullptr); + REQUIRE(rxs.payload.size == 0); + REQUIRE(rxs.payload.data == nullptr); REQUIRE(rxs.calculated_crc == 0xFFFFU); REQUIRE(rxs.transfer_id == 0U); REQUIRE(rxs.toggle); @@ -268,16 +279,16 @@ TEST_CASE("rxSessionWritePayload") REQUIRE(0 == rxSessionWritePayload(&ins.getInstance(), &rxs, 0, 3, "\x00\x01\x02")); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 0); REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == 0); - REQUIRE(rxs.payload_size == 0); - REQUIRE(rxs.payload == nullptr); + REQUIRE(rxs.payload.size == 0); + REQUIRE(rxs.payload.data == nullptr); // Write with OOM. ins.getAllocator().setAllocationCeiling(5); REQUIRE(-CANARD_ERROR_OUT_OF_MEMORY == rxSessionWritePayload(&ins.getInstance(), &rxs, 10, 3, "\x00\x01\x02")); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 0); REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == 0); - REQUIRE(rxs.payload_size == 0); - REQUIRE(rxs.payload == nullptr); + REQUIRE(rxs.payload.size == 0); + REQUIRE(rxs.payload.data == nullptr); } TEST_CASE("rxSessionUpdate") @@ -302,8 +313,8 @@ TEST_CASE("rxSessionUpdate") frame.start_of_transfer = true; frame.end_of_transfer = true; frame.toggle = true; - frame.payload_size = 3; - frame.payload = reinterpret_cast("\x01\x01\x01"); + frame.payload.size = 3; + frame.payload.data = reinterpret_cast("\x01\x01\x01"); RxSession rxs; rxs.transfer_id = 31; @@ -327,8 +338,8 @@ TEST_CASE("rxSessionUpdate") // Accept one transfer. REQUIRE(1 == update(1, 1'000'000, 16)); REQUIRE(rxs.transfer_timestamp_usec == 10'000'000); - REQUIRE(rxs.payload_size == 0); // Handed over to the output transfer. - REQUIRE(rxs.payload == nullptr); // Handed over to the output transfer. + REQUIRE(rxs.payload.size == 0); // Handed over to the output transfer. + REQUIRE(rxs.payload.data == nullptr); // Handed over to the output transfer. REQUIRE(rxs.calculated_crc == 0xFFFF); REQUIRE(rxs.transfer_id == 12U); // Incremented. REQUIRE(rxs.toggle); @@ -339,21 +350,21 @@ TEST_CASE("rxSessionUpdate") REQUIRE(transfer.metadata.port_id == 2'222); REQUIRE(transfer.metadata.remote_node_id == 55); REQUIRE(transfer.metadata.transfer_id == 11); - REQUIRE(transfer.payload_size == 3); - REQUIRE(transfer.allocated_size == 16); - REQUIRE(0 == std::memcmp(transfer.payload, "\x01\x01\x01", 3)); + REQUIRE(transfer.payload.size == 3); + REQUIRE(transfer.payload.allocated_size == 16); + REQUIRE(0 == std::memcmp(transfer.payload.data, "\x01\x01\x01", 3)); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == 16); - ins.getAllocator().deallocate(transfer.payload, transfer.allocated_size); + ins.getAllocator().deallocate(transfer.payload.data, transfer.payload.allocated_size); // Valid next transfer, wrong transport. frame.timestamp_usec = 10'000'100; frame.transfer_id = 12; - frame.payload = reinterpret_cast("\x02\x02\x02"); + frame.payload.data = reinterpret_cast("\x02\x02\x02"); REQUIRE(0 == update(2, 1'000'000, 16)); REQUIRE(rxs.transfer_timestamp_usec == 10'000'000); - REQUIRE(rxs.payload_size == 0); // Handed over to the output transfer. - REQUIRE(rxs.payload == nullptr); // Handed over to the output transfer. + REQUIRE(rxs.payload.size == 0); // Handed over to the output transfer. + REQUIRE(rxs.payload.data == nullptr); // Handed over to the output transfer. REQUIRE(rxs.calculated_crc == 0xFFFF); REQUIRE(rxs.transfer_id == 12U); // Incremented. REQUIRE(rxs.toggle); @@ -361,11 +372,11 @@ TEST_CASE("rxSessionUpdate") // Correct transport. frame.timestamp_usec = 10'000'050; - frame.payload = reinterpret_cast("\x03\x03\x03"); + frame.payload.data = reinterpret_cast("\x03\x03\x03"); REQUIRE(1 == update(1, 1'000'000, 16)); REQUIRE(rxs.transfer_timestamp_usec == 10'000'050); - REQUIRE(rxs.payload_size == 0); - REQUIRE(rxs.payload == nullptr); + REQUIRE(rxs.payload.size == 0); + REQUIRE(rxs.payload.data == nullptr); REQUIRE(rxs.calculated_crc == 0xFFFF); REQUIRE(rxs.transfer_id == 13U); REQUIRE(rxs.toggle); @@ -376,21 +387,21 @@ TEST_CASE("rxSessionUpdate") REQUIRE(transfer.metadata.port_id == 2'222); REQUIRE(transfer.metadata.remote_node_id == 55); REQUIRE(transfer.metadata.transfer_id == 12); - REQUIRE(transfer.payload_size == 3); - REQUIRE(transfer.allocated_size == 16); - REQUIRE(0 == std::memcmp(transfer.payload, "\x03\x03\x03", 3)); + REQUIRE(transfer.payload.size == 3); + REQUIRE(transfer.payload.allocated_size == 16); + REQUIRE(0 == std::memcmp(transfer.payload.data, "\x03\x03\x03", 3)); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == 16); - ins.getAllocator().deallocate(transfer.payload, transfer.allocated_size); + ins.getAllocator().deallocate(transfer.payload.data, transfer.payload.allocated_size); // Same TID. frame.timestamp_usec = 10'000'200; frame.transfer_id = 12; - frame.payload = reinterpret_cast("\x04\x04\x04"); + frame.payload.data = reinterpret_cast("\x04\x04\x04"); REQUIRE(0 == update(1, 1'000'200, 16)); REQUIRE(rxs.transfer_timestamp_usec == 10'000'050); - REQUIRE(rxs.payload_size == 0); - REQUIRE(rxs.payload == nullptr); + REQUIRE(rxs.payload.size == 0); + REQUIRE(rxs.payload.data == nullptr); REQUIRE(rxs.calculated_crc == 0xFFFF); REQUIRE(rxs.transfer_id == 13U); REQUIRE(rxs.toggle); @@ -399,11 +410,11 @@ TEST_CASE("rxSessionUpdate") // Restart due to TID timeout, same iface. frame.timestamp_usec = 15'000'000; frame.transfer_id = 12; - frame.payload = reinterpret_cast("\x05\x05\x05"); + frame.payload.data = reinterpret_cast("\x05\x05\x05"); REQUIRE(1 == update(1, 1'000'000, 16)); REQUIRE(rxs.transfer_timestamp_usec == 15'000'000); - REQUIRE(rxs.payload_size == 0); - REQUIRE(rxs.payload == nullptr); + REQUIRE(rxs.payload.size == 0); + REQUIRE(rxs.payload.data == nullptr); REQUIRE(rxs.calculated_crc == 0xFFFF); REQUIRE(rxs.transfer_id == 13U); REQUIRE(rxs.toggle); @@ -414,21 +425,21 @@ TEST_CASE("rxSessionUpdate") REQUIRE(transfer.metadata.port_id == 2'222); REQUIRE(transfer.metadata.remote_node_id == 55); REQUIRE(transfer.metadata.transfer_id == 12); - REQUIRE(transfer.payload_size == 3); - REQUIRE(transfer.allocated_size == 16); - REQUIRE(0 == std::memcmp(transfer.payload, "\x05\x05\x05", 3)); + REQUIRE(transfer.payload.size == 3); + REQUIRE(transfer.payload.allocated_size == 16); + REQUIRE(0 == std::memcmp(transfer.payload.data, "\x05\x05\x05", 3)); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == 16); - ins.getAllocator().deallocate(transfer.payload, transfer.allocated_size); + ins.getAllocator().deallocate(transfer.payload.data, transfer.payload.allocated_size); // Restart due to TID timeout, switch iface. frame.timestamp_usec = 20'000'000; frame.transfer_id = 11; - frame.payload = reinterpret_cast("\x05\x05\x05"); + frame.payload.data = reinterpret_cast("\x05\x05\x05"); REQUIRE(1 == update(0, 1'000'000, 16)); REQUIRE(rxs.transfer_timestamp_usec == 20'000'000); - REQUIRE(rxs.payload_size == 0); - REQUIRE(rxs.payload == nullptr); + REQUIRE(rxs.payload.size == 0); + REQUIRE(rxs.payload.data == nullptr); REQUIRE(rxs.calculated_crc == 0xFFFF); REQUIRE(rxs.transfer_id == 12U); REQUIRE(rxs.toggle); @@ -439,23 +450,23 @@ TEST_CASE("rxSessionUpdate") REQUIRE(transfer.metadata.port_id == 2'222); REQUIRE(transfer.metadata.remote_node_id == 55); REQUIRE(transfer.metadata.transfer_id == 11); - REQUIRE(transfer.payload_size == 3); - REQUIRE(transfer.allocated_size == 16); - REQUIRE(0 == std::memcmp(transfer.payload, "\x05\x05\x05", 3)); + REQUIRE(transfer.payload.size == 3); + REQUIRE(transfer.payload.allocated_size == 16); + REQUIRE(0 == std::memcmp(transfer.payload.data, "\x05\x05\x05", 3)); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == 16); - ins.getAllocator().deallocate(transfer.payload, transfer.allocated_size); + ins.getAllocator().deallocate(transfer.payload.data, transfer.payload.allocated_size); // Multi-frame, first. frame.timestamp_usec = 20'000'100; frame.transfer_id = 13; frame.end_of_transfer = false; - frame.payload_size = 7; - frame.payload = reinterpret_cast("\x06\x06\x06\x06\x06\x06\x06"); + frame.payload.size = 7; + frame.payload.data = reinterpret_cast("\x06\x06\x06\x06\x06\x06\x06"); REQUIRE(0 == update(0, 1'000'000, 16)); REQUIRE(rxs.transfer_timestamp_usec == 20'000'100); - REQUIRE(rxs.payload_size == 7); - REQUIRE(0 == std::memcmp(rxs.payload, "\x06\x06\x06\x06\x06\x06\x06", 7)); + REQUIRE(rxs.payload.size == 7); + REQUIRE(0 == std::memcmp(rxs.payload.data, "\x06\x06\x06\x06\x06\x06\x06", 7)); REQUIRE(rxs.calculated_crc == crc("\x06\x06\x06\x06\x06\x06\x06")); REQUIRE(rxs.transfer_id == 13U); REQUIRE(!rxs.toggle); @@ -468,11 +479,11 @@ TEST_CASE("rxSessionUpdate") frame.start_of_transfer = false; frame.end_of_transfer = false; frame.toggle = false; - frame.payload = reinterpret_cast("\x07\x07\x07\x07\x07\x07\x07"); + frame.payload.data = reinterpret_cast("\x07\x07\x07\x07\x07\x07\x07"); REQUIRE(0 == update(0, 1'000'000, 16)); REQUIRE(rxs.transfer_timestamp_usec == 20'000'100); - REQUIRE(rxs.payload_size == 14); - REQUIRE(0 == std::memcmp(rxs.payload, "\x06\x06\x06\x06\x06\x06\x06\x07\x07\x07\x07\x07\x07\x07", 14)); + REQUIRE(rxs.payload.size == 14); + REQUIRE(0 == std::memcmp(rxs.payload.data, "\x06\x06\x06\x06\x06\x06\x06\x07\x07\x07\x07\x07\x07\x07", 14)); REQUIRE(rxs.calculated_crc == crc("\x06\x06\x06\x06\x06\x06\x06\x07\x07\x07\x07\x07\x07\x07")); REQUIRE(rxs.transfer_id == 13U); REQUIRE(rxs.toggle); @@ -485,11 +496,11 @@ TEST_CASE("rxSessionUpdate") frame.start_of_transfer = false; frame.end_of_transfer = true; frame.toggle = false; - frame.payload = reinterpret_cast("\x08\x08\x08\x08"); + frame.payload.data = reinterpret_cast("\x08\x08\x08\x08"); REQUIRE(0 == update(0, 1'000'000, 16)); REQUIRE(rxs.transfer_timestamp_usec == 20'000'100); - REQUIRE(rxs.payload_size == 14); - REQUIRE(0 == std::memcmp(rxs.payload, "\x06\x06\x06\x06\x06\x06\x06\x07\x07\x07\x07\x07\x07\x07", 14)); + REQUIRE(rxs.payload.size == 14); + REQUIRE(0 == std::memcmp(rxs.payload.data, "\x06\x06\x06\x06\x06\x06\x06\x07\x07\x07\x07\x07\x07\x07", 14)); REQUIRE(rxs.calculated_crc == crc("\x06\x06\x06\x06\x06\x06\x06\x07\x07\x07\x07\x07\x07\x07")); REQUIRE(rxs.transfer_id == 13U); REQUIRE(rxs.toggle); @@ -502,12 +513,12 @@ TEST_CASE("rxSessionUpdate") frame.start_of_transfer = false; frame.end_of_transfer = true; frame.toggle = true; - frame.payload_size = 6; // The payload is IMPLICITLY TRUNCATED, and the CRC IS STILL VALIDATED. - frame.payload = reinterpret_cast("\x09\x09\x09\x09\r\x93"); + frame.payload.size = 6; // The payload is IMPLICITLY TRUNCATED, and the CRC IS STILL VALIDATED. + frame.payload.data = reinterpret_cast("\x09\x09\x09\x09\r\x93"); REQUIRE(1 == update(0, 1'000'000, 16)); REQUIRE(rxs.transfer_timestamp_usec == 20'000'100); // First frame. - REQUIRE(rxs.payload_size == 0); - REQUIRE(rxs.payload == nullptr); + REQUIRE(rxs.payload.size == 0); + REQUIRE(rxs.payload.data == nullptr); REQUIRE(rxs.calculated_crc == 0xFFFF); REQUIRE(rxs.transfer_id == 14U); REQUIRE(rxs.toggle); @@ -518,12 +529,13 @@ TEST_CASE("rxSessionUpdate") REQUIRE(transfer.metadata.port_id == 2'222); REQUIRE(transfer.metadata.remote_node_id == 55); REQUIRE(transfer.metadata.transfer_id == 13); - REQUIRE(transfer.payload_size == 16); - REQUIRE(transfer.allocated_size == 16); - REQUIRE(0 == std::memcmp(transfer.payload, "\x06\x06\x06\x06\x06\x06\x06\x07\x07\x07\x07\x07\x07\x07\x09\x09", 16)); + REQUIRE(transfer.payload.size == 16); + REQUIRE(transfer.payload.allocated_size == 16); + REQUIRE(0 == + std::memcmp(transfer.payload.data, "\x06\x06\x06\x06\x06\x06\x06\x07\x07\x07\x07\x07\x07\x07\x09\x09", 16)); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == 16); - ins.getAllocator().deallocate(transfer.payload, transfer.allocated_size); + ins.getAllocator().deallocate(transfer.payload.data, transfer.payload.allocated_size); // TID timeout does not occur until SOT; see https://github.com/OpenCyphal/libcanard/issues/212. frame.timestamp_usec = 30'000'000; @@ -531,8 +543,8 @@ TEST_CASE("rxSessionUpdate") frame.start_of_transfer = false; frame.end_of_transfer = false; frame.toggle = true; - frame.payload_size = 7; - frame.payload = reinterpret_cast("\x0A\x0A\x0A\x0A\x0A\x0A\x0A"); + frame.payload.size = 7; + frame.payload.data = reinterpret_cast("\x0A\x0A\x0A\x0A\x0A\x0A\x0A"); REQUIRE(0 == update(2, 1'000'000, 16)); REQUIRE(rxs.transfer_timestamp_usec == 20'000'100); // No change. REQUIRE(rxs.transfer_id == 14U); // No change. @@ -547,12 +559,12 @@ TEST_CASE("rxSessionUpdate") frame.start_of_transfer = true; frame.end_of_transfer = false; frame.toggle = true; - frame.payload_size = 7; - frame.payload = reinterpret_cast("\x0A\x0A\x0A\x0A\x0A\x0A\x0A"); + frame.payload.size = 7; + frame.payload.data = reinterpret_cast("\x0A\x0A\x0A\x0A\x0A\x0A\x0A"); REQUIRE(0 == update(2, 1'000'000, 16)); REQUIRE(rxs.transfer_timestamp_usec == 30'000'000); // Updated from the frame. - REQUIRE(rxs.payload_size == 7); // From the frame. - REQUIRE(rxs.payload != nullptr); + REQUIRE(rxs.payload.size == 7); // From the frame. + REQUIRE(rxs.payload.data != nullptr); REQUIRE(rxs.calculated_crc == 0x23C7); REQUIRE(rxs.transfer_id == 12U); // Updated from the frame. REQUIRE(!rxs.toggle); // In anticipation of the next frame. @@ -566,12 +578,12 @@ TEST_CASE("rxSessionUpdate") frame.start_of_transfer = true; frame.end_of_transfer = false; frame.toggle = true; - frame.payload_size = 7; - frame.payload = reinterpret_cast("\x0B\x0B\x0B\x0B\x0B\x0B\x0B"); + frame.payload.size = 7; + frame.payload.data = reinterpret_cast("\x0B\x0B\x0B\x0B\x0B\x0B\x0B"); REQUIRE(0 == update(2, 1'000'000, 16)); REQUIRE(rxs.transfer_timestamp_usec == 20'000'200); - REQUIRE(rxs.payload_size == 7); - REQUIRE(0 == std::memcmp(rxs.payload, "\x0B\x0B\x0B\x0B\x0B\x0B\x0B", 7)); + REQUIRE(rxs.payload.size == 7); + REQUIRE(0 == std::memcmp(rxs.payload.data, "\x0B\x0B\x0B\x0B\x0B\x0B\x0B", 7)); REQUIRE(rxs.calculated_crc == crc("\x0B\x0B\x0B\x0B\x0B\x0B\x0B")); REQUIRE(rxs.transfer_id == 10U); REQUIRE(!rxs.toggle); @@ -585,12 +597,12 @@ TEST_CASE("rxSessionUpdate") frame.start_of_transfer = true; frame.end_of_transfer = true; frame.toggle = true; - frame.payload_size = 7; - frame.payload = reinterpret_cast("\x0C\x0C\x0C\x0C\x0C\x0C\x0C"); + frame.payload.size = 7; + frame.payload.data = reinterpret_cast("\x0C\x0C\x0C\x0C\x0C\x0C\x0C"); REQUIRE(0 == update(2, 1'000'000, 16)); REQUIRE(rxs.transfer_timestamp_usec == 20'000'200); - REQUIRE(rxs.payload_size == 7); - REQUIRE(0 == std::memcmp(rxs.payload, "\x0B\x0B\x0B\x0B\x0B\x0B\x0B", 7)); + REQUIRE(rxs.payload.size == 7); + REQUIRE(0 == std::memcmp(rxs.payload.data, "\x0B\x0B\x0B\x0B\x0B\x0B\x0B", 7)); REQUIRE(rxs.calculated_crc == crc("\x0B\x0B\x0B\x0B\x0B\x0B\x0B")); REQUIRE(rxs.transfer_id == 10U); REQUIRE(!rxs.toggle); @@ -604,12 +616,12 @@ TEST_CASE("rxSessionUpdate") frame.start_of_transfer = false; frame.end_of_transfer = true; frame.toggle = false; - frame.payload_size = 5; - frame.payload = reinterpret_cast("\x0D\x0D\x0DWd"); // CRC at the end. + frame.payload.size = 5; + frame.payload.data = reinterpret_cast("\x0D\x0D\x0DWd"); // CRC at the end. REQUIRE(1 == update(2, 1'000'000, 16)); REQUIRE(rxs.transfer_timestamp_usec == 20'000'200); - REQUIRE(rxs.payload_size == 0); - REQUIRE(rxs.payload == nullptr); + REQUIRE(rxs.payload.size == 0); + REQUIRE(rxs.payload.data == nullptr); REQUIRE(rxs.calculated_crc == 0xFFFF); REQUIRE(rxs.transfer_id == 11U); REQUIRE(rxs.toggle); @@ -620,12 +632,12 @@ TEST_CASE("rxSessionUpdate") REQUIRE(transfer.metadata.port_id == 2'222); REQUIRE(transfer.metadata.remote_node_id == 55); REQUIRE(transfer.metadata.transfer_id == 10); - REQUIRE(transfer.payload_size == 10); - REQUIRE(transfer.allocated_size == 16); - REQUIRE(0 == std::memcmp(transfer.payload, "\x0B\x0B\x0B\x0B\x0B\x0B\x0B\x0D\x0D\x0D", 10)); + REQUIRE(transfer.payload.size == 10); + REQUIRE(transfer.payload.allocated_size == 16); + REQUIRE(0 == std::memcmp(transfer.payload.data, "\x0B\x0B\x0B\x0B\x0B\x0B\x0B\x0D\x0D\x0D", 10)); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == 16); - ins.getAllocator().deallocate(transfer.payload, transfer.allocated_size); + ins.getAllocator().deallocate(transfer.payload.data, transfer.payload.allocated_size); // CRC SPLIT -- first frame. frame.timestamp_usec = 30'000'000; @@ -633,12 +645,12 @@ TEST_CASE("rxSessionUpdate") frame.start_of_transfer = true; frame.end_of_transfer = false; frame.toggle = true; - frame.payload_size = 8; - frame.payload = reinterpret_cast("\x0E\x0E\x0E\x0E\x0E\x0E\x0E\xF7"); + frame.payload.size = 8; + frame.payload.data = reinterpret_cast("\x0E\x0E\x0E\x0E\x0E\x0E\x0E\xF7"); REQUIRE(0 == update(0, 1'000'000, 16)); REQUIRE(rxs.transfer_timestamp_usec == 30'000'000); - REQUIRE(rxs.payload_size == 8); - REQUIRE(0 == std::memcmp(rxs.payload, "\x0E\x0E\x0E\x0E\x0E\x0E\x0E\xF7", 8)); + REQUIRE(rxs.payload.size == 8); + REQUIRE(0 == std::memcmp(rxs.payload.data, "\x0E\x0E\x0E\x0E\x0E\x0E\x0E\xF7", 8)); REQUIRE(rxs.calculated_crc == crc("\x0E\x0E\x0E\x0E\x0E\x0E\x0E\xF7")); REQUIRE(rxs.transfer_id == 0); REQUIRE(!rxs.toggle); @@ -652,12 +664,12 @@ TEST_CASE("rxSessionUpdate") frame.start_of_transfer = false; frame.end_of_transfer = true; frame.toggle = false; - frame.payload_size = 1; - frame.payload = reinterpret_cast("\xD7"); + frame.payload.size = 1; + frame.payload.data = reinterpret_cast("\xD7"); REQUIRE(1 == update(0, 1'000'000, 16)); REQUIRE(rxs.transfer_timestamp_usec == 30'000'000); - REQUIRE(rxs.payload_size == 0); - REQUIRE(rxs.payload == nullptr); + REQUIRE(rxs.payload.size == 0); + REQUIRE(rxs.payload.data == nullptr); REQUIRE(rxs.calculated_crc == 0xFFFF); REQUIRE(rxs.transfer_id == 1U); REQUIRE(rxs.toggle); @@ -668,12 +680,12 @@ TEST_CASE("rxSessionUpdate") REQUIRE(transfer.metadata.port_id == 2'222); REQUIRE(transfer.metadata.remote_node_id == 55); REQUIRE(transfer.metadata.transfer_id == 0); - REQUIRE(transfer.payload_size == 7); // ONE CRC BYTE BACKTRACKED! - REQUIRE(transfer.allocated_size == 16); - REQUIRE(0 == std::memcmp(transfer.payload, "\x0E\x0E\x0E\x0E\x0E\x0E\x0E", 7)); + REQUIRE(transfer.payload.size == 7); // ONE CRC BYTE BACKTRACKED! + REQUIRE(transfer.payload.allocated_size == 16); + REQUIRE(0 == std::memcmp(transfer.payload.data, "\x0E\x0E\x0E\x0E\x0E\x0E\x0E", 7)); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == 16); - ins.getAllocator().deallocate(transfer.payload, transfer.allocated_size); + ins.getAllocator().deallocate(transfer.payload.data, transfer.payload.allocated_size); // BAD CRC -- first frame. frame.timestamp_usec = 30'001'000; @@ -681,12 +693,12 @@ TEST_CASE("rxSessionUpdate") frame.start_of_transfer = true; frame.end_of_transfer = false; frame.toggle = true; - frame.payload_size = 8; - frame.payload = reinterpret_cast("\x0E\x0E\x0E\x0E\x0E\x0E\x0E\xF7"); + frame.payload.size = 8; + frame.payload.data = reinterpret_cast("\x0E\x0E\x0E\x0E\x0E\x0E\x0E\xF7"); REQUIRE(0 == update(0, 1'000'000, 16)); REQUIRE(rxs.transfer_timestamp_usec == 30'001'000); - REQUIRE(rxs.payload_size == 8); - REQUIRE(0 == std::memcmp(rxs.payload, "\x0E\x0E\x0E\x0E\x0E\x0E\x0E\xF7", 8)); + REQUIRE(rxs.payload.size == 8); + REQUIRE(0 == std::memcmp(rxs.payload.data, "\x0E\x0E\x0E\x0E\x0E\x0E\x0E\xF7", 8)); REQUIRE(rxs.calculated_crc == crc("\x0E\x0E\x0E\x0E\x0E\x0E\x0E\xF7")); REQUIRE(rxs.transfer_id == 31U); REQUIRE(!rxs.toggle); @@ -700,12 +712,12 @@ TEST_CASE("rxSessionUpdate") frame.start_of_transfer = false; frame.end_of_transfer = true; frame.toggle = false; - frame.payload_size = 1; - frame.payload = reinterpret_cast("\xD8"); + frame.payload.size = 1; + frame.payload.data = reinterpret_cast("\xD8"); REQUIRE(0 == update(0, 1'000'000, 16)); REQUIRE(rxs.transfer_timestamp_usec == 30'001'000); - REQUIRE(rxs.payload_size == 0); - REQUIRE(rxs.payload == nullptr); + REQUIRE(rxs.payload.size == 0); + REQUIRE(rxs.payload.data == nullptr); REQUIRE(rxs.calculated_crc == 0xFFFF); REQUIRE(rxs.transfer_id == 0U); REQUIRE(rxs.toggle); @@ -719,12 +731,12 @@ TEST_CASE("rxSessionUpdate") frame.start_of_transfer = true; frame.end_of_transfer = false; frame.toggle = true; - frame.payload_size = 8; - frame.payload = reinterpret_cast("\x0E\x0E\x0E\x0E\x0E\x0E\x0E\xF7"); + frame.payload.size = 8; + frame.payload.data = reinterpret_cast("\x0E\x0E\x0E\x0E\x0E\x0E\x0E\xF7"); REQUIRE((-CANARD_ERROR_OUT_OF_MEMORY) == update(2, 1'000'000, 17)); // Exceeds the heap quota. REQUIRE(rxs.transfer_timestamp_usec == 40'000'000); - REQUIRE(rxs.payload_size == 0); - REQUIRE(rxs.payload == nullptr); + REQUIRE(rxs.payload.size == 0); + REQUIRE(rxs.payload.data == nullptr); REQUIRE(rxs.calculated_crc == 0xFFFF); REQUIRE(rxs.transfer_id == 31U); // Reset. REQUIRE(rxs.toggle); diff --git a/tests/test_public_roundtrip.cpp b/tests/test_public_roundtrip.cpp index fed4f8b..64e7629 100644 --- a/tests/test_public_roundtrip.cpp +++ b/tests/test_public_roundtrip.cpp @@ -100,7 +100,7 @@ TEST_CASE("RoundtripSimple") { const std::lock_guard locker(lock); const auto result = - que_tx.push(&ins_tx.getInstance(), timestamp_usec, tran, payload_size, payload.get()); + que_tx.push(&ins_tx.getInstance(), timestamp_usec, tran, {payload_size, payload.get()}); if (result > 0) { pending_transfers.emplace(timestamp_usec, Pending{tran, payload_size, std::move(payload)}); @@ -148,10 +148,10 @@ TEST_CASE("RoundtripSimple") if (ti != nullptr) { - const auto tail = static_cast(ti->frame.payload)[ti->frame.payload_size - 1U]; + const auto tail = static_cast(ti->frame.payload.data)[ti->frame.payload.size - 1U]; log_file << ti->tx_deadline_usec << " " // << std::hex << std::setfill('0') << std::setw(8) << ti->frame.extended_can_id // - << " [" << std::dec << std::setfill(' ') << std::setw(2) << ti->frame.payload_size << "] " // + << " [" << std::dec << std::setfill(' ') << std::setw(2) << ti->frame.payload.size << "] " // << (static_cast(tail & 128U) ? 'S' : ' ') // << (static_cast(tail & 64U) ? 'E' : ' ') // << (static_cast(tail & 32U) ? 'T' : ' ') // @@ -184,19 +184,19 @@ TEST_CASE("RoundtripSimple") REQUIRE(transfer.metadata.remote_node_id == ins_tx.getNodeID()); REQUIRE(transfer.metadata.transfer_id == ref_meta.transfer_id); // The payload size is not checked because the variance is huge due to padding and truncation. - if (transfer.payload != nullptr) + if (transfer.payload.data != nullptr) { - REQUIRE(0 == std::memcmp(transfer.payload, + REQUIRE(0 == std::memcmp(transfer.payload.data, ref_payload.get(), - std::min(transfer.payload_size, ref_payload_size))); + std::min(transfer.payload.size, ref_payload_size))); } else { - REQUIRE(transfer.payload_size == 0U); - REQUIRE(transfer.allocated_size == 0U); + REQUIRE(transfer.payload.size == 0U); + REQUIRE(transfer.payload.allocated_size == 0U); } - ins_rx.getAllocator().deallocate(transfer.payload, transfer.allocated_size); + ins_rx.getAllocator().deallocate(transfer.payload.data, transfer.payload.allocated_size); } else { diff --git a/tests/test_public_rx.cpp b/tests/test_public_rx.cpp index 4fe5132..d84161a 100644 --- a/tests/test_public_rx.cpp +++ b/tests/test_public_rx.cpp @@ -30,8 +30,7 @@ TEST_CASE("RxBasic0") payload_storage = payload; CanardFrame frame{}; frame.extended_can_id = extended_can_id; - frame.payload_size = std::size(payload); - frame.payload = payload_storage.data(); + frame.payload = {std::size(payload), payload_storage.data()}; return ins.rxAccept(timestamp_usec, frame, redundant_iface_index, transfer, &subscription); }; @@ -117,17 +116,17 @@ TEST_CASE("RxBasic0") REQUIRE(transfer.metadata.port_id == 0b0110011001100); REQUIRE(transfer.metadata.remote_node_id == 0b0100111); REQUIRE(transfer.metadata.transfer_id == 0); - REQUIRE(transfer.payload_size == 0); - REQUIRE(transfer.allocated_size == 16); - REQUIRE(0 == std::memcmp(transfer.payload, "", 0)); + REQUIRE(transfer.payload.size == 0); + REQUIRE(transfer.payload.allocated_size == 16); + REQUIRE(0 == std::memcmp(transfer.payload.data, "", 0)); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 2); // The SESSION and the PAYLOAD BUFFER. REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == (sizeof(RxSession) + 16)); REQUIRE(ins.getMessageSubs().at(0)->sessions[0b0100111] != nullptr); // Will need these later. // - auto* const msg_payload = transfer.payload; - const auto payload_alloc_size = transfer.allocated_size; + auto* const msg_payload = transfer.payload.data; + const auto payload_alloc_size = transfer.payload.allocated_size; // Provide the space for an extra session and its payload. ins.getAllocator().setAllocationCeiling(sizeof(RxSession) * 2 + 16 + 20); @@ -154,9 +153,9 @@ TEST_CASE("RxBasic0") REQUIRE(transfer.metadata.port_id == 0b0000110011); REQUIRE(transfer.metadata.remote_node_id == 0b0100101); REQUIRE(transfer.metadata.transfer_id == 4); - REQUIRE(transfer.payload_size == 3); - REQUIRE(transfer.allocated_size == 20); - REQUIRE(0 == std::memcmp(transfer.payload, "\x01\x02\x03", 3)); + REQUIRE(transfer.payload.size == 3); + REQUIRE(transfer.payload.allocated_size == 20); + REQUIRE(0 == std::memcmp(transfer.payload.data, "\x01\x02\x03", 3)); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 4); // Two SESSIONS and two PAYLOAD BUFFERS. REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == (2 * sizeof(RxSession) + 16 + 20)); REQUIRE(ins.getRequestSubs().at(0)->sessions[0b0100101] != nullptr); @@ -209,9 +208,9 @@ TEST_CASE("RxBasic0") REQUIRE(transfer.metadata.port_id == 0b0000111100); REQUIRE(transfer.metadata.remote_node_id == 0b0011011); REQUIRE(transfer.metadata.transfer_id == 3); - REQUIRE(transfer.payload_size == 1); - REQUIRE(transfer.allocated_size == 10); - REQUIRE(0 == std::memcmp(transfer.payload, "\x05", 1)); + REQUIRE(transfer.payload.size == 1); + REQUIRE(transfer.payload.allocated_size == 10); + REQUIRE(0 == std::memcmp(transfer.payload.data, "\x05", 1)); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 4); REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == (2 * sizeof(RxSession) + 10 + 20)); @@ -268,8 +267,7 @@ TEST_CASE("RxAnonymous") payload_storage = payload; CanardFrame frame{}; frame.extended_can_id = extended_can_id; - frame.payload_size = std::size(payload); - frame.payload = payload_storage.data(); + frame.payload = {std::size(payload), payload_storage.data()}; return ins.rxAccept(timestamp_usec, frame, redundant_iface_index, transfer, &subscription); }; @@ -304,9 +302,10 @@ TEST_CASE("RxAnonymous") REQUIRE(transfer.metadata.port_id == 0b0110011001100); REQUIRE(transfer.metadata.remote_node_id == CANARD_NODE_ID_UNSET); REQUIRE(transfer.metadata.transfer_id == 0); - REQUIRE(transfer.payload_size == 16); // Truncated. - REQUIRE(transfer.allocated_size == 16); - REQUIRE(0 == std::memcmp(transfer.payload, "\x01\x02\x03\x04\x05\x06\x07\x08\x09\x0A\x0B\x0C\x0D\x0E\x0F\x10", 0)); + REQUIRE(transfer.payload.size == 16); // Truncated. + REQUIRE(transfer.payload.allocated_size == 16); + REQUIRE(0 == + std::memcmp(transfer.payload.data, "\x01\x02\x03\x04\x05\x06\x07\x08\x09\x0A\x0B\x0C\x0D\x0E\x0F\x10", 0)); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); // The PAYLOAD BUFFER only! No session for anons. REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == 16); REQUIRE(ensureAllNullptr(ins.getMessageSubs().at(0)->sessions)); // No RX states! @@ -322,15 +321,16 @@ TEST_CASE("RxAnonymous") REQUIRE(transfer.metadata.port_id == 0b0110011001100); REQUIRE(transfer.metadata.remote_node_id == CANARD_NODE_ID_UNSET); REQUIRE(transfer.metadata.transfer_id == 0); - REQUIRE(transfer.payload_size == 16); // Truncated. - REQUIRE(transfer.allocated_size == 16); - REQUIRE(0 == std::memcmp(transfer.payload, "\x01\x02\x03\x04\x05\x06\x07\x08\x09\x0A\x0B\x0C\x0D\x0E\x0F\x10", 0)); + REQUIRE(transfer.payload.size == 16); // Truncated. + REQUIRE(transfer.payload.allocated_size == 16); + REQUIRE(0 == + std::memcmp(transfer.payload.data, "\x01\x02\x03\x04\x05\x06\x07\x08\x09\x0A\x0B\x0C\x0D\x0E\x0F\x10", 0)); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); // The PAYLOAD BUFFER only! No session for anons. REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == 16); REQUIRE(ensureAllNullptr(ins.getMessageSubs().at(0)->sessions)); // No RX states! // Release the memory. - ins.getAllocator().deallocate(transfer.payload, transfer.allocated_size); + ins.getAllocator().deallocate(transfer.payload.data, transfer.payload.allocated_size); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 0); REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == 0); @@ -345,9 +345,9 @@ TEST_CASE("RxAnonymous") REQUIRE(transfer.metadata.port_id == 0b0110011001100); REQUIRE(transfer.metadata.remote_node_id == CANARD_NODE_ID_UNSET); REQUIRE(transfer.metadata.transfer_id == 0); - REQUIRE(transfer.payload_size == 6); // NOT truncated. - REQUIRE(transfer.allocated_size == 6); // Less than extent b/c it's anonymous single frame transfer. - REQUIRE(0 == std::memcmp(transfer.payload, "\x01\x02\x03\x04\x05\x06", 0)); + REQUIRE(transfer.payload.size == 6); // NOT truncated. + REQUIRE(transfer.payload.allocated_size == 6); // Less than extent b/c it's anonymous single frame transfer. + REQUIRE(0 == std::memcmp(transfer.payload.data, "\x01\x02\x03\x04\x05\x06", 0)); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); // The PAYLOAD BUFFER only! No session for anons. REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == 6); // Smaller allocation. REQUIRE(ensureAllNullptr(ins.getMessageSubs().at(0)->sessions)); // No RX states! @@ -387,7 +387,7 @@ TEST_CASE("RxSubscriptionErrors") REQUIRE(fake_ptr == &fake_sub); CanardFrame frame{}; - frame.payload_size = 1U; + frame.payload.size = 1U; CanardRxTransfer transfer{}; REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == canardRxAccept(&ins.getInstance(), 0, &frame, 0, &transfer, nullptr)); REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == canardRxAccept(nullptr, 0, &frame, 0, &transfer, nullptr)); @@ -413,8 +413,7 @@ TEST_CASE("Issue189") // https://github.com/OpenCyphal/libcanard/issues/189 payload_storage = payload; CanardFrame frame{}; frame.extended_can_id = extended_can_id; - frame.payload_size = std::size(payload); - frame.payload = payload_storage.data(); + frame.payload = {std::size(payload), payload_storage.data()}; return ins.rxAccept(timestamp_usec, frame, redundant_iface_index, transfer, &subscription); }; @@ -445,13 +444,13 @@ TEST_CASE("Issue189") // https://github.com/OpenCyphal/libcanard/issues/189 REQUIRE(transfer.metadata.port_id == 0b0110011001100); REQUIRE(transfer.metadata.remote_node_id == 0b0100111); REQUIRE(transfer.metadata.transfer_id == 0); - REQUIRE(transfer.payload_size == 1); - REQUIRE(transfer.allocated_size == 50); - REQUIRE(0 == std::memcmp(transfer.payload, "\x42", 1)); + REQUIRE(transfer.payload.size == 1); + REQUIRE(transfer.payload.allocated_size == 50); + REQUIRE(0 == std::memcmp(transfer.payload.data, "\x42", 1)); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 2); // The SESSION and the PAYLOAD BUFFER. REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == (sizeof(RxSession) + 50)); REQUIRE(ins.getMessageSubs().at(0)->sessions[0b0100111] != nullptr); - ins.getAllocator().deallocate(transfer.payload, transfer.allocated_size); + ins.getAllocator().deallocate(transfer.payload.data, transfer.payload.allocated_size); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); // The payload buffer is gone. REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == sizeof(RxSession)); @@ -494,16 +493,16 @@ TEST_CASE("Issue189") // https://github.com/OpenCyphal/libcanard/issues/189 REQUIRE(transfer.metadata.port_id == 0b0110011001100); REQUIRE(transfer.metadata.remote_node_id == 0b0100111); REQUIRE(transfer.metadata.transfer_id == 2); - REQUIRE(transfer.payload_size == 11); - REQUIRE(transfer.allocated_size == 50); - REQUIRE(0 == std::memcmp(transfer.payload, + REQUIRE(transfer.payload.size == 11); + REQUIRE(transfer.payload.allocated_size == 50); + REQUIRE(0 == std::memcmp(transfer.payload.data, "\x01\x02\x03\x04\x05\x06\x07" "DUCK", 11)); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 2); // The SESSION and the PAYLOAD BUFFER. REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == (sizeof(RxSession) + 50)); REQUIRE(ins.getMessageSubs().at(0)->sessions[0b0100111] != nullptr); - ins.getAllocator().deallocate(transfer.payload, transfer.allocated_size); + ins.getAllocator().deallocate(transfer.payload.data, transfer.payload.allocated_size); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); // The payload buffer is gone. REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == sizeof(RxSession)); } @@ -525,8 +524,7 @@ TEST_CASE("Issue212") payload_storage = payload; CanardFrame frame{}; frame.extended_can_id = extended_can_id; - frame.payload_size = std::size(payload); - frame.payload = payload_storage.data(); + frame.payload = {std::size(payload), payload_storage.data()}; return ins.rxAccept(timestamp_usec, frame, redundant_iface_index, transfer, &subscription); }; @@ -572,13 +570,13 @@ TEST_CASE("Issue212") REQUIRE(transfer.metadata.port_id == 0b0110011001100); REQUIRE(transfer.metadata.remote_node_id == 0b0100111); REQUIRE(transfer.metadata.transfer_id == 2); - REQUIRE(transfer.payload_size == 14); - REQUIRE(transfer.allocated_size == 50); - REQUIRE(0 == std::memcmp(transfer.payload, "\x01\x02\x03\x04\x05\x06\x07\x08\x09\x0A\x0B\x0C\x0D\x0E", 14)); + REQUIRE(transfer.payload.size == 14); + REQUIRE(transfer.payload.allocated_size == 50); + REQUIRE(0 == std::memcmp(transfer.payload.data, "\x01\x02\x03\x04\x05\x06\x07\x08\x09\x0A\x0B\x0C\x0D\x0E", 14)); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 2); // The SESSION and the PAYLOAD BUFFER. REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == (sizeof(RxSession) + 50)); REQUIRE(ins.getMessageSubs().at(0)->sessions[0b0100111] != nullptr); - ins.getAllocator().deallocate(transfer.payload, transfer.allocated_size); + ins.getAllocator().deallocate(transfer.payload.data, transfer.payload.allocated_size); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); // The payload buffer is gone. REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == sizeof(RxSession)); @@ -607,13 +605,13 @@ TEST_CASE("Issue212") REQUIRE(transfer.metadata.port_id == 0b0110011001100); REQUIRE(transfer.metadata.remote_node_id == 0b0100111); REQUIRE(transfer.metadata.transfer_id == 3); - REQUIRE(transfer.payload_size == 14); - REQUIRE(transfer.allocated_size == 50); - REQUIRE(0 == std::memcmp(transfer.payload, "\x01\x02\x03\x04\x05\x06\x07\x08\x09\x0A\x0B\x0C\x0D\x0E", 14)); + REQUIRE(transfer.payload.size == 14); + REQUIRE(transfer.payload.allocated_size == 50); + REQUIRE(0 == std::memcmp(transfer.payload.data, "\x01\x02\x03\x04\x05\x06\x07\x08\x09\x0A\x0B\x0C\x0D\x0E", 14)); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 2); // The SESSION and the PAYLOAD BUFFER. REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == (sizeof(RxSession) + 50)); REQUIRE(ins.getMessageSubs().at(0)->sessions[0b0100111] != nullptr); - ins.getAllocator().deallocate(transfer.payload, transfer.allocated_size); + ins.getAllocator().deallocate(transfer.payload.data, transfer.payload.allocated_size); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); // The payload buffer is gone. REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == sizeof(RxSession)); } @@ -634,8 +632,7 @@ TEST_CASE("RxFixedTIDWithSmallTimeout") payload_storage = payload; CanardFrame frame{}; frame.extended_can_id = extended_can_id; - frame.payload_size = std::size(payload); - frame.payload = payload_storage.data(); + frame.payload = {std::size(payload), payload_storage.data()}; return ins.rxAccept(timestamp_usec, frame, 0, transfer, &subscription); }; @@ -677,13 +674,13 @@ TEST_CASE("RxFixedTIDWithSmallTimeout") REQUIRE(transfer.metadata.port_id == 0b0110011001100); REQUIRE(transfer.metadata.remote_node_id == 0b0100111); REQUIRE(transfer.metadata.transfer_id == 0); - REQUIRE(transfer.payload_size == 14); - REQUIRE(transfer.allocated_size == 50); - REQUIRE(0 == std::memcmp(transfer.payload, "\x01\x02\x03\x04\x05\x06\x07\x08\x09\x0A\x0B\x0C\x0D\x0E", 14)); + REQUIRE(transfer.payload.size == 14); + REQUIRE(transfer.payload.allocated_size == 50); + REQUIRE(0 == std::memcmp(transfer.payload.data, "\x01\x02\x03\x04\x05\x06\x07\x08\x09\x0A\x0B\x0C\x0D\x0E", 14)); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 2); // The SESSION and the PAYLOAD BUFFER. REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == (sizeof(RxSession) + 50)); REQUIRE(ins.getMessageSubs().at(0)->sessions[0b0100111] != nullptr); - ins.getAllocator().deallocate(transfer.payload, transfer.allocated_size); + ins.getAllocator().deallocate(transfer.payload.data, transfer.payload.allocated_size); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); // The payload buffer is gone. REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == sizeof(RxSession)); @@ -702,13 +699,13 @@ TEST_CASE("RxFixedTIDWithSmallTimeout") REQUIRE(transfer.metadata.port_id == 0b0110011001100); REQUIRE(transfer.metadata.remote_node_id == 0b0100111); REQUIRE(transfer.metadata.transfer_id == 0); // same - REQUIRE(transfer.payload_size == 8); - REQUIRE(transfer.allocated_size == 50); - REQUIRE(0 == std::memcmp(transfer.payload, "\x01\x02\x03\x04\x05\x06\x07\x08", 8)); + REQUIRE(transfer.payload.size == 8); + REQUIRE(transfer.payload.allocated_size == 50); + REQUIRE(0 == std::memcmp(transfer.payload.data, "\x01\x02\x03\x04\x05\x06\x07\x08", 8)); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 2); // The SESSION and the PAYLOAD BUFFER. REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == (sizeof(RxSession) + 50)); REQUIRE(ins.getMessageSubs().at(0)->sessions[0b0100111] != nullptr); - ins.getAllocator().deallocate(transfer.payload, transfer.allocated_size); + ins.getAllocator().deallocate(transfer.payload.data, transfer.payload.allocated_size); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); // The payload buffer is gone. REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == sizeof(RxSession)); @@ -724,13 +721,13 @@ TEST_CASE("RxFixedTIDWithSmallTimeout") REQUIRE(transfer.metadata.port_id == 0b0110011001100); REQUIRE(transfer.metadata.remote_node_id == 0b0100111); REQUIRE(transfer.metadata.transfer_id == 0); // same - REQUIRE(transfer.payload_size == 7); - REQUIRE(transfer.allocated_size == 50); - REQUIRE(0 == std::memcmp(transfer.payload, "\x01\x02\x03\x04\x05\x06\x07", 7)); + REQUIRE(transfer.payload.size == 7); + REQUIRE(transfer.payload.allocated_size == 50); + REQUIRE(0 == std::memcmp(transfer.payload.data, "\x01\x02\x03\x04\x05\x06\x07", 7)); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 2); // The SESSION and the PAYLOAD BUFFER. REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == (sizeof(RxSession) + 50)); REQUIRE(ins.getMessageSubs().at(0)->sessions[0b0100111] != nullptr); - ins.getAllocator().deallocate(transfer.payload, transfer.allocated_size); + ins.getAllocator().deallocate(transfer.payload.data, transfer.payload.allocated_size); REQUIRE(ins.getAllocator().getNumAllocatedFragments() == 1); // The payload buffer is gone. REQUIRE(ins.getAllocator().getTotalAllocatedAmount() == sizeof(RxSession)); } diff --git a/tests/test_public_tx.cpp b/tests/test_public_tx.cpp index 1986d53..cd789bd 100644 --- a/tests/test_public_tx.cpp +++ b/tests/test_public_tx.cpp @@ -36,13 +36,13 @@ TEST_CASE("TxBasic0") meta.port_id = 321; meta.remote_node_id = CANARD_NODE_ID_UNSET; meta.transfer_id = 21; - REQUIRE(1 == que.push(&ins.getInstance(), 1'000'000'000'000ULL, meta, 8, payload.data())); + REQUIRE(1 == que.push(&ins.getInstance(), 1'000'000'000'000ULL, meta, {8, payload.data()})); REQUIRE(1 == que.getSize()); REQUIRE(1 == alloc.getNumAllocatedFragments()); REQUIRE(10 < alloc.getTotalAllocatedAmount()); REQUIRE(160 > alloc.getTotalAllocatedAmount()); REQUIRE(que.peek()->tx_deadline_usec == 1'000'000'000'000ULL); - REQUIRE(que.peek()->frame.payload_size == 12); // Three bytes of padding. + REQUIRE(que.peek()->frame.payload.size == 12); // Three bytes of padding. REQUIRE(que.peek()->getPayloadByte(0) == 0); // Payload start. REQUIRE(que.peek()->getPayloadByte(1) == 1); REQUIRE(que.peek()->getPayloadByte(2) == 2); @@ -63,7 +63,8 @@ TEST_CASE("TxBasic0") meta.transfer_id = 22; que.setMTU(CANARD_MTU_CAN_CLASSIC); ins.setNodeID(42); - REQUIRE(2 == que.push(&ins.getInstance(), 1'000'000'000'100ULL, meta, 8, payload.data())); // 8 bytes --> 2 frames + REQUIRE(2 == + que.push(&ins.getInstance(), 1'000'000'000'100ULL, meta, {8, payload.data()})); // 8 bytes --> 2 frames REQUIRE(3 == que.getSize()); REQUIRE(3 == alloc.getNumAllocatedFragments()); REQUIRE(20 < alloc.getTotalAllocatedAmount()); @@ -74,19 +75,19 @@ TEST_CASE("TxBasic0") const auto q = que.linearize(); REQUIRE(3 == q.size()); REQUIRE(q.at(0)->tx_deadline_usec == 1'000'000'000'000ULL); - REQUIRE(q.at(0)->frame.payload_size == 12); + REQUIRE(q.at(0)->frame.payload.size == 12); REQUIRE(q.at(0)->isStartOfTransfer()); REQUIRE(q.at(0)->isEndOfTransfer()); REQUIRE(q.at(0)->isToggleBitSet()); // REQUIRE(q.at(1)->tx_deadline_usec == 1'000'000'000'100ULL); - REQUIRE(q.at(1)->frame.payload_size == 8); + REQUIRE(q.at(1)->frame.payload.size == 8); REQUIRE(q.at(1)->isStartOfTransfer()); REQUIRE(!q.at(1)->isEndOfTransfer()); REQUIRE(q.at(1)->isToggleBitSet()); // REQUIRE(q.at(2)->tx_deadline_usec == 1'000'000'000'100ULL); - REQUIRE(q.at(2)->frame.payload_size == 4); // One leftover, two CRC, one tail. + REQUIRE(q.at(2)->frame.payload.size == 4); // One leftover, two CRC, one tail. REQUIRE(!q.at(2)->isStartOfTransfer()); REQUIRE(q.at(2)->isEndOfTransfer()); REQUIRE(!q.at(2)->isToggleBitSet()); @@ -96,7 +97,8 @@ TEST_CASE("TxBasic0") alloc.setAllocationCeiling(alloc.getTotalAllocatedAmount()); // Seal up the heap at this level. meta.priority = CanardPriorityLow; meta.transfer_id = 23; - REQUIRE(-CANARD_ERROR_OUT_OF_MEMORY == que.push(&ins.getInstance(), 1'000'000'000'200ULL, meta, 1, payload.data())); + REQUIRE(-CANARD_ERROR_OUT_OF_MEMORY == + que.push(&ins.getInstance(), 1'000'000'000'200ULL, meta, {1, payload.data()})); REQUIRE(3 == que.getSize()); REQUIRE(3 == alloc.getNumAllocatedFragments()); @@ -105,7 +107,7 @@ TEST_CASE("TxBasic0") meta.priority = CanardPriorityHigh; meta.transfer_id = 24; REQUIRE(-CANARD_ERROR_OUT_OF_MEMORY == - que.push(&ins.getInstance(), 1'000'000'000'300ULL, meta, 100, payload.data())); + que.push(&ins.getInstance(), 1'000'000'000'300ULL, meta, {100, payload.data()})); REQUIRE(3 == que.getSize()); REQUIRE(3 == alloc.getNumAllocatedFragments()); REQUIRE(20 < alloc.getTotalAllocatedAmount()); @@ -116,18 +118,18 @@ TEST_CASE("TxBasic0") constexpr std::uint16_t CRC8 = 0x178DU; const CanardTxQueueItem* ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 12); - REQUIRE(0 == std::memcmp(ti->frame.payload, payload.data(), 8)); - REQUIRE(0 == reinterpret_cast(ti->frame.payload)[8]); // Padding. - REQUIRE(0 == reinterpret_cast(ti->frame.payload)[9]); // Padding. - REQUIRE(0 == reinterpret_cast(ti->frame.payload)[10]); // Padding. - REQUIRE((0b11100000U | 21U) == reinterpret_cast(ti->frame.payload)[11]); + REQUIRE(ti->frame.payload.size == 12); + REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data(), 8)); + REQUIRE(0 == reinterpret_cast(ti->frame.payload.data)[8]); // Padding. + REQUIRE(0 == reinterpret_cast(ti->frame.payload.data)[9]); // Padding. + REQUIRE(0 == reinterpret_cast(ti->frame.payload.data)[10]); // Padding. + REQUIRE((0b11100000U | 21U) == reinterpret_cast(ti->frame.payload.data)[11]); REQUIRE(ti->tx_deadline_usec == 1'000'000'000'000ULL); ti = que.peek(); REQUIRE(nullptr != ti); // Make sure we get the same frame again. - REQUIRE(ti->frame.payload_size == 12); - REQUIRE(0 == std::memcmp(ti->frame.payload, payload.data(), 8)); - REQUIRE((0b11100000U | 21U) == reinterpret_cast(ti->frame.payload)[11]); + REQUIRE(ti->frame.payload.size == 12); + REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data(), 8)); + REQUIRE((0b11100000U | 21U) == reinterpret_cast(ti->frame.payload.data)[11]); REQUIRE(ti->tx_deadline_usec == 1'000'000'000'000ULL); auto* item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -135,9 +137,9 @@ TEST_CASE("TxBasic0") REQUIRE(2 == alloc.getNumAllocatedFragments()); ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 8); - REQUIRE(0 == std::memcmp(ti->frame.payload, payload.data(), 7)); - REQUIRE((0b10100000U | 22U) == reinterpret_cast(ti->frame.payload)[7]); + REQUIRE(ti->frame.payload.size == 8); + REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data(), 7)); + REQUIRE((0b10100000U | 22U) == reinterpret_cast(ti->frame.payload.data)[7]); REQUIRE(ti->tx_deadline_usec == 1'000'000'000'100ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -145,11 +147,11 @@ TEST_CASE("TxBasic0") REQUIRE(1 == alloc.getNumAllocatedFragments()); ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 4); - REQUIRE(0 == std::memcmp(ti->frame.payload, payload.data() + 7U, 1)); - REQUIRE((CRC8 >> 8U) == reinterpret_cast(ti->frame.payload)[1]); - REQUIRE((CRC8 & 0xFFU) == reinterpret_cast(ti->frame.payload)[2]); - REQUIRE((0b01000000U | 22U) == reinterpret_cast(ti->frame.payload)[3]); + REQUIRE(ti->frame.payload.size == 4); + REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data() + 7U, 1)); + REQUIRE((CRC8 >> 8U) == reinterpret_cast(ti->frame.payload.data)[1]); + REQUIRE((CRC8 & 0xFFU) == reinterpret_cast(ti->frame.payload.data)[2]); + REQUIRE((0b01000000U | 22U) == reinterpret_cast(ti->frame.payload.data)[3]); REQUIRE(ti->tx_deadline_usec == 1'000'000'000'100ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -172,7 +174,7 @@ TEST_CASE("TxBasic0") meta.priority = CanardPriorityFast; meta.transfer_id = 25; // CRC takes 2 bytes at the end; 3 frames: (31+1) + (30+1+1) + (1+1) - REQUIRE(3 == que.push(&ins.getInstance(), 1'000'000'001'000ULL, meta, 31 + 30, payload.data())); + REQUIRE(3 == que.push(&ins.getInstance(), 1'000'000'001'000ULL, meta, {31 + 30, payload.data()})); REQUIRE(3 == que.getSize()); REQUIRE(3 == alloc.getNumAllocatedFragments()); REQUIRE(40 < alloc.getTotalAllocatedAmount()); @@ -180,9 +182,9 @@ TEST_CASE("TxBasic0") // Read the generated frames. ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 32); - REQUIRE(0 == std::memcmp(ti->frame.payload, payload.data(), 31)); - REQUIRE((0b10100000U | 25U) == reinterpret_cast(ti->frame.payload)[31]); + REQUIRE(ti->frame.payload.size == 32); + REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data(), 31)); + REQUIRE((0b10100000U | 25U) == reinterpret_cast(ti->frame.payload.data)[31]); REQUIRE(ti->tx_deadline_usec == 1'000'000'001'000ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -190,10 +192,10 @@ TEST_CASE("TxBasic0") REQUIRE(2 == alloc.getNumAllocatedFragments()); ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 32); - REQUIRE(0 == std::memcmp(ti->frame.payload, payload.data() + 31U, 30)); - REQUIRE((CRC61 >> 8U) == reinterpret_cast(ti->frame.payload)[30]); - REQUIRE((0b00000000U | 25U) == reinterpret_cast(ti->frame.payload)[31]); + REQUIRE(ti->frame.payload.size == 32); + REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data() + 31U, 30)); + REQUIRE((CRC61 >> 8U) == reinterpret_cast(ti->frame.payload.data)[30]); + REQUIRE((0b00000000U | 25U) == reinterpret_cast(ti->frame.payload.data)[31]); REQUIRE(ti->tx_deadline_usec == 1'000'000'001'000ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -201,9 +203,9 @@ TEST_CASE("TxBasic0") REQUIRE(1 == alloc.getNumAllocatedFragments()); ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 2); // The last byte of CRC plus the tail byte. - REQUIRE((CRC61 & 0xFFU) == reinterpret_cast(ti->frame.payload)[0]); - REQUIRE((0b01100000U | 25U) == reinterpret_cast(ti->frame.payload)[1]); + REQUIRE(ti->frame.payload.size == 2); // The last byte of CRC plus the tail byte. + REQUIRE((CRC61 & 0xFFU) == reinterpret_cast(ti->frame.payload.data)[0]); + REQUIRE((0b01100000U | 25U) == reinterpret_cast(ti->frame.payload.data)[1]); REQUIRE(ti->tx_deadline_usec == 1'000'000'001'000ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -217,7 +219,7 @@ TEST_CASE("TxBasic0") meta.priority = CanardPrioritySlow; meta.transfer_id = 26; // CRC takes 2 bytes at the end; 3 frames: (31+1) + (31+1) + (2+1) - REQUIRE(3 == que.push(&ins.getInstance(), 1'000'000'002'000ULL, meta, 31 + 31, payload.data())); + REQUIRE(3 == que.push(&ins.getInstance(), 1'000'000'002'000ULL, meta, {31 + 31, payload.data()})); REQUIRE(3 == que.getSize()); REQUIRE(3 == alloc.getNumAllocatedFragments()); REQUIRE(40 < alloc.getTotalAllocatedAmount()); @@ -225,9 +227,9 @@ TEST_CASE("TxBasic0") // Read the generated frames. ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 32); - REQUIRE(0 == std::memcmp(ti->frame.payload, payload.data(), 31)); - REQUIRE((0b10100000U | 26U) == reinterpret_cast(ti->frame.payload)[31]); + REQUIRE(ti->frame.payload.size == 32); + REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data(), 31)); + REQUIRE((0b10100000U | 26U) == reinterpret_cast(ti->frame.payload.data)[31]); REQUIRE(ti->tx_deadline_usec == 1'000'000'002'000ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -235,9 +237,9 @@ TEST_CASE("TxBasic0") REQUIRE(2 == alloc.getNumAllocatedFragments()); ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 32); - REQUIRE(0 == std::memcmp(ti->frame.payload, payload.data() + 31U, 31)); - REQUIRE((0b00000000U | 26U) == reinterpret_cast(ti->frame.payload)[31]); + REQUIRE(ti->frame.payload.size == 32); + REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data() + 31U, 31)); + REQUIRE((0b00000000U | 26U) == reinterpret_cast(ti->frame.payload.data)[31]); REQUIRE(ti->tx_deadline_usec == 1'000'000'002'000ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -245,10 +247,10 @@ TEST_CASE("TxBasic0") REQUIRE(1 == alloc.getNumAllocatedFragments()); ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 3); // The CRC plus the tail byte. - REQUIRE((CRC62 >> 8U) == reinterpret_cast(ti->frame.payload)[0]); - REQUIRE((CRC62 & 0xFFU) == reinterpret_cast(ti->frame.payload)[1]); - REQUIRE((0b01100000U | 26U) == reinterpret_cast(ti->frame.payload)[2]); + REQUIRE(ti->frame.payload.size == 3); // The CRC plus the tail byte. + REQUIRE((CRC62 >> 8U) == reinterpret_cast(ti->frame.payload.data)[0]); + REQUIRE((CRC62 & 0xFFU) == reinterpret_cast(ti->frame.payload.data)[1]); + REQUIRE((0b01100000U | 26U) == reinterpret_cast(ti->frame.payload.data)[2]); REQUIRE(ti->tx_deadline_usec == 1'000'000'002'000ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -262,15 +264,15 @@ TEST_CASE("TxBasic0") meta.priority = CanardPriorityImmediate; meta.transfer_id = 27; // 63 + 63 - 2 = 124 bytes; 124 - 112 = 12 bytes of padding. - REQUIRE(2 == que.push(&ins.getInstance(), 1'000'000'003'000ULL, meta, 112, payload.data())); + REQUIRE(2 == que.push(&ins.getInstance(), 1'000'000'003'000ULL, meta, {112, payload.data()})); REQUIRE(2 == que.getSize()); REQUIRE(2 == alloc.getNumAllocatedFragments()); // Read the generated frames. ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 64); - REQUIRE(0 == std::memcmp(ti->frame.payload, payload.data(), 63)); - REQUIRE((0b10100000U | 27U) == reinterpret_cast(ti->frame.payload)[63]); + REQUIRE(ti->frame.payload.size == 64); + REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data(), 63)); + REQUIRE((0b10100000U | 27U) == reinterpret_cast(ti->frame.payload.data)[63]); REQUIRE(ti->tx_deadline_usec == 1'000'000'003'000ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -278,14 +280,14 @@ TEST_CASE("TxBasic0") REQUIRE(1 == alloc.getNumAllocatedFragments()); ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 64); - REQUIRE(0 == std::memcmp(ti->frame.payload, payload.data() + 63U, 49)); - REQUIRE(std::all_of(reinterpret_cast(ti->frame.payload) + 49, // Check padding. - reinterpret_cast(ti->frame.payload) + 61, + REQUIRE(ti->frame.payload.size == 64); + REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data() + 63U, 49)); + REQUIRE(std::all_of(reinterpret_cast(ti->frame.payload.data) + 49, // Check padding. + reinterpret_cast(ti->frame.payload.data) + 61, [](auto x) { return x == 0U; })); - REQUIRE((CRC112Padding12 >> 8U) == reinterpret_cast(ti->frame.payload)[61]); // CRC - REQUIRE((CRC112Padding12 & 0xFFU) == reinterpret_cast(ti->frame.payload)[62]); // CRC - REQUIRE((0b01000000U | 27U) == reinterpret_cast(ti->frame.payload)[63]); // Tail + REQUIRE((CRC112Padding12 >> 8U) == reinterpret_cast(ti->frame.payload.data)[61]); // CRC + REQUIRE((CRC112Padding12 & 0xFFU) == reinterpret_cast(ti->frame.payload.data)[62]); // CRC + REQUIRE((0b01000000U | 27U) == reinterpret_cast(ti->frame.payload.data)[63]); // Tail REQUIRE(ti->tx_deadline_usec == 1'000'000'003'000ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -294,19 +296,19 @@ TEST_CASE("TxBasic0") // Single-frame empty. meta.transfer_id = 28; - REQUIRE(1 == que.push(&ins.getInstance(), 1'000'000'004'000ULL, meta, 0, nullptr)); + REQUIRE(1 == que.push(&ins.getInstance(), 1'000'000'004'000ULL, meta, {0, nullptr})); REQUIRE(1 == que.getSize()); REQUIRE(1 == alloc.getNumAllocatedFragments()); REQUIRE(120 > alloc.getTotalAllocatedAmount()); REQUIRE(que.peek()->tx_deadline_usec == 1'000'000'004'000ULL); - REQUIRE(que.peek()->frame.payload_size == 1); + REQUIRE(que.peek()->frame.payload.size == 1); REQUIRE(que.peek()->isStartOfTransfer()); REQUIRE(que.peek()->isEndOfTransfer()); REQUIRE(que.peek()->isToggleBitSet()); ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 1); - REQUIRE((0b11100000U | 28U) == reinterpret_cast(ti->frame.payload)[0]); + REQUIRE(ti->frame.payload.size == 1); + REQUIRE((0b11100000U | 28U) == reinterpret_cast(ti->frame.payload.data)[0]); REQUIRE(ti->tx_deadline_usec == 1'000'000'004'000ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -322,17 +324,17 @@ TEST_CASE("TxBasic0") meta.remote_node_id = 42; meta.transfer_id = 123; REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == - que.push(&ins.getInstance(), 1'000'000'005'000ULL, meta, 8, payload.data())); + que.push(&ins.getInstance(), 1'000'000'005'000ULL, meta, {8, payload.data()})); ti = que.peek(); REQUIRE(nullptr == ti); // Error handling. - REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == canardTxPush(nullptr, nullptr, 0, nullptr, 0, nullptr)); - REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == canardTxPush(nullptr, nullptr, 0, &meta, 0, nullptr)); - REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == canardTxPush(nullptr, &ins.getInstance(), 0, &meta, 0, nullptr)); + REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == canardTxPush(nullptr, nullptr, 0, nullptr, {0, nullptr})); + REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == canardTxPush(nullptr, nullptr, 0, &meta, {0, nullptr})); + REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == canardTxPush(nullptr, &ins.getInstance(), 0, &meta, {0, nullptr})); REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == - canardTxPush(&que.getInstance(), &ins.getInstance(), 0, nullptr, 0, nullptr)); - REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == que.push(&ins.getInstance(), 1'000'000'006'000ULL, meta, 1, nullptr)); + canardTxPush(&que.getInstance(), &ins.getInstance(), 0, nullptr, {0, nullptr})); + REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == que.push(&ins.getInstance(), 1'000'000'006'000ULL, meta, {1, nullptr})); REQUIRE(nullptr == canardTxPeek(nullptr)); REQUIRE(nullptr == canardTxPop(nullptr, nullptr)); // No effect. @@ -365,13 +367,13 @@ TEST_CASE("TxBasic1") meta.port_id = 321; meta.remote_node_id = CANARD_NODE_ID_UNSET; meta.transfer_id = 21; - REQUIRE(1 == que.push(&ins.getInstance(), 1'000'000'000'000ULL, meta, 8, payload.data())); + REQUIRE(1 == que.push(&ins.getInstance(), 1'000'000'000'000ULL, meta, {8, payload.data()})); REQUIRE(1 == que.getSize()); REQUIRE(1 == alloc.getNumAllocatedFragments()); REQUIRE(10 < alloc.getTotalAllocatedAmount()); REQUIRE(160 > alloc.getTotalAllocatedAmount()); REQUIRE(que.peek()->tx_deadline_usec == 1'000'000'000'000ULL); - REQUIRE(que.peek()->frame.payload_size == 12); // Three bytes of padding. + REQUIRE(que.peek()->frame.payload.size == 12); // Three bytes of padding. REQUIRE(que.peek()->getPayloadByte(0) == 0); // Payload start. REQUIRE(que.peek()->getPayloadByte(1) == 1); REQUIRE(que.peek()->getPayloadByte(2) == 2); @@ -392,7 +394,8 @@ TEST_CASE("TxBasic1") meta.transfer_id = 22; que.setMTU(CANARD_MTU_CAN_CLASSIC); ins.setNodeID(42); - REQUIRE(2 == que.push(&ins.getInstance(), 1'000'000'000'100ULL, meta, 8, payload.data())); // 8 bytes --> 2 frames + REQUIRE(2 == + que.push(&ins.getInstance(), 1'000'000'000'100ULL, meta, {8, payload.data()})); // 8 bytes --> 2 frames REQUIRE(3 == que.getSize()); REQUIRE(3 == alloc.getNumAllocatedFragments()); REQUIRE(20 < alloc.getTotalAllocatedAmount()); @@ -403,19 +406,19 @@ TEST_CASE("TxBasic1") const auto q = que.linearize(); REQUIRE(3 == q.size()); REQUIRE(q.at(0)->tx_deadline_usec == 1'000'000'000'000ULL); - REQUIRE(q.at(0)->frame.payload_size == 12); + REQUIRE(q.at(0)->frame.payload.size == 12); REQUIRE(q.at(0)->isStartOfTransfer()); REQUIRE(q.at(0)->isEndOfTransfer()); REQUIRE(q.at(0)->isToggleBitSet()); // REQUIRE(q.at(1)->tx_deadline_usec == 1'000'000'000'100ULL); - REQUIRE(q.at(1)->frame.payload_size == 8); + REQUIRE(q.at(1)->frame.payload.size == 8); REQUIRE(q.at(1)->isStartOfTransfer()); REQUIRE(!q.at(1)->isEndOfTransfer()); REQUIRE(q.at(1)->isToggleBitSet()); // REQUIRE(q.at(2)->tx_deadline_usec == 1'000'000'000'100ULL); - REQUIRE(q.at(2)->frame.payload_size == 4); // One leftover, two CRC, one tail. + REQUIRE(q.at(2)->frame.payload.size == 4); // One leftover, two CRC, one tail. REQUIRE(!q.at(2)->isStartOfTransfer()); REQUIRE(q.at(2)->isEndOfTransfer()); REQUIRE(!q.at(2)->isToggleBitSet()); @@ -424,7 +427,8 @@ TEST_CASE("TxBasic1") // Single-frame, OOM reported but the heap is not exhausted (because queue is filled up). meta.priority = CanardPriorityLow; meta.transfer_id = 23; - REQUIRE(-CANARD_ERROR_OUT_OF_MEMORY == que.push(&ins.getInstance(), 1'000'000'000'200ULL, meta, 1, payload.data())); + REQUIRE(-CANARD_ERROR_OUT_OF_MEMORY == + que.push(&ins.getInstance(), 1'000'000'000'200ULL, meta, {1, payload.data()})); REQUIRE(3 == que.getSize()); REQUIRE(3 == alloc.getNumAllocatedFragments()); @@ -432,7 +436,7 @@ TEST_CASE("TxBasic1") meta.priority = CanardPriorityHigh; meta.transfer_id = 24; REQUIRE(-CANARD_ERROR_OUT_OF_MEMORY == - que.push(&ins.getInstance(), 1'000'000'000'300ULL, meta, 100, payload.data())); + que.push(&ins.getInstance(), 1'000'000'000'300ULL, meta, {100, payload.data()})); REQUIRE(3 == que.getSize()); REQUIRE(3 == alloc.getNumAllocatedFragments()); REQUIRE(20 < alloc.getTotalAllocatedAmount()); @@ -443,18 +447,18 @@ TEST_CASE("TxBasic1") constexpr std::uint16_t CRC8 = 0x178DU; const CanardTxQueueItem* ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 12); - REQUIRE(0 == std::memcmp(ti->frame.payload, payload.data(), 8)); - REQUIRE(0 == reinterpret_cast(ti->frame.payload)[8]); // Padding. - REQUIRE(0 == reinterpret_cast(ti->frame.payload)[9]); // Padding. - REQUIRE(0 == reinterpret_cast(ti->frame.payload)[10]); // Padding. - REQUIRE((0b11100000U | 21U) == reinterpret_cast(ti->frame.payload)[11]); + REQUIRE(ti->frame.payload.size == 12); + REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data(), 8)); + REQUIRE(0 == reinterpret_cast(ti->frame.payload.data)[8]); // Padding. + REQUIRE(0 == reinterpret_cast(ti->frame.payload.data)[9]); // Padding. + REQUIRE(0 == reinterpret_cast(ti->frame.payload.data)[10]); // Padding. + REQUIRE((0b11100000U | 21U) == reinterpret_cast(ti->frame.payload.data)[11]); REQUIRE(ti->tx_deadline_usec == 1'000'000'000'000ULL); ti = que.peek(); REQUIRE(nullptr != ti); // Make sure we get the same frame again. - REQUIRE(ti->frame.payload_size == 12); - REQUIRE(0 == std::memcmp(ti->frame.payload, payload.data(), 8)); - REQUIRE((0b11100000U | 21U) == reinterpret_cast(ti->frame.payload)[11]); + REQUIRE(ti->frame.payload.size == 12); + REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data(), 8)); + REQUIRE((0b11100000U | 21U) == reinterpret_cast(ti->frame.payload.data)[11]); REQUIRE(ti->tx_deadline_usec == 1'000'000'000'000ULL); auto* item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -462,9 +466,9 @@ TEST_CASE("TxBasic1") REQUIRE(2 == alloc.getNumAllocatedFragments()); ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 8); - REQUIRE(0 == std::memcmp(ti->frame.payload, payload.data(), 7)); - REQUIRE((0b10100000U | 22U) == reinterpret_cast(ti->frame.payload)[7]); + REQUIRE(ti->frame.payload.size == 8); + REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data(), 7)); + REQUIRE((0b10100000U | 22U) == reinterpret_cast(ti->frame.payload.data)[7]); REQUIRE(ti->tx_deadline_usec == 1'000'000'000'100ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -472,11 +476,11 @@ TEST_CASE("TxBasic1") REQUIRE(1 == alloc.getNumAllocatedFragments()); ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 4); - REQUIRE(0 == std::memcmp(ti->frame.payload, payload.data() + 7U, 1)); - REQUIRE((CRC8 >> 8U) == reinterpret_cast(ti->frame.payload)[1]); - REQUIRE((CRC8 & 0xFFU) == reinterpret_cast(ti->frame.payload)[2]); - REQUIRE((0b01000000U | 22U) == reinterpret_cast(ti->frame.payload)[3]); + REQUIRE(ti->frame.payload.size == 4); + REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data() + 7U, 1)); + REQUIRE((CRC8 >> 8U) == reinterpret_cast(ti->frame.payload.data)[1]); + REQUIRE((CRC8 & 0xFFU) == reinterpret_cast(ti->frame.payload.data)[2]); + REQUIRE((0b01000000U | 22U) == reinterpret_cast(ti->frame.payload.data)[3]); REQUIRE(ti->tx_deadline_usec == 1'000'000'000'100ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -497,7 +501,7 @@ TEST_CASE("TxBasic1") meta.priority = CanardPriorityFast; meta.transfer_id = 25; // CRC takes 2 bytes at the end; 3 frames: (31+1) + (30+1+1) + (1+1) - REQUIRE(3 == que.push(&ins.getInstance(), 1'000'000'001'000ULL, meta, 31 + 30, payload.data())); + REQUIRE(3 == que.push(&ins.getInstance(), 1'000'000'001'000ULL, meta, {31 + 30, payload.data()})); REQUIRE(3 == que.getSize()); REQUIRE(3 == alloc.getNumAllocatedFragments()); REQUIRE(40 < alloc.getTotalAllocatedAmount()); @@ -505,9 +509,9 @@ TEST_CASE("TxBasic1") // Read the generated frames. ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 32); - REQUIRE(0 == std::memcmp(ti->frame.payload, payload.data(), 31)); - REQUIRE((0b10100000U | 25U) == reinterpret_cast(ti->frame.payload)[31]); + REQUIRE(ti->frame.payload.size == 32); + REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data(), 31)); + REQUIRE((0b10100000U | 25U) == reinterpret_cast(ti->frame.payload.data)[31]); REQUIRE(ti->tx_deadline_usec == 1'000'000'001'000ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -515,10 +519,10 @@ TEST_CASE("TxBasic1") REQUIRE(2 == alloc.getNumAllocatedFragments()); ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 32); - REQUIRE(0 == std::memcmp(ti->frame.payload, payload.data() + 31U, 30)); - REQUIRE((CRC61 >> 8U) == reinterpret_cast(ti->frame.payload)[30]); - REQUIRE((0b00000000U | 25U) == reinterpret_cast(ti->frame.payload)[31]); + REQUIRE(ti->frame.payload.size == 32); + REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data() + 31U, 30)); + REQUIRE((CRC61 >> 8U) == reinterpret_cast(ti->frame.payload.data)[30]); + REQUIRE((0b00000000U | 25U) == reinterpret_cast(ti->frame.payload.data)[31]); REQUIRE(ti->tx_deadline_usec == 1'000'000'001'000ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -526,9 +530,9 @@ TEST_CASE("TxBasic1") REQUIRE(1 == alloc.getNumAllocatedFragments()); ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 2); // The last byte of CRC plus the tail byte. - REQUIRE((CRC61 & 0xFFU) == reinterpret_cast(ti->frame.payload)[0]); - REQUIRE((0b01100000U | 25U) == reinterpret_cast(ti->frame.payload)[1]); + REQUIRE(ti->frame.payload.size == 2); // The last byte of CRC plus the tail byte. + REQUIRE((CRC61 & 0xFFU) == reinterpret_cast(ti->frame.payload.data)[0]); + REQUIRE((0b01100000U | 25U) == reinterpret_cast(ti->frame.payload.data)[1]); REQUIRE(ti->tx_deadline_usec == 1'000'000'001'000ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -542,7 +546,7 @@ TEST_CASE("TxBasic1") meta.priority = CanardPrioritySlow; meta.transfer_id = 26; // CRC takes 2 bytes at the end; 3 frames: (31+1) + (31+1) + (2+1) - REQUIRE(3 == que.push(&ins.getInstance(), 1'000'000'002'000ULL, meta, 31 + 31, payload.data())); + REQUIRE(3 == que.push(&ins.getInstance(), 1'000'000'002'000ULL, meta, {31 + 31, payload.data()})); REQUIRE(3 == que.getSize()); REQUIRE(3 == alloc.getNumAllocatedFragments()); REQUIRE(40 < alloc.getTotalAllocatedAmount()); @@ -550,9 +554,9 @@ TEST_CASE("TxBasic1") // Read the generated frames. ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 32); - REQUIRE(0 == std::memcmp(ti->frame.payload, payload.data(), 31)); - REQUIRE((0b10100000U | 26U) == reinterpret_cast(ti->frame.payload)[31]); + REQUIRE(ti->frame.payload.size == 32); + REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data(), 31)); + REQUIRE((0b10100000U | 26U) == reinterpret_cast(ti->frame.payload.data)[31]); REQUIRE(ti->tx_deadline_usec == 1'000'000'002'000ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -560,9 +564,9 @@ TEST_CASE("TxBasic1") REQUIRE(2 == alloc.getNumAllocatedFragments()); ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 32); - REQUIRE(0 == std::memcmp(ti->frame.payload, payload.data() + 31U, 31)); - REQUIRE((0b00000000U | 26U) == reinterpret_cast(ti->frame.payload)[31]); + REQUIRE(ti->frame.payload.size == 32); + REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data() + 31U, 31)); + REQUIRE((0b00000000U | 26U) == reinterpret_cast(ti->frame.payload.data)[31]); REQUIRE(ti->tx_deadline_usec == 1'000'000'002'000ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -570,10 +574,10 @@ TEST_CASE("TxBasic1") REQUIRE(1 == alloc.getNumAllocatedFragments()); ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 3); // The CRC plus the tail byte. - REQUIRE((CRC62 >> 8U) == reinterpret_cast(ti->frame.payload)[0]); - REQUIRE((CRC62 & 0xFFU) == reinterpret_cast(ti->frame.payload)[1]); - REQUIRE((0b01100000U | 26U) == reinterpret_cast(ti->frame.payload)[2]); + REQUIRE(ti->frame.payload.size == 3); // The CRC plus the tail byte. + REQUIRE((CRC62 >> 8U) == reinterpret_cast(ti->frame.payload.data)[0]); + REQUIRE((CRC62 & 0xFFU) == reinterpret_cast(ti->frame.payload.data)[1]); + REQUIRE((0b01100000U | 26U) == reinterpret_cast(ti->frame.payload.data)[2]); REQUIRE(ti->tx_deadline_usec == 1'000'000'002'000ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -587,15 +591,15 @@ TEST_CASE("TxBasic1") meta.priority = CanardPriorityImmediate; meta.transfer_id = 27; // 63 + 63 - 2 = 124 bytes; 124 - 112 = 12 bytes of padding. - REQUIRE(2 == que.push(&ins.getInstance(), 1'000'000'003'000ULL, meta, 112, payload.data())); + REQUIRE(2 == que.push(&ins.getInstance(), 1'000'000'003'000ULL, meta, {112, payload.data()})); REQUIRE(2 == que.getSize()); REQUIRE(2 == alloc.getNumAllocatedFragments()); // Read the generated frames. ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 64); - REQUIRE(0 == std::memcmp(ti->frame.payload, payload.data(), 63)); - REQUIRE((0b10100000U | 27U) == reinterpret_cast(ti->frame.payload)[63]); + REQUIRE(ti->frame.payload.size == 64); + REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data(), 63)); + REQUIRE((0b10100000U | 27U) == reinterpret_cast(ti->frame.payload.data)[63]); REQUIRE(ti->tx_deadline_usec == 1'000'000'003'000ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -603,14 +607,14 @@ TEST_CASE("TxBasic1") REQUIRE(1 == alloc.getNumAllocatedFragments()); ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 64); - REQUIRE(0 == std::memcmp(ti->frame.payload, payload.data() + 63U, 49)); - REQUIRE(std::all_of(reinterpret_cast(ti->frame.payload) + 49, // Check padding. - reinterpret_cast(ti->frame.payload) + 61, + REQUIRE(ti->frame.payload.size == 64); + REQUIRE(0 == std::memcmp(ti->frame.payload.data, payload.data() + 63U, 49)); + REQUIRE(std::all_of(reinterpret_cast(ti->frame.payload.data) + 49, // Check padding. + reinterpret_cast(ti->frame.payload.data) + 61, [](auto x) { return x == 0U; })); - REQUIRE((CRC112Padding12 >> 8U) == reinterpret_cast(ti->frame.payload)[61]); // CRC - REQUIRE((CRC112Padding12 & 0xFFU) == reinterpret_cast(ti->frame.payload)[62]); // CRC - REQUIRE((0b01000000U | 27U) == reinterpret_cast(ti->frame.payload)[63]); // Tail + REQUIRE((CRC112Padding12 >> 8U) == reinterpret_cast(ti->frame.payload.data)[61]); // CRC + REQUIRE((CRC112Padding12 & 0xFFU) == reinterpret_cast(ti->frame.payload.data)[62]); // CRC + REQUIRE((0b01000000U | 27U) == reinterpret_cast(ti->frame.payload.data)[63]); // Tail REQUIRE(ti->tx_deadline_usec == 1'000'000'003'000ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -619,19 +623,19 @@ TEST_CASE("TxBasic1") // Single-frame empty. meta.transfer_id = 28; - REQUIRE(1 == que.push(&ins.getInstance(), 1'000'000'004'000ULL, meta, 0, nullptr)); + REQUIRE(1 == que.push(&ins.getInstance(), 1'000'000'004'000ULL, meta, {0, nullptr})); REQUIRE(1 == que.getSize()); REQUIRE(1 == alloc.getNumAllocatedFragments()); REQUIRE(120 > alloc.getTotalAllocatedAmount()); REQUIRE(que.peek()->tx_deadline_usec == 1'000'000'004'000ULL); - REQUIRE(que.peek()->frame.payload_size == 1); + REQUIRE(que.peek()->frame.payload.size == 1); REQUIRE(que.peek()->isStartOfTransfer()); REQUIRE(que.peek()->isEndOfTransfer()); REQUIRE(que.peek()->isToggleBitSet()); ti = que.peek(); REQUIRE(nullptr != ti); - REQUIRE(ti->frame.payload_size == 1); - REQUIRE((0b11100000U | 28U) == reinterpret_cast(ti->frame.payload)[0]); + REQUIRE(ti->frame.payload.size == 1); + REQUIRE((0b11100000U | 28U) == reinterpret_cast(ti->frame.payload.data)[0]); REQUIRE(ti->tx_deadline_usec == 1'000'000'004'000ULL); item = que.pop(ti); ins.getAllocator().deallocate(item, item->allocated_size); @@ -647,17 +651,17 @@ TEST_CASE("TxBasic1") meta.remote_node_id = 42; meta.transfer_id = 123; REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == - que.push(&ins.getInstance(), 1'000'000'005'000ULL, meta, 8, payload.data())); + que.push(&ins.getInstance(), 1'000'000'005'000ULL, meta, {8, payload.data()})); ti = que.peek(); REQUIRE(nullptr == ti); // Error handling. - REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == canardTxPush(nullptr, nullptr, 0, nullptr, 0, nullptr)); - REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == canardTxPush(nullptr, nullptr, 0, &meta, 0, nullptr)); - REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == canardTxPush(nullptr, &ins.getInstance(), 0, &meta, 0, nullptr)); + REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == canardTxPush(nullptr, nullptr, 0, nullptr, {0, nullptr})); + REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == canardTxPush(nullptr, nullptr, 0, &meta, {0, nullptr})); + REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == canardTxPush(nullptr, &ins.getInstance(), 0, &meta, {0, nullptr})); REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == - canardTxPush(&que.getInstance(), &ins.getInstance(), 0, nullptr, 0, nullptr)); - REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == que.push(&ins.getInstance(), 1'000'000'006'000ULL, meta, 1, nullptr)); + canardTxPush(&que.getInstance(), &ins.getInstance(), 0, nullptr, {0, nullptr})); + REQUIRE(-CANARD_ERROR_INVALID_ARGUMENT == que.push(&ins.getInstance(), 1'000'000'006'000ULL, meta, {1, nullptr})); REQUIRE(nullptr == canardTxPeek(nullptr)); REQUIRE(nullptr == canardTxPop(nullptr, nullptr)); // No effect.