diff --git a/.clang-tidy b/.clang-tidy new file mode 100644 index 00000000..bd04775b --- /dev/null +++ b/.clang-tidy @@ -0,0 +1,32 @@ +--- +Checks: >- + boost-*, + bugprone-*, + cert-*, + clang-analyzer-*, + cppcoreguidelines-*, + google-*, + hicpp-*, + llvm-*, + misc-*, + modernize-*, + performance-*, + portability-*, + readability-*, + -google-readability-todo, + -readability-avoid-const-params-in-decls, + -readability-identifier-length, + -bugprone-easily-swappable-parameters, + -llvm-header-guard, + -cert-dcl03-c, + -hicpp-static-assert, + -misc-static-assert, + -modernize-macro-to-enum, +CheckOptions: + - key: readability-function-cognitive-complexity.Threshold + value: '99' +WarningsAsErrors: '*' +HeaderFilterRegex: '.*' +AnalyzeTemporaryDtors: false +FormatStyle: file +... diff --git a/_canard_cavl.h b/_canard_cavl.h new file mode 100644 index 00000000..79f89d94 --- /dev/null +++ b/_canard_cavl.h @@ -0,0 +1,337 @@ +/// Source: https://github.com/pavel-kirienko/cavl +/// +/// Cavl is a single-header C library providing an implementation of AVL tree suitable for deeply embedded systems. +/// To integrate it into your project, simply copy this file into your source tree. Read the API docs below. +/// +/// See also O1Heap -- a deterministic memory manager for hard-real-time +/// high-integrity embedded systems. +/// +/// Copyright (c) 2021 Pavel Kirienko +/// +/// Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated +/// documentation files (the "Software"), to deal in the Software without restriction, including without limitation +/// the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, +/// and to permit persons to whom the Software is furnished to do so, subject to the following conditions: +/// +/// The above copyright notice and this permission notice shall be included in all copies or substantial portions of +/// the Software. +/// +/// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE +/// WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS +/// OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR +/// OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +#pragma once + +#include "canard.h" + +/// Modified for use with Libcanard: use the same assertion check macro if provided. +#ifdef CANARD_ASSERT +# define CAVL_ASSERT CANARD_ASSERT +#else +// Intentional violation of MISRA: inclusion not at the top of the file to eliminate unnecessary dependency on assert.h. +# include // NOSONAR +# define CAVL_ASSERT assert +#endif + +#ifdef __cplusplus +// This is, strictly speaking, useless because we do not define any functions with external linkage here, +// but it tells static analyzers that what follows should be interpreted as C code rather than C++. +extern "C" { +#endif + +// ---------------------------------------- PUBLIC API SECTION ---------------------------------------- + +/// Modified for use with Libcanard: expose the Cavl structure via public API as CanardTreeNode. +typedef CanardTreeNode Cavl; + +/// Returns POSITIVE if the search target is GREATER than the provided node, negative if smaller, zero on match (found). +/// Values other than {-1, 0, +1} are not recommended to avoid overflow during the narrowing conversion of the result. +typedef int8_t (*CavlPredicate)(void* user_reference, const Cavl* node); + +/// If provided, the factory will be invoked when the sought node does not exist in the tree. +/// It is expected to return a new node that will be inserted immediately (without the need to traverse the tree again). +/// If the factory returns NULL or is not provided, the tree is not modified. +typedef Cavl* (*CavlFactory)(void* user_reference); + +/// Look for a node in the tree using the specified search predicate. The worst-case complexity is O(log n). +/// - If the node is found, return it. +/// - If the node is not found and the factory is NULL, return NULL. +/// - Otherwise, construct a new node using the factory; if the result is not NULL, insert it; return the result. +/// The user_reference is passed into the predicate & factory unmodified. +/// The root node may be replaced in the process. +/// If predicate is NULL, returns NULL. +static inline Cavl* cavlSearch(Cavl** const root, + void* const user_reference, + const CavlPredicate predicate, + const CavlFactory factory); + +/// Remove the specified node from its tree. The root node may be replaced in the process. +/// The worst-case complexity is O(log n). +/// The function has no effect if either of the pointers are NULL. +/// If the node is not in the tree, the behavior is undefined; it may create cycles in the tree which is deadly. +/// It is safe to pass the result of cavlSearch() directly as the second argument: +/// cavlRemove(&root, cavlSearch(&root, user_reference, search_predicate, NULL)); +/// It is recommended to invalidate the pointers stored in the node after its removal. +static inline void cavlRemove(Cavl** const root, const Cavl* const node); + +/// Return the min-/max-valued node stored in the tree, depending on the flag. This is an extremely fast query. +/// Returns NULL iff the argument is NULL (i.e., the tree is empty). The worst-case complexity is O(log n). +static inline Cavl* cavlFindExtremum(Cavl* const root, const bool maximum) +{ + Cavl* result = NULL; + Cavl* c = root; + while (c != NULL) + { + result = c; + c = c->lr[maximum]; + } + return result; +} + +// ---------------------------------------- END OF PUBLIC API SECTION ---------------------------------------- +// ---------------------------------------- POLICE LINE DO NOT CROSS ---------------------------------------- + +/// INTERNAL USE ONLY. Makes the '!r' child of node 'x' its parent; i.e., rotates 'x' toward 'r'. +static inline void cavlPrivateRotate(Cavl* const x, const bool r) +{ + CAVL_ASSERT((x != NULL) && (x->lr[!r] != NULL) && ((x->bf >= -1) && (x->bf <= +1))); + Cavl* const z = x->lr[!r]; + if (x->up != NULL) + { + x->up->lr[x->up->lr[1] == x] = z; + } + z->up = x->up; + x->up = z; + x->lr[!r] = z->lr[r]; + if (x->lr[!r] != NULL) + { + x->lr[!r]->up = x; + } + z->lr[r] = x; +} + +/// INTERNAL USE ONLY. +/// Accepts a node and how its balance factor needs to be changed -- either +1 or -1. +/// Returns the new node to replace the old one if tree rotation took place, same node otherwise. +static inline Cavl* cavlPrivateAdjustBalance(Cavl* const x, const bool increment) +{ + CAVL_ASSERT((x != NULL) && ((x->bf >= -1) && (x->bf <= +1))); + Cavl* out = x; + const int8_t new_bf = (int8_t) (x->bf + (increment ? +1 : -1)); + if ((new_bf < -1) || (new_bf > 1)) + { + const bool r = new_bf < 0; // bf<0 if left-heavy --> right rotation is needed. + const int8_t sign = r ? +1 : -1; // Positive if we are rotating right. + Cavl* const z = x->lr[!r]; + CAVL_ASSERT(z != NULL); // Heavy side cannot be empty. + if ((z->bf * sign) <= 0) // Parent and child are heavy on the same side or the child is balanced. + { + out = z; + cavlPrivateRotate(x, r); + if (0 == z->bf) + { + x->bf = (int8_t) (-sign); + z->bf = (int8_t) (+sign); + } + else + { + x->bf = 0; + z->bf = 0; + } + } + else // Otherwise, the child needs to be rotated in the opposite direction first. + { + Cavl* const y = z->lr[r]; + CAVL_ASSERT(y != NULL); // Heavy side cannot be empty. + out = y; + cavlPrivateRotate(z, !r); + cavlPrivateRotate(x, r); + if ((y->bf * sign) < 0) + { + x->bf = (int8_t) (+sign); + y->bf = 0; + z->bf = 0; + } + else if ((y->bf * sign) > 0) + { + x->bf = 0; + y->bf = 0; + z->bf = (int8_t) (-sign); + } + else + { + x->bf = 0; + z->bf = 0; + } + } + } + else + { + x->bf = new_bf; // Balancing not needed, just update the balance factor and call it a day. + } + return out; +} + +/// INTERNAL USE ONLY. +/// Takes the culprit node (the one that is added); returns NULL or the root of the tree (possibly new one). +/// When adding a new node, set its balance factor to zero and call this function to propagate the changes upward. +static inline Cavl* cavlPrivateRetraceOnGrowth(Cavl* const added) +{ + CAVL_ASSERT((added != NULL) && (0 == added->bf)); + Cavl* c = added; // Child + Cavl* p = added->up; // Parent + while (p != NULL) + { + const bool r = p->lr[1] == c; // c is the right child of parent + CAVL_ASSERT(p->lr[r] == c); + c = cavlPrivateAdjustBalance(p, r); + p = c->up; + if (0 == c->bf) + { // The height change of the subtree made this parent perfectly balanced (as all things should be), + break; // hence, the height of the outer subtree is unchanged, so upper balance factors are unchanged. + } + } + CAVL_ASSERT(c != NULL); + return (NULL == p) ? c : NULL; // New root or nothing. +} + +static inline Cavl* cavlSearch(Cavl** const root, + void* const user_reference, + const CavlPredicate predicate, + const CavlFactory factory) +{ + Cavl* out = NULL; + if ((root != NULL) && (predicate != NULL)) + { + Cavl* up = *root; + Cavl** n = root; + while (*n != NULL) + { + const int8_t cmp = predicate(user_reference, *n); + if (0 == cmp) + { + out = *n; + break; + } + up = *n; + n = &(*n)->lr[cmp > 0]; + CAVL_ASSERT((NULL == *n) || ((*n)->up == up)); + } + if (NULL == out) + { + out = (NULL == factory) ? NULL : factory(user_reference); + if (out != NULL) + { + *n = out; // Overwrite the pointer to the new node in the parent node. + out->lr[0] = NULL; + out->lr[1] = NULL; + out->up = up; + out->bf = 0; + Cavl* const rt = cavlPrivateRetraceOnGrowth(out); + if (rt != NULL) + { + *root = rt; + } + } + } + } + return out; +} + +static inline void cavlRemove(Cavl** const root, const Cavl* const node) +{ + if ((root != NULL) && (node != NULL)) + { + CAVL_ASSERT(*root != NULL); // Otherwise, the node would have to be NULL. + CAVL_ASSERT((node->up != NULL) || (node == *root)); + Cavl* p = NULL; // The lowest parent node that suffered a shortening of its subtree. + bool r = false; // Which side of the above was shortened. + // The first step is to update the topology and remember the node where to start the retracing from later. + // Balancing is not performed yet so we may end up with an unbalanced tree. + if ((node->lr[0] != NULL) && (node->lr[1] != NULL)) + { + Cavl* const re = cavlFindExtremum(node->lr[1], false); + CAVL_ASSERT((re != NULL) && (NULL == re->lr[0]) && (re->up != NULL)); + re->bf = node->bf; + re->lr[0] = node->lr[0]; + re->lr[0]->up = re; + if (re->up != node) + { + p = re->up; // Retracing starts with the ex-parent of our replacement node. + CAVL_ASSERT(p->lr[0] == re); + p->lr[0] = re->lr[1]; // Reducing the height of the left subtree here. + if (p->lr[0] != NULL) + { + p->lr[0]->up = p; + } + re->lr[1] = node->lr[1]; + re->lr[1]->up = re; + r = false; + } + else // In this case, we are reducing the height of the right subtree, so r=1. + { + p = re; // Retracing starts with the replacement node itself as we are deleting its parent. + r = true; // The right child of the replacement node remains the same so we don't bother relinking it. + } + re->up = node->up; + if (re->up != NULL) + { + re->up->lr[re->up->lr[1] == node] = re; // Replace link in the parent of node. + } + else + { + *root = re; + } + } + else // Either or both of the children are NULL. + { + p = node->up; + const bool rr = node->lr[1] != NULL; + if (node->lr[rr] != NULL) + { + node->lr[rr]->up = p; + } + if (p != NULL) + { + r = p->lr[1] == node; + p->lr[r] = node->lr[rr]; + if (p->lr[r] != NULL) + { + p->lr[r]->up = p; + } + } + else + { + *root = node->lr[rr]; + } + } + // Now that the topology is updated, perform the retracing to restore balance. We climb up adjusting the + // balance factors until we reach the root or a parent whose balance factor becomes plus/minus one, which + // means that that parent was able to absorb the balance delta; in other words, the height of the outer + // subtree is unchanged, so upper balance factors shall be kept unchanged. + if (p != NULL) + { + Cavl* c = NULL; + for (;;) + { + c = cavlPrivateAdjustBalance(p, !r); + p = c->up; + if ((c->bf != 0) || (NULL == p)) // Reached the root or the height difference is absorbed by c. + { + break; + } + r = p->lr[1] == c; + } + if (NULL == p) + { + CAVL_ASSERT(c != NULL); + *root = c; + } + } + } +} + +#ifdef __cplusplus +} +#endif diff --git a/canard.c b/canard.c new file mode 100644 index 00000000..d4577bfb --- /dev/null +++ b/canard.c @@ -0,0 +1,1277 @@ +/// This software is distributed under the terms of the MIT License. +/// Copyright (c) 2016 OpenCyphal. +/// Author: Pavel Kirienko + +#include "canard.h" +#include "_canard_cavl.h" +#include + +// --------------------------------------------- BUILD CONFIGURATION --------------------------------------------- + +/// Define this macro to include build configuration header. +/// Usage example with CMake: "-DCANARD_CONFIG_HEADER=\"${CMAKE_CURRENT_SOURCE_DIR}/my_canard_config.h\"" +#ifdef CANARD_CONFIG_HEADER +# include CANARD_CONFIG_HEADER +#endif + +/// By default, this macro resolves to the standard assert(). The user can redefine this if necessary. +/// To disable assertion checks completely, make it expand into `(void)(0)`. +#ifndef CANARD_ASSERT +// Intentional violation of MISRA: inclusion not at the top of the file to eliminate unnecessary dependency on assert.h. +# include // NOSONAR +// Intentional violation of MISRA: assertion macro cannot be replaced with a function definition. +# define CANARD_ASSERT(x) assert(x) // NOSONAR +#endif + +/// Define CANARD_CRC_TABLE=0 to use slow but ROM-efficient transfer-CRC computation algorithm. +/// Doing so is expected to save ca. 500 bytes of ROM and increase the cost of RX/TX transfer processing by ~half. +#ifndef CANARD_CRC_TABLE +# define CANARD_CRC_TABLE 1 +#endif + +/// This macro is needed for testing and for library development. +#ifndef CANARD_PRIVATE +# define CANARD_PRIVATE static inline +#endif + +#if !defined(__STDC_VERSION__) || (__STDC_VERSION__ < 199901L) +# error "Unsupported language: ISO C99 or a newer version is required." +#endif + +// --------------------------------------------- COMMON DEFINITIONS --------------------------------------------- + +#define BITS_PER_BYTE 8U +#define BYTE_MAX 0xFFU + +#define CAN_EXT_ID_MASK ((UINT32_C(1) << 29U) - 1U) + +#define MFT_NON_LAST_FRAME_PAYLOAD_MIN 7U + +#define PADDING_BYTE_VALUE 0U + +#define OFFSET_PRIORITY 26U +#define OFFSET_SUBJECT_ID 8U +#define OFFSET_SERVICE_ID 14U +#define OFFSET_DST_NODE_ID 7U + +#define FLAG_SERVICE_NOT_MESSAGE (UINT32_C(1) << 25U) +#define FLAG_ANONYMOUS_MESSAGE (UINT32_C(1) << 24U) +#define FLAG_REQUEST_NOT_RESPONSE (UINT32_C(1) << 24U) +#define FLAG_RESERVED_23 (UINT32_C(1) << 23U) +#define FLAG_RESERVED_07 (UINT32_C(1) << 7U) + +#define TAIL_START_OF_TRANSFER 128U +#define TAIL_END_OF_TRANSFER 64U +#define TAIL_TOGGLE 32U + +#define INITIAL_TOGGLE_STATE true + +/// Used for inserting new items into AVL trees. +CANARD_PRIVATE CanardTreeNode* avlTrivialFactory(void* const user_reference) +{ + return (CanardTreeNode*) user_reference; +} + +// --------------------------------------------- TRANSFER CRC --------------------------------------------- + +typedef uint16_t TransferCRC; + +#define CRC_INITIAL 0xFFFFU +#define CRC_RESIDUE 0x0000U +#define CRC_SIZE_BYTES 2U + +#if (CANARD_CRC_TABLE != 0) +static const uint16_t CRCTable[256] = { + 0x0000U, 0x1021U, 0x2042U, 0x3063U, 0x4084U, 0x50A5U, 0x60C6U, 0x70E7U, 0x8108U, 0x9129U, 0xA14AU, 0xB16BU, 0xC18CU, + 0xD1ADU, 0xE1CEU, 0xF1EFU, 0x1231U, 0x0210U, 0x3273U, 0x2252U, 0x52B5U, 0x4294U, 0x72F7U, 0x62D6U, 0x9339U, 0x8318U, + 0xB37BU, 0xA35AU, 0xD3BDU, 0xC39CU, 0xF3FFU, 0xE3DEU, 0x2462U, 0x3443U, 0x0420U, 0x1401U, 0x64E6U, 0x74C7U, 0x44A4U, + 0x5485U, 0xA56AU, 0xB54BU, 0x8528U, 0x9509U, 0xE5EEU, 0xF5CFU, 0xC5ACU, 0xD58DU, 0x3653U, 0x2672U, 0x1611U, 0x0630U, + 0x76D7U, 0x66F6U, 0x5695U, 0x46B4U, 0xB75BU, 0xA77AU, 0x9719U, 0x8738U, 0xF7DFU, 0xE7FEU, 0xD79DU, 0xC7BCU, 0x48C4U, + 0x58E5U, 0x6886U, 0x78A7U, 0x0840U, 0x1861U, 0x2802U, 0x3823U, 0xC9CCU, 0xD9EDU, 0xE98EU, 0xF9AFU, 0x8948U, 0x9969U, + 0xA90AU, 0xB92BU, 0x5AF5U, 0x4AD4U, 0x7AB7U, 0x6A96U, 0x1A71U, 0x0A50U, 0x3A33U, 0x2A12U, 0xDBFDU, 0xCBDCU, 0xFBBFU, + 0xEB9EU, 0x9B79U, 0x8B58U, 0xBB3BU, 0xAB1AU, 0x6CA6U, 0x7C87U, 0x4CE4U, 0x5CC5U, 0x2C22U, 0x3C03U, 0x0C60U, 0x1C41U, + 0xEDAEU, 0xFD8FU, 0xCDECU, 0xDDCDU, 0xAD2AU, 0xBD0BU, 0x8D68U, 0x9D49U, 0x7E97U, 0x6EB6U, 0x5ED5U, 0x4EF4U, 0x3E13U, + 0x2E32U, 0x1E51U, 0x0E70U, 0xFF9FU, 0xEFBEU, 0xDFDDU, 0xCFFCU, 0xBF1BU, 0xAF3AU, 0x9F59U, 0x8F78U, 0x9188U, 0x81A9U, + 0xB1CAU, 0xA1EBU, 0xD10CU, 0xC12DU, 0xF14EU, 0xE16FU, 0x1080U, 0x00A1U, 0x30C2U, 0x20E3U, 0x5004U, 0x4025U, 0x7046U, + 0x6067U, 0x83B9U, 0x9398U, 0xA3FBU, 0xB3DAU, 0xC33DU, 0xD31CU, 0xE37FU, 0xF35EU, 0x02B1U, 0x1290U, 0x22F3U, 0x32D2U, + 0x4235U, 0x5214U, 0x6277U, 0x7256U, 0xB5EAU, 0xA5CBU, 0x95A8U, 0x8589U, 0xF56EU, 0xE54FU, 0xD52CU, 0xC50DU, 0x34E2U, + 0x24C3U, 0x14A0U, 0x0481U, 0x7466U, 0x6447U, 0x5424U, 0x4405U, 0xA7DBU, 0xB7FAU, 0x8799U, 0x97B8U, 0xE75FU, 0xF77EU, + 0xC71DU, 0xD73CU, 0x26D3U, 0x36F2U, 0x0691U, 0x16B0U, 0x6657U, 0x7676U, 0x4615U, 0x5634U, 0xD94CU, 0xC96DU, 0xF90EU, + 0xE92FU, 0x99C8U, 0x89E9U, 0xB98AU, 0xA9ABU, 0x5844U, 0x4865U, 0x7806U, 0x6827U, 0x18C0U, 0x08E1U, 0x3882U, 0x28A3U, + 0xCB7DU, 0xDB5CU, 0xEB3FU, 0xFB1EU, 0x8BF9U, 0x9BD8U, 0xABBBU, 0xBB9AU, 0x4A75U, 0x5A54U, 0x6A37U, 0x7A16U, 0x0AF1U, + 0x1AD0U, 0x2AB3U, 0x3A92U, 0xFD2EU, 0xED0FU, 0xDD6CU, 0xCD4DU, 0xBDAAU, 0xAD8BU, 0x9DE8U, 0x8DC9U, 0x7C26U, 0x6C07U, + 0x5C64U, 0x4C45U, 0x3CA2U, 0x2C83U, 0x1CE0U, 0x0CC1U, 0xEF1FU, 0xFF3EU, 0xCF5DU, 0xDF7CU, 0xAF9BU, 0xBFBAU, 0x8FD9U, + 0x9FF8U, 0x6E17U, 0x7E36U, 0x4E55U, 0x5E74U, 0x2E93U, 0x3EB2U, 0x0ED1U, 0x1EF0U, +}; +#endif + +CANARD_PRIVATE TransferCRC crcAddByte(const TransferCRC crc, const uint8_t byte) +{ +#if (CANARD_CRC_TABLE != 0) + return (uint16_t) ((uint16_t) (crc << BITS_PER_BYTE) ^ + CRCTable[(uint16_t) ((uint16_t) (crc >> BITS_PER_BYTE) ^ byte) & BYTE_MAX]); +#else + static const TransferCRC Top = 0x8000U; + static const TransferCRC Poly = 0x1021U; + TransferCRC out = crc ^ (uint16_t) ((uint16_t) (byte) << BITS_PER_BYTE); + // Consider adding a compilation option that replaces this with a CRC table. Adds 512 bytes of ROM. + // Do not fold this into a loop because a size-optimizing compiler won't unroll it degrading the performance. + out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U)); + out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U)); + out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U)); + out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U)); + out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U)); + out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U)); + out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U)); + out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U)); + return out; +#endif +} + +CANARD_PRIVATE TransferCRC crcAdd(const TransferCRC crc, const size_t size, const void* const data) +{ + CANARD_ASSERT((data != NULL) || (size == 0U)); + TransferCRC out = crc; + const uint8_t* p = (const uint8_t*) data; + for (size_t i = 0; i < size; i++) + { + out = crcAddByte(out, *p); + ++p; + } + return out; +} + +// --------------------------------------------- TRANSMISSION --------------------------------------------- + +/// This is a subclass of CanardTxQueueItem. A pointer to this type can be cast to CanardTxQueueItem safely. +/// This is standard-compliant. The paragraph 6.7.2.1.15 says: +/// A pointer to a structure object, suitably converted, points to its initial member (or if that member is a +/// bit-field, then to the unit in which it resides), and vice versa. There may be unnamed padding within a +/// structure object, but not at its beginning. +typedef struct TxItem +{ + CanardTxQueueItem base; + uint8_t payload_buffer[CANARD_MTU_MAX]; +} TxItem; + +/// Chain of TX frames prepared for insertion into a TX queue. +typedef struct +{ + TxItem* head; + TxItem* tail; + size_t size; +} TxChain; + +CANARD_PRIVATE uint32_t txMakeMessageSessionSpecifier(const CanardPortID subject_id, const CanardNodeID src_node_id) +{ + CANARD_ASSERT(src_node_id <= CANARD_NODE_ID_MAX); + CANARD_ASSERT(subject_id <= CANARD_SUBJECT_ID_MAX); + const uint32_t tmp = subject_id | (CANARD_SUBJECT_ID_MAX + 1) | ((CANARD_SUBJECT_ID_MAX + 1) * 2); + return src_node_id | (tmp << OFFSET_SUBJECT_ID); +} + +CANARD_PRIVATE uint32_t txMakeServiceSessionSpecifier(const CanardPortID service_id, + const bool request_not_response, + const CanardNodeID src_node_id, + const CanardNodeID dst_node_id) +{ + CANARD_ASSERT(src_node_id <= CANARD_NODE_ID_MAX); + CANARD_ASSERT(dst_node_id <= CANARD_NODE_ID_MAX); + CANARD_ASSERT(service_id <= CANARD_SERVICE_ID_MAX); + return src_node_id | (((uint32_t) dst_node_id) << OFFSET_DST_NODE_ID) | // + (((uint32_t) service_id) << OFFSET_SERVICE_ID) | // + (request_not_response ? FLAG_REQUEST_NOT_RESPONSE : 0U) | FLAG_SERVICE_NOT_MESSAGE; +} + +/// This is the transport MTU rounded up to next full DLC minus the tail byte. +CANARD_PRIVATE size_t adjustPresentationLayerMTU(const size_t mtu_bytes) +{ + const size_t max_index = (sizeof(CanardCANLengthToDLC) / sizeof(CanardCANLengthToDLC[0])) - 1U; + size_t mtu = 0U; + if (mtu_bytes < CANARD_MTU_CAN_CLASSIC) + { + mtu = CANARD_MTU_CAN_CLASSIC; + } + else if (mtu_bytes <= max_index) + { + mtu = CanardCANDLCToLength[CanardCANLengthToDLC[mtu_bytes]]; // Round up to nearest valid length. + } + else + { + mtu = CanardCANDLCToLength[CanardCANLengthToDLC[max_index]]; + } + return mtu - 1U; +} + +CANARD_PRIVATE int32_t txMakeCANID(const CanardTransferMetadata* const tr, + const size_t payload_size, + const void* const payload, + const CanardNodeID local_node_id, + const size_t presentation_layer_mtu) +{ + CANARD_ASSERT(tr != NULL); + CANARD_ASSERT(presentation_layer_mtu > 0); + int32_t out = -CANARD_ERROR_INVALID_ARGUMENT; + if ((tr->transfer_kind == CanardTransferKindMessage) && (CANARD_NODE_ID_UNSET == tr->remote_node_id) && + (tr->port_id <= CANARD_SUBJECT_ID_MAX)) + { + if (local_node_id <= CANARD_NODE_ID_MAX) + { + out = (int32_t) txMakeMessageSessionSpecifier(tr->port_id, local_node_id); + CANARD_ASSERT(out >= 0); + } + 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); + const uint32_t spec = txMakeMessageSessionSpecifier(tr->port_id, c) | FLAG_ANONYMOUS_MESSAGE; + CANARD_ASSERT(spec <= CAN_EXT_ID_MASK); + out = (int32_t) spec; + } + else + { + out = -CANARD_ERROR_INVALID_ARGUMENT; // Anonymous multi-frame message trs are not allowed. + } + } + else if (((tr->transfer_kind == CanardTransferKindRequest) || (tr->transfer_kind == CanardTransferKindResponse)) && + (tr->remote_node_id <= CANARD_NODE_ID_MAX) && (tr->port_id <= CANARD_SERVICE_ID_MAX)) + { + if (local_node_id <= CANARD_NODE_ID_MAX) + { + out = (int32_t) txMakeServiceSessionSpecifier(tr->port_id, + tr->transfer_kind == CanardTransferKindRequest, + local_node_id, + tr->remote_node_id); + CANARD_ASSERT(out >= 0); + } + else + { + out = -CANARD_ERROR_INVALID_ARGUMENT; // Anonymous service transfers are not allowed. + } + } + else + { + out = -CANARD_ERROR_INVALID_ARGUMENT; + } + + if (out >= 0) + { + const uint32_t prio = (uint32_t) tr->priority; + if (prio <= CANARD_PRIORITY_MAX) + { + const uint32_t id = ((uint32_t) out) | (prio << OFFSET_PRIORITY); + out = (int32_t) id; + } + else + { + out = -CANARD_ERROR_INVALID_ARGUMENT; + } + } + return out; +} + +CANARD_PRIVATE uint8_t txMakeTailByte(const bool start_of_transfer, + const bool end_of_transfer, + const bool toggle, + const CanardTransferID transfer_id) +{ + CANARD_ASSERT(start_of_transfer ? (toggle == INITIAL_TOGGLE_STATE) : true); + return (uint8_t) ((start_of_transfer ? TAIL_START_OF_TRANSFER : 0U) | + (end_of_transfer ? TAIL_END_OF_TRANSFER : 0U) | (toggle ? TAIL_TOGGLE : 0U) | + (transfer_id & CANARD_TRANSFER_ID_MAX)); +} + +/// Takes a frame payload size, returns a new size that is >=x and is rounded up to the nearest valid DLC. +CANARD_PRIVATE size_t txRoundFramePayloadSizeUp(const size_t x) +{ + CANARD_ASSERT(x < (sizeof(CanardCANLengthToDLC) / sizeof(CanardCANLengthToDLC[0]))); + // Suppressing a false-positive out-of-bounds access error from Sonar. Its control flow analyser is misbehaving. + const size_t y = CanardCANLengthToDLC[x]; // NOSONAR + CANARD_ASSERT(y < (sizeof(CanardCANDLCToLength) / sizeof(CanardCANDLCToLength[0]))); + return CanardCANDLCToLength[y]; +} + +/// The item is only allocated and initialized, but NOT included into the queue! The caller needs to do that. +CANARD_PRIVATE TxItem* txAllocateQueueItem(CanardInstance* const ins, + const uint32_t id, + const CanardMicrosecond deadline_usec, + const size_t payload_size) +{ + CANARD_ASSERT(ins != NULL); + CANARD_ASSERT(payload_size > 0U); + TxItem* const out = (TxItem*) ins->memory_allocate(ins, (sizeof(TxItem) - CANARD_MTU_MAX) + payload_size); + if (out != NULL) + { + out->base.base.up = NULL; + out->base.base.lr[0] = NULL; + out->base.base.lr[1] = NULL; + out->base.base.bf = 0; + + 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.extended_can_id = id; + } + return out; +} + +/// Frames with identical CAN ID that are added later always compare greater than their counterparts with same CAN ID. +/// This ensures that CAN frames with the same CAN ID are transmitted in the FIFO order. +/// Frames that should be transmitted earlier compare smaller (i.e., put on the left side of the tree). +CANARD_PRIVATE int8_t txAVLPredicate(void* const user_reference, // NOSONAR Cavl API requires pointer to non-const. + const CanardTreeNode* const node) +{ + const CanardTxQueueItem* const target = (const CanardTxQueueItem*) user_reference; + const CanardTxQueueItem* const other = (const CanardTxQueueItem*) (const void*) node; + CANARD_ASSERT((target != NULL) && (other != NULL)); + return (target->frame.extended_can_id >= other->frame.extended_can_id) ? +1 : -1; +} + +/// Returns the number of frames enqueued or error (i.e., =1 or <0). +CANARD_PRIVATE int32_t txPushSingleFrame(CanardTxQueue* const que, + CanardInstance* const ins, + const CanardMicrosecond deadline_usec, + const uint32_t can_id, + const CanardTransferID transfer_id, + const size_t payload_size, + const void* const payload) +{ + CANARD_ASSERT(ins != 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); + int32_t out = 0; + TxItem* const tqi = + (que->size < que->capacity) ? txAllocateQueueItem(ins, 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. + { + CANARD_ASSERT(payload != 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 + } + // 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 + 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); + (void) res; + CANARD_ASSERT(res == &tqi->base.base); + que->size++; + CANARD_ASSERT(que->size <= que->capacity); + out = 1; // One frame enqueued. + } + else + { + out = -CANARD_ERROR_OUT_OF_MEMORY; + } + CANARD_ASSERT((out < 0) || (out == 1)); + return out; +} + +/// Produces a chain of Tx queue items for later insertion into the Tx queue. The tail is NULL if OOM. +CANARD_PRIVATE TxChain txGenerateMultiFrameChain(CanardInstance* const ins, + 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_ASSERT(ins != 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); + + TxChain out = {NULL, NULL, 0}; + const size_t payload_size_with_crc = payload_size + CRC_SIZE_BYTES; + size_t offset = 0U; + TransferCRC crc = crcAdd(CRC_INITIAL, payload_size, payload); + bool toggle = INITIAL_TOGGLE_STATE; + const uint8_t* payload_ptr = (const uint8_t*) payload; + while (offset < payload_size_with_crc) + { + out.size++; + const size_t frame_payload_size_with_tail = + ((payload_size_with_crc - offset) < presentation_layer_mtu) + ? txRoundFramePayloadSizeUp((payload_size_with_crc - offset) + 1U) // Padding in the last frame only. + : (presentation_layer_mtu + 1U); + TxItem* const tqi = txAllocateQueueItem(ins, can_id, deadline_usec, frame_payload_size_with_tail); + if (NULL == out.head) + { + out.head = tqi; + } + else + { + // C std, 6.7.2.1.15: A pointer to a structure object <...> points to its initial member, and vice versa. + // Can't just read tqi->base because tqi may be NULL; https://github.com/OpenCyphal/libcanard/issues/203. + out.tail->base.next_in_transfer = (CanardTxQueueItem*) tqi; + } + out.tail = tqi; + if (NULL == out.tail) + { + break; + } + + // 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) + { + size_t move_size = payload_size - offset; + if (move_size > frame_payload_size) + { + move_size = frame_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. + // SonarQube incorrectly detects a buffer overflow here. + (void) memcpy(&out.tail->payload_buffer[0], payload_ptr, move_size); // NOLINT NOSONAR + frame_offset = frame_offset + move_size; + offset += move_size; + payload_ptr += move_size; + } + + // Handle the last frame of the transfer: it is special because it also contains padding and CRC. + 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) + { + out.tail->payload_buffer[frame_offset] = PADDING_BYTE_VALUE; + ++frame_offset; + crc = crcAddByte(crc, PADDING_BYTE_VALUE); + } + + // Insert the CRC. + 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)) + { + out.tail->payload_buffer[frame_offset] = (uint8_t) (crc & BYTE_MAX); + ++frame_offset; + ++offset; + } + } + + // Finalize the frame. + 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); + toggle = !toggle; + } + return out; +} + +/// Returns the number of frames enqueued or error. +CANARD_PRIVATE int32_t txPushMultiFrame(CanardTxQueue* const que, + CanardInstance* const ins, + 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_ASSERT((ins != NULL) && (que != NULL)); + CANARD_ASSERT(presentation_layer_mtu > 0U); + 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 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(ins, + presentation_layer_mtu, + deadline_usec, + can_id, + transfer_id, + payload_size, + payload); + if (sq.tail != NULL) + { + CanardTxQueueItem* next = &sq.head->base; + do + { + const CanardTreeNode* const res = + cavlSearch(&que->root, &next->base, &txAVLPredicate, &avlTrivialFactory); + (void) res; + CANARD_ASSERT(res == &next->base); + CANARD_ASSERT(que->root != NULL); + next = next->next_in_transfer; + } while (next != NULL); + CANARD_ASSERT(num_frames == sq.size); + que->size += sq.size; + CANARD_ASSERT(que->size <= que->capacity); + CANARD_ASSERT((sq.size + 0ULL) <= INT32_MAX); // +0 is to suppress warning. + out = (int32_t) sq.size; + } + else + { + out = -CANARD_ERROR_OUT_OF_MEMORY; + CanardTxQueueItem* head = &sq.head->base; + while (head != NULL) + { + CanardTxQueueItem* const next = head->next_in_transfer; + ins->memory_free(ins, head); + head = next; + } + } + } + else // We predict that we're going to run out of queue, don't bother serializing the transfer. + { + out = -CANARD_ERROR_OUT_OF_MEMORY; + } + CANARD_ASSERT((out < 0) || (out >= 2)); + return out; +} + +// --------------------------------------------- RECEPTION --------------------------------------------- + +#define RX_SESSIONS_PER_SUBSCRIPTION (CANARD_NODE_ID_MAX + 1U) + +/// The memory requirement model provided in the documentation assumes that the maximum size of this structure never +/// exceeds 48 bytes on any conventional platform. +/// A user that needs a detailed analysis of the worst-case memory consumption may compute the size of this structure +/// for the particular platform at hand manually or by evaluating its sizeof(). +/// The fields are ordered to minimize the amount of padding on all conventional platforms. +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; +} 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; +} RxFrameModel; + +/// Returns truth if the frame is valid and parsed successfully. False if the frame is not a valid Cyphal/CAN frame. +CANARD_PRIVATE bool rxTryParseFrame(const CanardMicrosecond timestamp_usec, + const CanardFrame* const frame, + RxFrameModel* const out) +{ + CANARD_ASSERT(frame != NULL); + CANARD_ASSERT(frame->extended_can_id <= CAN_EXT_ID_MASK); + CANARD_ASSERT(out != NULL); + bool valid = false; + if (frame->payload_size > 0) + { + CANARD_ASSERT(frame->payload != NULL); + out->timestamp_usec = timestamp_usec; + + // CAN ID parsing. + const uint32_t can_id = frame->extended_can_id; + out->priority = (CanardPriority) ((can_id >> OFFSET_PRIORITY) & CANARD_PRIORITY_MAX); + out->source_node_id = (CanardNodeID) (can_id & CANARD_NODE_ID_MAX); + if (0 == (can_id & FLAG_SERVICE_NOT_MESSAGE)) + { + out->transfer_kind = CanardTransferKindMessage; + out->port_id = (CanardPortID) ((can_id >> OFFSET_SUBJECT_ID) & CANARD_SUBJECT_ID_MAX); + if ((can_id & FLAG_ANONYMOUS_MESSAGE) != 0) + { + out->source_node_id = CANARD_NODE_ID_UNSET; + } + out->destination_node_id = CANARD_NODE_ID_UNSET; + // Reserved bits may be unreserved in the future. + valid = (0 == (can_id & FLAG_RESERVED_23)) && (0 == (can_id & FLAG_RESERVED_07)); + } + else + { + out->transfer_kind = + ((can_id & FLAG_REQUEST_NOT_RESPONSE) != 0) ? CanardTransferKindRequest : CanardTransferKindResponse; + out->port_id = (CanardPortID) ((can_id >> OFFSET_SERVICE_ID) & CANARD_SERVICE_ID_MAX); + out->destination_node_id = (CanardNodeID) ((can_id >> OFFSET_DST_NODE_ID) & CANARD_NODE_ID_MAX); + // The reserved bit may be unreserved in the future. It may be used to extend the service-ID to 10 bits. + // Per Specification, source cannot be the same as the destination. + valid = (0 == (can_id & FLAG_RESERVED_23)) && (out->source_node_id != out->destination_node_id); + } + + // Payload parsing. + out->payload_size = frame->payload_size - 1U; // Cut off the tail byte. + out->payload = frame->payload; + + // 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 + 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); + out->toggle = ((tail & TAIL_TOGGLE) != 0); + + // Final validation. + // Protocol version check: if SOT is set, then the toggle shall also be set. + valid = valid && ((!out->start_of_transfer) || (INITIAL_TOGGLE_STATE == out->toggle)); + // Anonymous transfers can be only single-frame transfers. + 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); + // 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)); + } + return valid; +} + +CANARD_PRIVATE void rxInitTransferMetadataFromFrame(const RxFrameModel* const frame, + CanardTransferMetadata* const out_transfer) +{ + CANARD_ASSERT(frame != NULL); + CANARD_ASSERT(frame->payload != NULL); + CANARD_ASSERT(out_transfer != NULL); + out_transfer->priority = frame->priority; + out_transfer->transfer_kind = frame->transfer_kind; + out_transfer->port_id = frame->port_id; + out_transfer->remote_node_id = frame->source_node_id; + out_transfer->transfer_id = frame->transfer_id; +} + +/// The implementation is borrowed from the Specification. +CANARD_PRIVATE uint8_t rxComputeTransferIDDifference(const uint8_t a, const uint8_t b) +{ + CANARD_ASSERT(a <= CANARD_TRANSFER_ID_MAX); + CANARD_ASSERT(b <= CANARD_TRANSFER_ID_MAX); + int16_t diff = (int16_t) (((int16_t) a) - ((int16_t) b)); + if (diff < 0) + { + const uint8_t modulo = 1U << CANARD_TRANSFER_ID_BIT_LENGTH; + diff = (int16_t) (diff + (int16_t) modulo); + } + return (uint8_t) diff; +} + +CANARD_PRIVATE int8_t rxSessionWritePayload(CanardInstance* const ins, + CanardInternalRxSession* const rxs, + const size_t extent, + const size_t payload_size, + const void* const 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); + + rxs->total_payload_size += payload_size; + + // Allocate the payload lazily, as late as possible. + if ((NULL == rxs->payload) && (extent > 0U)) + { + CANARD_ASSERT(rxs->payload_size == 0); + rxs->payload = ins->memory_allocate(ins, extent); + } + + int8_t out = 0; + if (rxs->payload != 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) + { + 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. + // Excepting these two cases, the entire RX pipeline contains neither loops nor recursion. + // 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); + } + else + { + 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) +{ + CANARD_ASSERT(ins != NULL); + CANARD_ASSERT(rxs != NULL); + ins->memory_free(ins, 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); + // The transport index is retained. + rxs->toggle = INITIAL_TOGGLE_STATE; +} + +CANARD_PRIVATE int8_t rxSessionAcceptFrame(CanardInstance* const ins, + CanardInternalRxSession* const rxs, + const RxFrameModel* const frame, + const size_t extent, + CanardRxTransfer* const out_transfer) +{ + CANARD_ASSERT(ins != NULL); + CANARD_ASSERT(rxs != NULL); + CANARD_ASSERT(frame != NULL); + CANARD_ASSERT(frame->payload != NULL); + CANARD_ASSERT(frame->transfer_id <= CANARD_TRANSFER_ID_MAX); + CANARD_ASSERT(out_transfer != NULL); + + if (frame->start_of_transfer) // The transfer timestamp is the timestamp of its first frame. + { + rxs->transfer_timestamp_usec = frame->timestamp_usec; + } + + const bool single_frame = frame->start_of_transfer && frame->end_of_transfer; + if (!single_frame) + { + // 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); + } + + int8_t out = rxSessionWritePayload(ins, rxs, extent, frame->payload_size, frame->payload); + if (out < 0) + { + CANARD_ASSERT(-CANARD_ERROR_OUT_OF_MEMORY == out); + rxSessionRestart(ins, rxs); // Out-of-memory. + } + else if (frame->end_of_transfer) + { + CANARD_ASSERT(0 == out); + if (single_frame || (CRC_RESIDUE == rxs->calculated_crc)) + { + 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; + + // 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; + 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; + } + + rxs->payload = NULL; // Ownership passed over to the application, nullify to prevent freeing. + } + rxSessionRestart(ins, rxs); // Successful completion. + } + else + { + rxs->toggle = !rxs->toggle; + } + return out; +} + +/// Evaluates the state of the RX session with respect to time and the new frame, and restarts it if necessary. +/// The next step is to accept the frame if the transfer-ID, toggle but, and transport index match; reject otherwise. +/// The logic of this function is simple: it restarts the reassembler if the start-of-transfer flag is set and +/// any two of the three conditions are met: +/// +/// - The frame has arrived over the same interface as the previous transfer. +/// - New transfer-ID is detected. +/// - The transfer-ID timeout has expired. +/// +/// Notice that mere TID-timeout is not enough to restart to prevent the interface index oscillation; +/// while this is not visible at the application layer, it may delay the transfer arrival. +CANARD_PRIVATE void rxSessionSynchronize(CanardInternalRxSession* const rxs, + const RxFrameModel* const frame, + const uint8_t redundant_iface_index, + const CanardMicrosecond transfer_id_timeout_usec) +{ + CANARD_ASSERT(rxs != NULL); + CANARD_ASSERT(frame != NULL); + CANARD_ASSERT(rxs->transfer_id <= CANARD_TRANSFER_ID_MAX); + CANARD_ASSERT(frame->transfer_id <= CANARD_TRANSFER_ID_MAX); + + const bool same_transport = rxs->redundant_iface_index == redundant_iface_index; + // Examples: rxComputeTransferIDDifference(2, 3)==31 + // rxComputeTransferIDDifference(2, 2)==0 + // rxComputeTransferIDDifference(2, 1)==1 + const bool tid_new = rxComputeTransferIDDifference(rxs->transfer_id, frame->transfer_id) > 1; + // The transfer ID timeout is measured relative to the timestamp of the last start-of-transfer frame. + const bool tid_timeout = (frame->timestamp_usec > rxs->transfer_timestamp_usec) && + ((frame->timestamp_usec - rxs->transfer_timestamp_usec) > transfer_id_timeout_usec); + + const bool restartable = (same_transport && tid_new) || // + (same_transport && tid_timeout) || // + (tid_new && tid_timeout); + // Restarting the transfer reassembly only makes sense if the new frame is a start of transfer. + // Otherwise, the new transfer would be impossible to reassemble anyway since the first frame is lost. + if (frame->start_of_transfer && restartable) + { + 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->calculated_crc = CRC_INITIAL; + rxs->transfer_id = frame->transfer_id; + rxs->toggle = INITIAL_TOGGLE_STATE; + rxs->redundant_iface_index = redundant_iface_index; + } +} + +/// RX session state machine update is the most intricate part of any Cyphal transport implementation. +/// The state model used here is derived from the reference pseudocode given in the original UAVCAN v0 specification. +/// The Cyphal/CAN v1 specification, which this library is an implementation of, does not provide any reference +/// pseudocode. Instead, it takes a higher-level, more abstract approach, where only the high-level requirements +/// are given and the particular algorithms are left to be implementation-defined. Such abstract approach is much +/// advantageous because it allows implementers to choose whatever solution works best for the specific application at +/// hand, while the wire compatibility is still guaranteed by the high-level requirements given in the specification. +CANARD_PRIVATE int8_t rxSessionUpdate(CanardInstance* const ins, + CanardInternalRxSession* const rxs, + const RxFrameModel* const frame, + const uint8_t redundant_iface_index, + const CanardMicrosecond transfer_id_timeout_usec, + const size_t extent, + CanardRxTransfer* const out_transfer) +{ + CANARD_ASSERT(ins != NULL); + CANARD_ASSERT(rxs != NULL); + CANARD_ASSERT(frame != NULL); + CANARD_ASSERT(out_transfer != NULL); + CANARD_ASSERT(rxs->transfer_id <= CANARD_TRANSFER_ID_MAX); + CANARD_ASSERT(frame->transfer_id <= CANARD_TRANSFER_ID_MAX); + rxSessionSynchronize(rxs, frame, redundant_iface_index, transfer_id_timeout_usec); + int8_t out = 0; + // The purpose of the correct_start check is to reduce the possibility of accepting a malformed multi-frame + // transfer in the event of a CRC collision. The scenario where this failure mode would manifest is as follows: + // 1. A valid transfer (whether single- or multi-frame) is accepted with TID=X. + // 2. All frames of the subsequent multi-frame transfer with TID=X+1 are lost except for the last one. + // 3. The CRC of said multi-frame transfer happens to yield the correct residue when applied to the fragment + // of the payload contained in the last frame of the transfer (a CRC collision is in effect). + // 4. The last frame of the multi-frame transfer is erroneously accepted even though it is malformed. + // The correct_start check eliminates this failure mode by ensuring that the first frame is observed. + // See https://github.com/OpenCyphal/libcanard/issues/189. + const bool correct_iface = (rxs->redundant_iface_index == redundant_iface_index); + const bool correct_toggle = (frame->toggle == rxs->toggle); + const bool correct_tid = (frame->transfer_id == rxs->transfer_id); + const bool correct_start = frame->start_of_transfer // + ? (0 == rxs->total_payload_size) + : (rxs->total_payload_size > 0); + if (correct_iface && correct_toggle && correct_tid && correct_start) + { + out = rxSessionAcceptFrame(ins, rxs, frame, extent, out_transfer); + } + return out; +} + +CANARD_PRIVATE int8_t rxAcceptFrame(CanardInstance* const ins, + CanardRxSubscription* const subscription, + const RxFrameModel* const frame, + const uint8_t redundant_iface_index, + CanardRxTransfer* const out_transfer) +{ + CANARD_ASSERT(ins != NULL); + CANARD_ASSERT(subscription != NULL); + CANARD_ASSERT(subscription->port_id == frame->port_id); + CANARD_ASSERT(frame != NULL); + CANARD_ASSERT(frame->payload != 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); + + int8_t out = 0; + if (frame->source_node_id <= CANARD_NODE_ID_MAX) + { + // If such session does not exist, create it. This only makes sense if this is the first frame of a + // transfer, otherwise, we won't be able to receive the transfer anyway so we don't bother. + if ((NULL == subscription->sessions[frame->source_node_id]) && frame->start_of_transfer) + { + CanardInternalRxSession* const rxs = + (CanardInternalRxSession*) ins->memory_allocate(ins, sizeof(CanardInternalRxSession)); + subscription->sessions[frame->source_node_id] = rxs; + if (rxs != NULL) + { + rxs->transfer_timestamp_usec = frame->timestamp_usec; + rxs->total_payload_size = 0U; + rxs->payload_size = 0U; + rxs->payload = NULL; + rxs->calculated_crc = CRC_INITIAL; + rxs->transfer_id = frame->transfer_id; + rxs->redundant_iface_index = redundant_iface_index; + rxs->toggle = INITIAL_TOGGLE_STATE; + } + else + { + out = -CANARD_ERROR_OUT_OF_MEMORY; + } + } + // There are two possible reasons why the session may not exist: 1. OOM; 2. SOT-miss. + if (subscription->sessions[frame->source_node_id] != NULL) + { + CANARD_ASSERT(out == 0); + out = rxSessionUpdate(ins, + subscription->sessions[frame->source_node_id], + frame, + redundant_iface_index, + subscription->transfer_id_timeout_usec, + subscription->extent, + out_transfer); + } + } + else + { + CANARD_ASSERT(frame->source_node_id == CANARD_NODE_ID_UNSET); + // Anonymous transfers are stateless. No need to update the state machine, just blindly accept it. + // 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, payload_size); + if (payload != NULL) + { + rxInitTransferMetadataFromFrame(frame, &out_transfer->metadata); + out_transfer->timestamp_usec = frame->timestamp_usec; + out_transfer->payload_size = payload_size; + out_transfer->payload = payload; + // 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 + out = 1; + } + else + { + out = -CANARD_ERROR_OUT_OF_MEMORY; + } + } + return out; +} + +CANARD_PRIVATE int8_t +rxSubscriptionPredicateOnPortID(void* const user_reference, // NOSONAR Cavl API requires pointer to non-const. + const CanardTreeNode* const node) +{ + const CanardPortID sought = *((const CanardPortID*) user_reference); + const CanardPortID other = ((const CanardRxSubscription*) (const void*) node)->port_id; + static const int8_t NegPos[2] = {-1, +1}; + // Clang-Tidy mistakenly identifies a narrowing cast to int8_t here, which is incorrect. + return (sought == other) ? 0 : NegPos[sought > other]; // NOLINT no narrowing conversion is taking place here +} + +CANARD_PRIVATE int8_t +rxSubscriptionPredicateOnStruct(void* const user_reference, // NOSONAR Cavl API requires pointer to non-const. + const CanardTreeNode* const node) +{ + return rxSubscriptionPredicateOnPortID(&((CanardRxSubscription*) user_reference)->port_id, node); +} + +// --------------------------------------------- PUBLIC API --------------------------------------------- + +const uint8_t CanardCANDLCToLength[16] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 12, 16, 20, 24, 32, 48, 64}; +const uint8_t CanardCANLengthToDLC[65] = { + 0, 1, 2, 3, 4, 5, 6, 7, 8, // 0-8 + 9, 9, 9, 9, // 9-12 + 10, 10, 10, 10, // 13-16 + 11, 11, 11, 11, // 17-20 + 12, 12, 12, 12, // 21-24 + 13, 13, 13, 13, 13, 13, 13, 13, // 25-32 + 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, // 33-48 + 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, // 49-64 +}; + +CanardInstance canardInit(const CanardMemoryAllocate memory_allocate, const CanardMemoryFree memory_free) +{ + CANARD_ASSERT(memory_allocate != NULL); + CANARD_ASSERT(memory_free != NULL); + const CanardInstance out = { + .user_reference = NULL, + .node_id = CANARD_NODE_ID_UNSET, + .memory_allocate = memory_allocate, + .memory_free = memory_free, + .rx_subscriptions = {NULL, NULL, NULL}, + }; + return out; +} + +CanardTxQueue canardTxInit(const size_t capacity, const size_t mtu_bytes) +{ + CanardTxQueue out = { + .capacity = capacity, + .mtu_bytes = mtu_bytes, + .size = 0, + .root = NULL, + .user_reference = NULL, + }; + return out; +} + +int32_t canardTxPush(CanardTxQueue* const que, + CanardInstance* const ins, + const CanardMicrosecond tx_deadline_usec, + const CanardTransferMetadata* const metadata, + const size_t payload_size, + const void* const payload) +{ + int32_t out = -CANARD_ERROR_INVALID_ARGUMENT; + if ((ins != NULL) && (que != NULL) && (metadata != NULL) && ((payload != 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); + if (maybe_can_id >= 0) + { + if (payload_size <= pl_mtu) + { + out = txPushSingleFrame(que, + ins, + tx_deadline_usec, + (uint32_t) maybe_can_id, + metadata->transfer_id, + payload_size, + payload); + CANARD_ASSERT((out < 0) || (out == 1)); + } + else + { + out = txPushMultiFrame(que, + ins, + pl_mtu, + tx_deadline_usec, + (uint32_t) maybe_can_id, + metadata->transfer_id, + payload_size, + payload); + CANARD_ASSERT((out < 0) || (out >= 2)); + } + } + else + { + out = maybe_can_id; + } + } + CANARD_ASSERT(out != 0); + return out; +} + +const CanardTxQueueItem* canardTxPeek(const CanardTxQueue* const que) +{ + const CanardTxQueueItem* out = NULL; + if (que != NULL) + { + // Paragraph 6.7.2.1.15 of the C standard says: + // A pointer to a structure object, suitably converted, points to its initial member, and vice versa. + out = (const CanardTxQueueItem*) (void*) cavlFindExtremum(que->root, false); + } + return out; +} + +CanardTxQueueItem* canardTxPop(CanardTxQueue* const que, const CanardTxQueueItem* const item) +{ + CanardTxQueueItem* out = NULL; + if ((que != NULL) && (item != NULL)) + { + // Intentional violation of MISRA: casting away const qualifier. This is considered safe because the API + // contract dictates that the pointer shall point to a mutable entity in RAM previously allocated by the + // memory manager. It is difficult to avoid this cast in this context. + out = (CanardTxQueueItem*) item; // NOSONAR casting away const qualifier. + // Paragraph 6.7.2.1.15 of the C standard says: + // A pointer to a structure object, suitably converted, points to its initial member, and vice versa. + // Note that the highest-priority frame is always a leaf node in the AVL tree, which means that it is very + // cheap to remove. + cavlRemove(&que->root, &item->base); + que->size--; + } + return out; +} + +int8_t canardRxAccept(CanardInstance* const ins, + const CanardMicrosecond timestamp_usec, + const CanardFrame* const frame, + const uint8_t redundant_iface_index, + CanardRxTransfer* const out_transfer, + CanardRxSubscription** const out_subscription) +{ + int8_t 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))) + { + RxFrameModel model = {0}; + if (rxTryParseFrame(timestamp_usec, frame, &model)) + { + if ((CANARD_NODE_ID_UNSET == model.destination_node_id) || (ins->node_id == model.destination_node_id)) + { + // This is the reason the function has a logarithmic time complexity of the number of subscriptions. + // Note also that this one of the two variable-complexity operations in the RX pipeline; the other one + // is memcpy(). Excepting these two cases, the entire RX pipeline contains neither loops nor recursion. + CanardRxSubscription* const sub = + (CanardRxSubscription*) (void*) cavlSearch(&ins->rx_subscriptions[(size_t) model.transfer_kind], + &model.port_id, + &rxSubscriptionPredicateOnPortID, + NULL); + if (out_subscription != NULL) + { + *out_subscription = sub; // Expose selected instance to the caller. + } + if (sub != NULL) + { + CANARD_ASSERT(sub->port_id == model.port_id); + out = rxAcceptFrame(ins, sub, &model, redundant_iface_index, out_transfer); + } + else + { + out = 0; // No matching subscription. + } + } + else + { + out = 0; // Mis-addressed frame (normally it should be filtered out by the hardware). + } + } + else + { + out = 0; // A non-Cyphal/CAN input frame. + } + } + CANARD_ASSERT(out <= 1); + return out; +} + +int8_t canardRxSubscribe(CanardInstance* const ins, + const CanardTransferKind transfer_kind, + const CanardPortID port_id, + const size_t extent, + const CanardMicrosecond transfer_id_timeout_usec, + CanardRxSubscription* const out_subscription) +{ + int8_t out = -CANARD_ERROR_INVALID_ARGUMENT; + const size_t tk = (size_t) transfer_kind; + if ((ins != NULL) && (out_subscription != NULL) && (tk < CANARD_NUM_TRANSFER_KINDS)) + { + // Reset to the initial state. This is absolutely critical because the new payload size limit may be larger + // than the old value; if there are any payload buffers allocated, we may overrun them because they are shorter + // than the new payload limit. So we clear the subscription and thus ensure that no overrun may occur. + out = canardRxUnsubscribe(ins, transfer_kind, port_id); + if (out >= 0) + { + out_subscription->transfer_id_timeout_usec = transfer_id_timeout_usec; + out_subscription->extent = extent; + out_subscription->port_id = port_id; + for (size_t i = 0; i < RX_SESSIONS_PER_SUBSCRIPTION; i++) + { + // The sessions will be created ad-hoc. Normally, for a low-jitter deterministic system, + // we could have pre-allocated sessions here, but that requires too much memory to be feasible. + // We could accept an extra argument that would instruct us to pre-allocate sessions here? + out_subscription->sessions[i] = NULL; + } + const CanardTreeNode* const res = cavlSearch(&ins->rx_subscriptions[tk], + out_subscription, + &rxSubscriptionPredicateOnStruct, + &avlTrivialFactory); + (void) res; + CANARD_ASSERT(res == &out_subscription->base); + out = (out > 0) ? 0 : 1; + } + } + return out; +} + +int8_t canardRxUnsubscribe(CanardInstance* const ins, + const CanardTransferKind transfer_kind, + const CanardPortID port_id) +{ + int8_t out = -CANARD_ERROR_INVALID_ARGUMENT; + const size_t tk = (size_t) transfer_kind; + if ((ins != NULL) && (tk < CANARD_NUM_TRANSFER_KINDS)) + { + CanardPortID port_id_mutable = port_id; + CanardRxSubscription* const sub = (CanardRxSubscription*) (void*) + cavlSearch(&ins->rx_subscriptions[tk], &port_id_mutable, &rxSubscriptionPredicateOnPortID, NULL); + if (sub != NULL) + { + cavlRemove(&ins->rx_subscriptions[tk], &sub->base); + CANARD_ASSERT(sub->port_id == port_id); + out = 1; + for (size_t i = 0; i < RX_SESSIONS_PER_SUBSCRIPTION; i++) + { + ins->memory_free(ins, (sub->sessions[i] != NULL) ? sub->sessions[i]->payload : NULL); + ins->memory_free(ins, sub->sessions[i]); + sub->sessions[i] = NULL; + } + } + else + { + out = 0; + } + } + return out; +} + +CanardFilter canardMakeFilterForSubject(const CanardPortID subject_id) +{ + CanardFilter out = {0}; + + out.extended_can_id = ((uint32_t) subject_id) << OFFSET_SUBJECT_ID; + out.extended_mask = FLAG_SERVICE_NOT_MESSAGE | FLAG_RESERVED_07 | (CANARD_SUBJECT_ID_MAX << OFFSET_SUBJECT_ID); + + return out; +} + +CanardFilter canardMakeFilterForService(const CanardPortID service_id, const CanardNodeID local_node_id) +{ + CanardFilter out = {0}; + + out.extended_can_id = FLAG_SERVICE_NOT_MESSAGE | (((uint32_t) service_id) << OFFSET_SERVICE_ID) | + (((uint32_t) local_node_id) << OFFSET_DST_NODE_ID); + out.extended_mask = FLAG_SERVICE_NOT_MESSAGE | FLAG_RESERVED_23 | (CANARD_SERVICE_ID_MAX << OFFSET_SERVICE_ID) | + (CANARD_NODE_ID_MAX << OFFSET_DST_NODE_ID); + + return out; +} + +CanardFilter canardMakeFilterForServices(const CanardNodeID local_node_id) +{ + CanardFilter out = {0}; + + out.extended_can_id = FLAG_SERVICE_NOT_MESSAGE | (((uint32_t) local_node_id) << OFFSET_DST_NODE_ID); + out.extended_mask = FLAG_SERVICE_NOT_MESSAGE | FLAG_RESERVED_23 | (CANARD_NODE_ID_MAX << OFFSET_DST_NODE_ID); + + return out; +} + +CanardFilter canardConsolidateFilters(const CanardFilter* a, const CanardFilter* b) +{ + CanardFilter out = {0}; + + out.extended_mask = a->extended_mask & b->extended_mask & ~(a->extended_can_id ^ b->extended_can_id); + out.extended_can_id = a->extended_can_id & out.extended_mask; + + return out; +} diff --git a/canard.h b/canard.h new file mode 100644 index 00000000..0f1b5a7c --- /dev/null +++ b/canard.h @@ -0,0 +1,699 @@ +/// ____ ______ __ __ +/// / __ `____ ___ ____ / ____/_ ______ / /_ ____ / / +/// / / / / __ `/ _ `/ __ `/ / / / / / __ `/ __ `/ __ `/ / +/// / /_/ / /_/ / __/ / / / /___/ /_/ / /_/ / / / / /_/ / / +/// `____/ .___/`___/_/ /_/`____/`__, / .___/_/ /_/`__,_/_/ +/// /_/ /____/_/ +/// +/// Libcanard is a compact implementation of the Cyphal/CAN protocol for high-integrity real-time embedded systems. +/// It is designed for use in robust deterministic embedded systems equipped with at least 32K ROM and 8K RAM. +/// The codebase follows the MISRA C rules, has 100% test coverage, and is validated by at least two static analyzers. +/// The library is designed to be compatible with any target platform and instruction set architecture, from 8 to 64 +/// bit, little- and big-endian, RTOS-based or baremetal, etc., as long as there is a standards-compliant compiler. +/// +/// INTEGRATION +/// +/// The library is intended to be integrated into the end application by simply copying its source files into the +/// source tree of the project; it does not require any special compilation options and should work out of the box. +/// There are build-time configuration parameters defined near the top of canard.c, but they are safe to ignore. +/// +/// As explained in this documentation, the library requires a deterministic constant-time bounded-fragmentation dynamic +/// memory allocator. If your target platform does not provide a deterministic memory manager (most platforms don't), +/// it is recommended to use O1Heap (MIT licensed): https://github.com/pavel-kirienko/o1heap. +/// +/// There are no specific requirements to the underlying I/O layer. Some low-level drivers maintained by the +/// OpenCyphal team may be found at https://github.com/OpenCyphal-Garage/platform_specific_components. +/// +/// If your application requires a MISRA C compliance report, please get in touch with the maintainers via the forum +/// at https://forum.opencyphal.org. +/// +/// ARCHITECTURE +/// +/// Cyphal, as a protocol stack, is composed of two layers: TRANSPORT and PRESENTATION. The transport layer is portable +/// across different transport protocols, one of which is CAN (FD), formally referred to as Cyphal/CAN. This library +/// is focused on Cyphal/CAN only and it will not support other transports. The presentation layer is implemented +/// through the DSDL language and the associated data type regulation policies; these parts are out of the scope of +/// this library as it is focused purely on the transport. +/// +/// This library consists of two components: the transmission (TX) pipeline and the reception (RX) pipeline. +/// The pipelines are completely independent from each other except that they both rely on the same dynamic memory +/// manager. The TX pipeline uses the dynamic memory to store outgoing CAN frames in the prioritized transmission +/// queue. The RX pipeline uses the dynamic memory to store contiguous payload buffers for received transfers and +/// for keeping the transfer reassembly state machine data. The exact memory consumption model is defined for both +/// pipelines, so it is possible to statically determine the minimum size of the dynamic memory pool required to +/// guarantee that a given application will never encounter an out-of-memory error at runtime. +/// +/// Much like with dynamic memory, the time complexity of every API function is well-characterized, allowing the +/// application to guarantee predictable real-time performance. +/// +/// The TX pipeline is managed with the help of four API functions. The first one -- canardTxInit() -- is used for +/// constructing a new TX queue, of which there should be as many as there are redundant CAN interfaces; +/// each queue is managed independently. When the application needs to emit a transfer, it invokes canardTxPush() +/// on each queue separately. The function splits the transfer into CAN frames and stores them into the queue. +/// The application then picks the produced CAN frames from the queue one-by-one by calling canardTxPeek() followed +/// by canardTxPop() -- the former allows the application to look at the next frame scheduled for transmission, +/// and the latter tells the library that the frame shall be removed from the queue. +/// Popped frames need to be manually deallocated by the application upon transmission. +/// +/// The RX pipeline is managed with the help of three API functions; unlike the TX pipeline, there is one shared +/// state for all redundant interfaces that manages deduplication transparently. The main function canardRxAccept() +/// takes a received CAN frame and updates the appropriate transfer reassembly state machine. The functions +/// canardRxSubscribe() and its counterpart canardRxUnsubscribe() instruct the library which transfers should be +/// received (by default, all transfers are ignored); also, the subscription function specifies vital transfer +/// reassembly parameters such as the maximum payload size (i.e., the maximum size of a serialized representation +/// of a DSDL object) and the transfer-ID timeout. Transfers that carry more payload than the configured maximum per +/// subscription are truncated following the Implicit Truncation Rule (ITR) defined by the Cyphal Specification -- +/// the rule is implemented to facilitate backward-compatible DSDL data type extensibility. +/// +/// The library supports a practically unlimited number of redundant interfaces. +/// +/// The library is not thread-safe: if used in a concurrent environment, it is the responsibility of the application +/// to provide adequate synchronization. +/// +/// The library is purely reactive: it does not perform any background processing and does not require periodic +/// servicing. Its internal state is only updated as a response to well-specified external events. +/// +/// -------------------------------------------------------------------------------------------------------------------- +/// +/// This software is distributed under the terms of the MIT License. +/// Copyright (c) 2016 OpenCyphal. +/// Author: Pavel Kirienko +/// Contributors: https://github.com/OpenCyphal/libcanard/contributors. + +#ifndef CANARD_H_INCLUDED +#define CANARD_H_INCLUDED + +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/// Semantic version of this library (not the Cyphal specification). +/// API will be backward compatible within the same major version. +#define CANARD_VERSION_MAJOR 3 +#define CANARD_VERSION_MINOR 1 + +/// The version number of the Cyphal specification implemented by this library. +#define CANARD_CYPHAL_SPECIFICATION_VERSION_MAJOR 1 +#define CANARD_CYPHAL_SPECIFICATION_VERSION_MINOR 0 + +/// These error codes may be returned from the library API calls whose return type is a signed integer in the negated +/// form (e.g., error code 2 returned as -2). A non-negative return value represents success. +/// API calls whose return type is not a signed integer cannot fail by contract. +/// No other error states may occur in the library. +/// By contract, a well-characterized application with a properly sized memory pool will never encounter errors. +/// The error code 1 is not used because -1 is often used as a generic error code in 3rd-party code. +#define CANARD_ERROR_INVALID_ARGUMENT 2 +#define CANARD_ERROR_OUT_OF_MEMORY 3 + +/// MTU values for the supported protocols. +/// Per the recommendations given in the Cyphal/CAN Specification, other MTU values should not be used. +#define CANARD_MTU_CAN_CLASSIC 8U +#define CANARD_MTU_CAN_FD 64U +#define CANARD_MTU_MAX CANARD_MTU_CAN_FD + +/// Parameter ranges are inclusive; the lower bound is zero for all. See Cyphal/CAN Specification for background. +#define CANARD_SUBJECT_ID_MAX 8191U +#define CANARD_SERVICE_ID_MAX 511U +#define CANARD_NODE_ID_MAX 127U +#define CANARD_PRIORITY_MAX 7U +#define CANARD_TRANSFER_ID_BIT_LENGTH 5U +#define CANARD_TRANSFER_ID_MAX ((1U << CANARD_TRANSFER_ID_BIT_LENGTH) - 1U) + +/// This value represents an undefined node-ID: broadcast destination or anonymous source. +/// Library functions treat all values above CANARD_NODE_ID_MAX as anonymous. +#define CANARD_NODE_ID_UNSET 255U + +/// This is the recommended transfer-ID timeout value given in the Cyphal Specification. The application may choose +/// different values per subscription (i.e., per data specifier) depending on its timing requirements. +#define CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC 2000000UL + +// Forward declarations. +typedef struct CanardInstance CanardInstance; +typedef struct CanardTreeNode CanardTreeNode; +typedef struct CanardTxQueueItem CanardTxQueueItem; +typedef uint64_t CanardMicrosecond; +typedef uint16_t CanardPortID; +typedef uint8_t CanardNodeID; +typedef uint8_t CanardTransferID; + +/// Transfer priority level mnemonics per the recommendations given in the Cyphal Specification. +typedef enum +{ + CanardPriorityExceptional = 0, + CanardPriorityImmediate = 1, + CanardPriorityFast = 2, + CanardPriorityHigh = 3, + CanardPriorityNominal = 4, ///< Nominal priority level should be the default. + CanardPriorityLow = 5, + CanardPrioritySlow = 6, + CanardPriorityOptional = 7, +} CanardPriority; + +/// Transfer kinds as defined by the Cyphal Specification. +typedef enum +{ + CanardTransferKindMessage = 0, ///< Multicast, from publisher to all subscribers. + CanardTransferKindResponse = 1, ///< Point-to-point, from server to client. + CanardTransferKindRequest = 2, ///< Point-to-point, from client to server. +} CanardTransferKind; +#define CANARD_NUM_TRANSFER_KINDS 3 + +/// The AVL tree node structure is exposed here to avoid pointer casting/arithmetics inside the library. +/// The user code is not expected to interact with this type except if advanced introspection is required. +struct CanardTreeNode +{ + CanardTreeNode* up; ///< Do not access this field. + CanardTreeNode* lr[2]; ///< Left and right children of this node may be accessed for tree traversal. + int8_t bf; ///< Do not access this field. +}; + +/// 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 +{ + /// 29-bit extended ID. The bits above 29-th shall be zero. + 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. + /// 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; +} CanardFrame; + +/// Conversion look-up table from CAN DLC to data length. +extern const uint8_t CanardCANDLCToLength[16]; + +/// Conversion look-up table from data length to CAN DLC; the length is rounded up. +extern const uint8_t CanardCANLengthToDLC[65]; + +/// A Cyphal transfer metadata (everything except the payload). +/// Per Specification, a transfer is represented on the wire as a non-empty set of transport frames (i.e., CAN frames). +/// The library is responsible for serializing transfers into transport frames when transmitting, and reassembling +/// transfers from an incoming stream of frames (possibly duplicated if redundant interfaces are used) during reception. +typedef struct +{ + /// Per the Specification, all frames belonging to a given transfer shall share the same priority level. + /// If this is not the case, then this field contains the priority level of the last frame to arrive. + CanardPriority priority; + + CanardTransferKind transfer_kind; + + /// Subject-ID for message publications; service-ID for service requests/responses. + CanardPortID port_id; + + /// For outgoing message transfers the value shall be CANARD_NODE_ID_UNSET (otherwise the state is invalid). + /// For outgoing service transfers this is the destination address (invalid if unset). + /// For incoming non-anonymous transfers this is the node-ID of the origin. + /// For incoming anonymous transfers the value is reported as CANARD_NODE_ID_UNSET. + CanardNodeID remote_node_id; + + /// When responding to a service request, the response transfer SHALL have the same transfer-ID value as the + /// request because the client will match the response with the request based on that. + /// + /// When publishing a message transfer, the value SHALL be one greater than the previous transfer under the same + /// subject-ID; the initial value should be zero. + /// + /// When publishing a service request transfer, the value SHALL be one greater than the previous transfer under + /// the same service-ID addressed to the same server node-ID; the initial value should be zero. + /// + /// Upon overflow, the value SHALL be reset back to zero. + /// Values above CANARD_TRANSFER_ID_MAX are permitted -- the library will compute the modulo automatically. + /// For received transfers, the values never exceed CANARD_TRANSFER_ID_MAX. + /// + /// A simple and robust way of managing transfer-ID counters is to keep a separate static variable per subject-ID + /// and per (service-ID, server-node-ID) pair. + CanardTransferID transfer_id; +} CanardTransferMetadata; + +/// Prioritized transmission queue that keeps CAN frames destined for transmission via one CAN interface. +/// Applications with redundant interfaces are expected to have one instance of this type per interface. +/// Applications that are not interested in transmission may have zero queues. +/// All operations (push, peek, pop) are O(log n); there is exactly one heap allocation per element. +/// API functions that work with this type are named "canardTx*()", find them below. +typedef struct CanardTxQueue +{ + /// The maximum number of frames this queue is allowed to contain. An attempt to push more will fail with an + /// out-of-memory error even if the memory is not exhausted. This value can be changed by the user at any moment. + /// The purpose of this limitation is to ensure that a blocked queue does not exhaust the heap memory. + size_t capacity; + + /// The transport-layer maximum transmission unit (MTU). The value can be changed arbitrarily at any time between + /// pushes. It defines the maximum number of data bytes per CAN data frame in outgoing transfers via this queue. + /// + /// Only the standard values should be used as recommended by the specification; + /// otherwise, networking interoperability issues may arise. See recommended values CANARD_MTU_*. + /// + /// Valid values are any valid CAN frame data length value not smaller than 8. + /// Invalid values are treated as the nearest valid value. The default is the maximum valid value. + size_t mtu_bytes; + + /// The number of frames that are currently contained in the queue, initially zero. + /// Do not modify this field! + size_t size; + + /// The root of the priority queue is NULL if the queue is empty. Do not modify this field! + CanardTreeNode* root; + + /// This field can be arbitrarily mutated by the user. It is never accessed by the library. + /// Its purpose is to simplify integration with OOP interfaces. + void* user_reference; +} CanardTxQueue; + +/// One frame stored in the transmission queue along with its metadata. +struct CanardTxQueueItem +{ + /// Internal use only; do not access this field. + CanardTreeNode base; + + /// Points to the next frame in this transfer or NULL. This field is mostly intended for own needs of the library. + /// Normally, the application would not use it because transfer frame ordering is orthogonal to global TX ordering. + /// It can be useful though for pulling pending frames from the TX queue if at least one frame of their transfer + /// failed to transmit; the idea is that if at least one frame is missing, the transfer will not be received by + /// remote nodes anyway, so all its remaining frames can be dropped from the queue at once using canardTxPop(). + CanardTxQueueItem* next_in_transfer; + + /// This is the same value that is passed to canardTxPush(). + /// Frames whose transmission deadline is in the past shall be dropped. + CanardMicrosecond tx_deadline_usec; + + /// The actual CAN frame data. + CanardFrame frame; +}; + +/// Transfer subscription state. The application can register its interest in a particular kind of data exchanged +/// over the bus by creating such subscription objects. Frames that carry data for which there is no active +/// subscription will be silently dropped by the library. The entire RX pipeline is invariant to the number of +/// redundant CAN interfaces used. +/// +/// SUBSCRIPTION INSTANCES SHALL NOT BE MOVED WHILE IN USE. +/// +/// The memory footprint of a subscription is large. On a 32-bit platform it slightly exceeds half a KiB. +/// This is an intentional time-memory trade-off: use a large look-up table to ensure predictable temporal properties. +typedef struct CanardRxSubscription +{ + CanardTreeNode base; ///< Read-only DO NOT MODIFY THIS + + CanardMicrosecond transfer_id_timeout_usec; + size_t extent; ///< Read-only DO NOT MODIFY THIS + CanardPortID port_id; ///< Read-only DO NOT MODIFY THIS + + /// This field can be arbitrarily mutated by the user. It is never accessed by the library. + /// Its purpose is to simplify integration with OOP interfaces. + void* user_reference; + + /// The current architecture is an acceptable middle ground between worst-case execution time and memory + /// consumption. Instead of statically pre-allocating a dedicated RX session for each remote node-ID here in + /// this table, we only keep pointers, which are NULL by default, populating a new RX session dynamically + /// on an ad-hoc basis when we first receive a transfer from that node. This is O(1) because our memory + /// allocation routines are assumed to be O(1) and we make at most one allocation per remote node. + /// + /// A more predictable and simpler approach is to pre-allocate states here statically instead of keeping + /// just pointers, but it would push the size of this instance from about 0.5 KiB to ~3 KiB for a typical 32-bit + /// system. Since this is a general-purpose library, we have to pick a middle ground so we use the more complex + /// but more memory-efficient approach. + struct CanardInternalRxSession* sessions[CANARD_NODE_ID_MAX + 1U]; ///< Read-only DO NOT MODIFY THIS +} CanardRxSubscription; + +/// Reassembled incoming transfer returned by canardRxAccept(). +typedef struct CanardRxTransfer +{ + CanardTransferMetadata metadata; + + /// The timestamp of the first received CAN frame of this transfer. + /// The time system may be arbitrary as long as the clock is monotonic (steady). + CanardMicrosecond timestamp_usec; + + /// If the payload is empty (payload_size = 0), the payload pointer may be NULL. + /// The application is required to deallocate the payload buffer after the transfer is processed. + size_t payload_size; + void* payload; +} CanardRxTransfer; + +/// A pointer to the memory allocation function. The semantics are similar to malloc(): +/// - The returned pointer shall point to an uninitialized block of memory that is at least "amount" bytes large. +/// - If there is not enough memory, the returned pointer shall be NULL. +/// - The memory shall be aligned at least at max_align_t. +/// - The execution time should be constant (O(1)). +/// - The worst-case memory fragmentation should be bounded and easily predictable. +/// If the standard dynamic memory manager of the target platform does not satisfy the above requirements, +/// consider using O1Heap: https://github.com/pavel-kirienko/o1heap. +typedef void* (*CanardMemoryAllocate)(CanardInstance* ins, size_t amount); + +/// The counterpart of the above -- this function is invoked to return previously allocated memory to the allocator. +/// The semantics are similar to free(): +/// - The pointer was previously returned by the allocation function. +/// - The pointer may be NULL, in which case the function shall have no effect. +/// - The execution time should be constant (O(1)). +typedef void (*CanardMemoryFree)(CanardInstance* ins, void* pointer); + +/// This is the core structure that keeps all of the states and allocated resources of the library instance. +struct CanardInstance +{ + /// User pointer that can link this instance with other objects. + /// This field can be changed arbitrarily, the library does not access it after initialization. + /// The default value is NULL. + void* user_reference; + + /// The node-ID of the local node. + /// Per the Cyphal Specification, the node-ID should not be assigned more than once. + /// Invalid values are treated as CANARD_NODE_ID_UNSET. The default value is CANARD_NODE_ID_UNSET. + CanardNodeID node_id; + + /// Dynamic memory management callbacks. See their type documentation for details. + /// They SHALL be valid function pointers at all times. + /// The time complexity models given in the API documentation are made on the assumption that the memory management + /// functions have constant complexity O(1). + /// + /// The following API functions may allocate memory: canardRxAccept(), canardTxPush(). + /// The following API functions may deallocate memory: canardRxAccept(), canardRxSubscribe(), canardRxUnsubscribe(). + /// The exact memory requirement and usage model is specified for each function in its documentation. + CanardMemoryAllocate memory_allocate; + CanardMemoryFree memory_free; + + /// Read-only DO NOT MODIFY THIS + CanardTreeNode* rx_subscriptions[CANARD_NUM_TRANSFER_KINDS]; +}; + +/// CAN acceptance filter configuration with an extended 29-bit ID utilizing an ID + mask filter scheme. +/// Filter configuration can be programmed into a CAN controller to filter out irrelevant messages in hardware. +/// This allows the software application to reduce CPU load spent on processing irrelevant messages. +typedef struct CanardFilter +{ + /// 29-bit extended ID. Defines the extended CAN ID to filter incoming frames against. + /// The bits above 29-th shall be zero. + uint32_t extended_can_id; + /// 29-bit extended mask. Defines the bitmask used to enable/disable bits used to filter messages. + /// Only bits that are enabled are compared to the extended_can_id for filtering. + /// The bits above 29-th shall be zero. + uint32_t extended_mask; +} CanardFilter; + +/// Construct a new library instance. +/// The default values will be assigned as specified in the structure field documentation. +/// If any of the pointers are NULL, the behavior is undefined. +/// +/// The instance does not hold any resources itself except for the allocated memory. +/// To safely discard it, simply remove all existing subscriptions, and don't forget about the TX queues. +/// +/// The time complexity is constant. This function does not invoke the dynamic memory manager. +CanardInstance canardInit(const CanardMemoryAllocate memory_allocate, const CanardMemoryFree memory_free); + +/// Construct a new transmission queue instance with the specified values for capacity and mtu_bytes. +/// No memory allocation is going to take place until the queue is actually pushed to. +/// Applications are expected to have one instance of this type per redundant interface. +/// +/// The instance does not hold any resources itself except for the allocated memory. +/// To safely discard it, simply pop all items from the queue. +/// +/// The time complexity is constant. This function does not invoke the dynamic memory manager. +CanardTxQueue canardTxInit(const size_t capacity, const size_t mtu_bytes); + +/// This function serializes a transfer into a sequence of transport frames and inserts them into the prioritized +/// transmission queue at the appropriate position. Afterwards, the application is supposed to take the enqueued frames +/// from the transmission queue using the function canardTxPeek() and transmit them. Each transmitted (or otherwise +/// discarded, e.g., due to timeout) frame should be removed from the queue using canardTxPop(). The queue is +/// prioritized following the normal CAN frame arbitration rules to avoid the inner priority inversion. The transfer +/// payload will be copied into the transmission queue so that the lifetime of the frames is not related to the +/// lifetime of the input payload buffer. +/// +/// The MTU of the generated frames is dependent on the value of the MTU setting at the time when this function +/// is invoked. The MTU setting can be changed arbitrarily between invocations. +/// +/// The tx_deadline_usec will be used to populate the timestamp values of the resulting transport +/// frames (so all frames will have the same timestamp value). This feature is intended to facilitate transmission +/// deadline tracking, i.e., aborting frames that could not be transmitted before the specified deadline. +/// Therefore, normally, the timestamp value should be in the future. +/// The library itself, however, does not use or check this value in any way, so it can be zero if not needed. +/// +/// The function returns the number of frames enqueued into the prioritized TX queue (which is always a positive +/// number) in case of success (so that the application can track the number of items in the TX queue if necessary). +/// In case of failure, the function returns a negated error code: either invalid argument or out-of-memory. +/// +/// An invalid argument error may be returned in the following cases: +/// - Any of the input arguments are NULL. +/// - The remote node-ID is not CANARD_NODE_ID_UNSET and the transfer is a message transfer. +/// - The remote node-ID is above CANARD_NODE_ID_MAX and the transfer is a service transfer. +/// - The priority, subject-ID, or service-ID exceed their respective maximums. +/// - The transfer kind is invalid. +/// - The payload pointer is NULL while the payload size is nonzero. +/// - The local node is anonymous and a message transfer is requested that requires a multi-frame transfer. +/// - The local node is anonymous and a service transfer is requested. +/// The following cases are handled without raising an invalid argument error: +/// - If the transfer-ID is above the maximum, the excessive bits are silently masked away +/// (i.e., the modulo is computed automatically, so the caller doesn't have to bother). +/// +/// An out-of-memory error is returned if a TX frame could not be allocated due to the memory being exhausted, +/// or if the capacity of the queue would be exhausted by this operation. In such cases, all frames allocated for +/// this transfer (if any) will be deallocated automatically. In other words, either all frames of the transfer are +/// enqueued successfully, or none are. +/// +/// The time complexity is O(p + log e), where p is the amount of payload in the transfer, and e is the number of +/// frames already enqueued in the transmission queue. +/// +/// The memory allocation requirement is one allocation per transport frame. A single-frame transfer takes one +/// allocation; a multi-frame transfer of N frames takes N allocations. The size of each allocation is +/// (sizeof(CanardTxQueueItem) + MTU). +int32_t canardTxPush(CanardTxQueue* const que, + CanardInstance* const ins, + const CanardMicrosecond tx_deadline_usec, + const CanardTransferMetadata* const metadata, + const size_t payload_size, + const void* const 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 +/// frames of serialized transfers pushed into the prioritized transmission queue by canardTxPush(). +/// +/// The timestamp values of returned frames are initialized with tx_deadline_usec from canardTxPush(). +/// Timestamps are used to specify the transmission deadline. It is up to the application and/or the media layer +/// to implement the discardment of timed-out transport frames. The library does not check it, so a frame that is +/// already timed out may be returned here. +/// +/// If the queue is empty or if the argument is NULL, the returned value is NULL. +/// +/// If the queue is non-empty, the returned value is a pointer to its top element (i.e., the next frame to transmit). +/// The returned pointer points to an object allocated in the dynamic storage; it should be eventually freed by the +/// application by calling CanardInstance::memory_free(). The memory shall not be freed before the entry is removed +/// from the queue by calling canardTxPop(); this is because until canardTxPop() is executed, the library retains +/// ownership of the object. The pointer retains validity until explicitly freed by the application; in other words, +/// calling canardTxPop() does not invalidate the object. +/// +/// The payload buffer is located shortly after the object itself, in the same memory fragment. The application shall +/// not attempt to free it. +/// +/// The time complexity is logarithmic of the queue size. This function does not invoke the dynamic memory manager. +const CanardTxQueueItem* canardTxPeek(const CanardTxQueue* const que); + +/// This function transfers the ownership of the specified element of the prioritized transmission queue from the queue +/// to the application. The element does not necessarily need to be the top one -- it is safe to dequeue any element. +/// The element is dequeued but not invalidated; it is the responsibility of the application to deallocate the +/// memory used by the object later. The memory SHALL NOT be deallocated UNTIL this function is invoked. +/// The function returns the same pointer that it is given except that it becomes mutable. +/// +/// If any of the arguments are NULL, the function has no effect and returns NULL. +/// +/// The time complexity is logarithmic of the queue size. This function does not invoke the dynamic memory manager. +CanardTxQueueItem* canardTxPop(CanardTxQueue* const que, const CanardTxQueueItem* const item); + +/// This function implements the transfer reassembly logic. It accepts a transport frame from any of the redundant +/// interfaces, locates the appropriate subscription state, and, if found, updates it. If the frame completed a +/// transfer, the return value is 1 (one) and the out_transfer pointer is populated with the parameters of the +/// newly reassembled transfer. The transfer reassembly logic is defined in the Cyphal specification. +/// +/// The MTU of the accepted frame can be arbitrary; that is, any MTU is accepted. The DLC validity is irrelevant. +/// +/// Any value of redundant_iface_index is accepted; that is, up to 256 redundant interfaces are supported. +/// The index of the interface from which the transfer is accepted is always the same as redundant_iface_index +/// of the current invocation, so the application can always determine which interface has delivered the transfer. +/// +/// Upon return, the out_subscription pointer will point to the instance of CanardRxSubscription that accepted this +/// frame; if no matching subscription exists (i.e., frame discarded), the pointer will be NULL. +/// If this information is not relevant, set out_subscription to NULL. +/// The purpose of this argument is to allow integration with OOP adapters built on top of libcanard; see also the +/// user_reference provided in CanardRxSubscription. +/// +/// The function invokes the dynamic memory manager in the following cases only: +/// +/// 1. New memory for a session state object is allocated when a new session is initiated. +/// This event occurs when a transport frame that matches a known subscription is received from a node that +/// did not emit matching frames since the subscription was created. +/// Once a new session is created, it is not destroyed until the subscription is terminated by invoking +/// canardRxUnsubscribe(). The number of sessions is bounded and the bound is low (at most the number of nodes +/// in the network minus one), also the size of a session instance is very small, so the removal is unnecessary. +/// Real-time networks typically do not change their configuration at runtime, so it is possible to reduce +/// the time complexity by never deallocating sessions. +/// The size of a session instance is at most 48 bytes on any conventional platform (typically much smaller). +/// +/// 2. New memory for the transfer payload buffer is allocated when a new transfer is initiated, unless the buffer +/// was already allocated at the time. +/// This event occurs when a transport frame that matches a known subscription is received and it begins a +/// new transfer (that is, the start-of-frame flag is set and it is not a duplicate). +/// The amount of the allocated memory equals the extent as configured via canardRxSubscribe(); please read +/// its documentation for further information about the extent and related edge cases. +/// The worst case occurs when every node on the bus initiates a multi-frame transfer for which there is a +/// matching subscription: in this case, the library will allocate number_of_nodes allocations, where each +/// allocation is the same size as the configured extent. +/// +/// 3. Memory allocated for the transfer payload buffer may be deallocated at the discretion of the library. +/// This operation does not increase the worst case execution time and does not improve the worst case memory +/// consumption, so a deterministic application need not consider this behavior in the resource analysis. +/// This behavior is implemented for the benefit of applications where rigorous characterization is unnecessary. +/// +/// The worst case dynamic memory consumption per subscription is: +/// +/// (sizeof(session instance) + extent) * number_of_nodes +/// +/// Where sizeof(session instance) and extent are defined above, and number_of_nodes is the number of remote +/// nodes emitting transfers that match the subscription (which cannot exceed (CANARD_NODE_ID_MAX-1) by design). +/// If the dynamic memory pool is sized correctly, the application is guaranteed to never encounter an +/// out-of-memory (OOM) error at runtime. The actual size of the dynamic memory pool is typically larger; +/// for a detailed treatment of the problem and the related theory please refer to the documentation of O1Heap -- +/// a deterministic memory allocator for hard real-time embedded systems. +/// +/// The time complexity is O(p + log n) where n is the number of subject-IDs or service-IDs subscribed to by the +/// application, depending on the transfer kind of the supplied frame, and p is the amount of payload in the received +/// frame (because it will be copied into an internal contiguous buffer). Observe that the time complexity is +/// invariant to the network configuration (such as the number of online nodes) -- this is a very important +/// design guarantee for real-time applications because the execution time is dependent only on the number of +/// active subscriptions for a given transfer kind, and the MTU, both of which are easy to predict and account for. +/// Excepting the subscription search and the payload data copying, the entire RX pipeline contains neither loops +/// nor recursion. +/// Misaddressed and malformed frames are discarded in constant time. +/// +/// The function returns 1 (one) if the new frame completed a transfer. In this case, the details of the transfer +/// are stored into out_transfer, and the transfer payload buffer ownership is passed to that object. The lifetime +/// of the resulting transfer object is not related to the lifetime of the input transport frame (that is, even if +/// it is a single-frame transfer, its payload is copied out into a new dynamically allocated buffer storage). +/// If the extent is zero, the payload pointer may be NULL, since there is no data to store and so a +/// buffer is not needed. The application is responsible for deallocating the payload buffer when the processing +/// is done by invoking memory_free on the transfer payload pointer. +/// +/// The function returns a negated out-of-memory error if it was unable to allocate dynamic memory. +/// +/// The function does nothing and returns a negated invalid argument error immediately if any condition is true: +/// - Any of the input arguments that are pointers are NULL. +/// - The payload pointer of the input frame is NULL while its size is non-zero. +/// - The CAN ID of the input frame is not less than 2**29=0x20000000. +/// +/// The function returns zero if any of the following conditions are true (the general policy is that protocol +/// errors are not escalated because they do not construe a node-local error): +/// - The received frame is not a valid Cyphal/CAN transport frame. +/// - The received frame is a valid Cyphal/CAN transport frame, but there is no matching subscription, +/// the frame did not complete a transfer, the frame forms an invalid frame sequence, the frame is a duplicate, +/// the frame is unicast to a different node (address mismatch). +int8_t canardRxAccept(CanardInstance* const ins, + const CanardMicrosecond timestamp_usec, + const CanardFrame* const frame, + const uint8_t redundant_iface_index, + CanardRxTransfer* const out_transfer, + CanardRxSubscription** const out_subscription); + +/// This function creates a new subscription, allowing the application to register its interest in a particular +/// category of transfers. The library will reject all transport frames for which there is no active subscription. +/// The reference out_subscription shall retain validity until the subscription is terminated (the referred object +/// cannot be moved or destroyed). +/// +/// If such subscription already exists, it will be removed first as if canardRxUnsubscribe() was +/// invoked by the application, and then re-created anew with the new parameters. +/// +/// The extent defines the size of the transfer payload memory buffer; or, in other words, the maximum possible size +/// of received objects, considering also possible future versions with new fields. It is safe to pick larger values. +/// Note well that the extent is not the same thing as the maximum size of the object, it is usually larger! +/// Transfers that carry payloads that exceed the specified extent will be accepted anyway but the excess payload +/// will be truncated away, as mandated by the Specification. The transfer CRC is always validated regardless of +/// whether its payload is truncated. +/// +/// The default transfer-ID timeout value is defined as CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC; use it if not sure. +/// The redundant interface fail-over timeout (if redundant interfaces are used) is the same as the transfer-ID timeout. +/// It may be reduced in a future release of the library, but it will not affect the backward compatibility. +/// +/// The return value is 1 if a new subscription has been created as requested. +/// The return value is 0 if such subscription existed at the time the function was invoked. In this case, +/// the existing subscription is terminated and then a new one is created in its place. Pending transfers may be lost. +/// The return value is a negated invalid argument error if any of the input arguments are invalid. +/// +/// The time complexity is logarithmic from the number of current subscriptions under the specified transfer kind. +/// This function does not allocate new memory. The function may deallocate memory if such subscription already +/// existed; the deallocation behavior is specified in the documentation for canardRxUnsubscribe(). +/// +/// Subscription instances have large look-up tables to ensure that the temporal properties of the algorithms are +/// invariant to the network configuration (i.e., a node that is validated on a network containing one other node +/// will provably perform identically on a network that contains X nodes). This is a conscious time-memory trade-off. +int8_t canardRxSubscribe(CanardInstance* const ins, + const CanardTransferKind transfer_kind, + const CanardPortID port_id, + const size_t extent, + const CanardMicrosecond transfer_id_timeout_usec, + CanardRxSubscription* const out_subscription); + +/// This function reverses the effect of canardRxSubscribe(). +/// If the subscription is found, all its memory is de-allocated (session states and payload buffers); to determine +/// the amount of memory freed, please refer to the memory allocation requirement model of canardRxAccept(). +/// +/// The return value is 1 if such subscription existed (and, therefore, it was removed). +/// The return value is 0 if such subscription does not exist. In this case, the function has no effect. +/// The return value is a negated invalid argument error if any of the input arguments are invalid. +/// +/// The time complexity is logarithmic from the number of current subscriptions under the specified transfer kind. +/// This function does not allocate new memory. +int8_t canardRxUnsubscribe(CanardInstance* const ins, + const CanardTransferKind transfer_kind, + const CanardPortID port_id); + +/// Utilities for generating CAN controller hardware acceptance filter configurations +/// to accept specific subjects, services, or nodes. +/// +/// Complex applications will likely subscribe to more subject IDs than there are +/// acceptance filters available in the CAN hardware. In this case, the application +/// should implement filter consolidation. See canardConsolidateFilters() +/// as well as the Cyphal specification for details. + +/// Generate an acceptance filter configuration to accept a specific subject ID. +CanardFilter canardMakeFilterForSubject(const CanardPortID subject_id); + +/// Generate an acceptance filter configuration to accept both requests and responses for a specific service. +/// +/// Users may prefer to instead use a catch-all acceptance filter configuration for accepting +/// all service requests and responses targeted at the specified local node ID. +/// See canardMakeFilterForServices() for this. +CanardFilter canardMakeFilterForService(const CanardPortID service_id, const CanardNodeID local_node_id); + +/// Generate an acceptance filter configuration to accept all service +/// requests and responses targeted to the specified local node ID. +/// +/// Due to the relatively low frequency of service transfers expected on a network, +/// and the fact that a service directed at a specific node is not likely to be rejected by that node, +/// a user may prefer to use this over canardMakeFilterForService() +/// in order to simplify the API usage and reduce the number of required hardware CAN acceptance filters. +CanardFilter canardMakeFilterForServices(const CanardNodeID local_node_id); + +/// Consolidate two acceptance filter configurations into a single configuration. +/// +/// Complex applications will likely subscribe to more subject IDs than there are +/// acceptance filters available in the CAN hardware. In this case, the application +/// should implement filter consolidation. While this may make it impossible to create +/// a 'perfect' filter that only accepts desired subject IDs, the application should apply +/// consolidation in a manner that minimizes the number of undesired messages that pass +/// through the hardware acceptance filters and require software filtering (implemented by canardRxSubscribe). +/// +/// While optimal choice of filter consolidation is a function of the number of available hardware filters, +/// the set of transfers needed by the application, and the expected frequency of occurrence +/// of all possible distinct transfers on the bus, it is possible to generate a quasi-optimal configuration +/// if information about the frequency of occurrence of different transfers is not known. +/// For details, see the "Automatic hardware acceptance filter configuration" note under the Cyphal/CAN section +/// in the Transport Layer chapter of the Cyphal specification. +CanardFilter canardConsolidateFilters(const CanardFilter* const a, const CanardFilter* const b); + +#ifdef __cplusplus +} +#endif +#endif