diff --git a/examples/CAN/host-example-01-opencyphal-basic-node/kv_host.cpp b/examples/CAN/host-example-01-opencyphal-basic-node/kv_host.cpp index d530667d..dd0d3df5 100644 --- a/examples/CAN/host-example-01-opencyphal-basic-node/kv_host.cpp +++ b/examples/CAN/host-example-01-opencyphal-basic-node/kv_host.cpp @@ -11,29 +11,37 @@ #include "kv_host.h" -#if !defined(__GNUC__) || (__GNUC__ >= 11) - #include - -#include #include +#include + +#include /************************************************************************************** * NAMESPACE **************************************************************************************/ -namespace cyphal::support::platform::storage::host -{ +namespace cyphal::support::platform::storage::host { /************************************************************************************** * PRIVATE FREE FUNCTIONS **************************************************************************************/ -[[nodiscard]] static inline std::string toFilename(std::string_view const key) -{ +[[nodiscard]] static inline std::string toFilename(std::string_view const key) { auto const key_hash = std::hash{}(key); + const std::string dir_path = "ros_nodes/firmware_bridge/cyphal_registry/"; + + // Check if the directory exists + struct stat info; + if (stat(dir_path.c_str(), &info) != 0 || + !(info.st_mode & S_IFDIR)) { // Path does not exist or is not a directory + // Create the directory with read/write/search permissions for owner and group, and with read/search + // permissions for others. + mkdir(dir_path.c_str(), 0755); + } + std::stringstream key_filename; - key_filename << key_hash; + key_filename << dir_path << key_hash; return key_filename.str(); } @@ -41,37 +49,34 @@ namespace cyphal::support::platform::storage::host * PUBLIC MEMBER FUNCTIONS **************************************************************************************/ -auto KeyValueStorage::get(const std::string_view key, const std::size_t size, void* const data) const - -> std::variant -{ +auto KeyValueStorage::get(const std::string_view key, const std::size_t size, + void* const data) const -> std::variant { std::ifstream in(toFilename(key), std::ifstream::in | std::ifstream::binary); if (!in.good()) return Error::Existence; - in.read(static_cast(data), size); + in.read(static_cast(data), size); size_t const bytes_read = in ? size : in.gcount(); in.close(); return bytes_read; } -auto KeyValueStorage::put(const std::string_view key, const std::size_t size, const void* const data) - -> std::optional -{ +auto KeyValueStorage::put(const std::string_view key, const std::size_t size, + const void* const data) -> std::optional { std::ofstream out(toFilename(key), std::ofstream::in | std::ofstream::binary | std::ofstream::trunc); if (!out.good()) return Error::Existence; - out.write(static_cast(data), size); + out.write(static_cast(data), size); out.close(); return std::nullopt; } -auto KeyValueStorage::drop(const std::string_view key) -> std::optional -{ +auto KeyValueStorage::drop(const std::string_view key) -> std::optional { if (std::remove(toFilename(key).c_str())) return Error::IO; @@ -82,6 +87,5 @@ auto KeyValueStorage::drop(const std::string_view key) -> std::optional * NAMESPACE **************************************************************************************/ -} /* cyphal::support::platform::storage::host */ +} // namespace cyphal::support::platform::storage::host -#endif /* !defined(__GNUC__) || (__GNUC__ >= 11) */ diff --git a/examples/CAN/host-example-01-opencyphal-basic-node/kv_host.h b/examples/CAN/host-example-01-opencyphal-basic-node/kv_host.h index fcd6ed42..9767a409 100644 --- a/examples/CAN/host-example-01-opencyphal-basic-node/kv_host.h +++ b/examples/CAN/host-example-01-opencyphal-basic-node/kv_host.h @@ -13,7 +13,6 @@ #include <107-Arduino-Cyphal.h> -#if !defined(__GNUC__) || (__GNUC__ >= 11) /************************************************************************************** * NAMESPACE @@ -51,4 +50,4 @@ class KeyValueStorage final : public interface::KeyValueStorage } /* cyphal::support::platform::storage::host */ -#endif /* !defined(__GNUC__) || (__GNUC__ >= 11) */ + diff --git a/examples/CAN/host-example-01-opencyphal-basic-node/socketcan.c b/examples/CAN/host-example-01-opencyphal-basic-node/socketcan.c index f5b1c9a8..291a03b9 100644 --- a/examples/CAN/host-example-01-opencyphal-basic-node/socketcan.c +++ b/examples/CAN/host-example-01-opencyphal-basic-node/socketcan.c @@ -26,11 +26,13 @@ #include #include #include +#include +#include #define KILO 1000L #define MEGA (KILO * KILO) -static int16_t getNegatedErrno() +static int16_t getNegatedErrno(void) { const int out = -abs(errno); if (out < 0) @@ -116,12 +118,12 @@ SocketCANFD socketcanOpen(const char* const iface_name, const bool can_fd) ok = 0 == setsockopt(fd, SOL_SOCKET, SO_TIMESTAMP, &en, sizeof(en)); } - // Enable outgoing-frame loop-back. - if (ok) - { - const int en = 1; - ok = 0 == setsockopt(fd, SOL_CAN_RAW, CAN_RAW_RECV_OWN_MSGS, &en, sizeof(en)); - } + // // Enable outgoing-frame loop-back. + // if (ok) + // { + // const int en = 1; + // ok = 0 == setsockopt(fd, SOL_CAN_RAW, CAN_RAW_RECV_OWN_MSGS, &en, sizeof(en)); + // } if (ok) { @@ -164,12 +166,13 @@ int16_t socketcanPush(const SocketCANFD fd, const CanardFrame* const frame, cons return poll_result; } -int16_t socketcanPop(const SocketCANFD fd, - CanardFrame* const out_frame, - const size_t payload_buffer_size, - void* const payload_buffer, - const CanardMicrosecond timeout_usec, - bool* const loopback) +int16_t socketcanPop(const SocketCANFD fd, + CanardFrame* const out_frame, + CanardMicrosecond* const out_timestamp_usec, + const size_t payload_buffer_size, + void* const payload_buffer, + const CanardMicrosecond timeout_usec, + bool* const loopback) { if ((out_frame == NULL) || (payload_buffer == NULL)) { @@ -185,8 +188,8 @@ int16_t socketcanPop(const SocketCANFD fd, struct canfd_frame sockcan_frame = {0}; // CAN FD frame storage. struct iovec iov = { // Scatter/gather array items struct. - .iov_base = &sockcan_frame, // Starting address. - .iov_len = sizeof(sockcan_frame) // Number of bytes to transfer. + .iov_base = &sockcan_frame, // Starting address. + .iov_len = sizeof(sockcan_frame) // Number of bytes to transfer. }; @@ -223,6 +226,8 @@ int16_t socketcanPop(const SocketCANFD fd, return -EFBIG; } + // printf("RX = CAN ID:0x%x, Length:%d, Flags:%d\n", sockcan_frame.can_id, sockcan_frame.len, sockcan_frame.flags); + const bool valid = ((sockcan_frame.can_id & CAN_EFF_FLAG) != 0) && // Extended frame ((sockcan_frame.can_id & CAN_ERR_FLAG) == 0) && // Not RTR frame ((sockcan_frame.can_id & CAN_RTR_FLAG) == 0); // Not error frame @@ -244,21 +249,25 @@ int16_t socketcanPop(const SocketCANFD fd, // Obtain the CAN frame time stamp from the kernel. // This time stamp is from the CLOCK_REALTIME kernel source. - const struct cmsghdr* cmsg = CMSG_FIRSTHDR(&msg); - struct timeval tv = {0}; - assert(cmsg != NULL); - if (cmsg->cmsg_level == SOL_SOCKET && cmsg->cmsg_type == SO_TIMESTAMP) + if (NULL != out_timestamp_usec) { - (void) memcpy(&tv, CMSG_DATA(cmsg), sizeof(tv)); // Copy to avoid alignment problems - assert(tv.tv_sec >= 0 && tv.tv_usec >= 0); + const struct cmsghdr* cmsg = CMSG_FIRSTHDR(&msg); + struct timeval tv = {0}; + assert(cmsg != NULL); + if ((cmsg->cmsg_level == SOL_SOCKET) && (cmsg->cmsg_type == SO_TIMESTAMP)) + { + (void) memcpy(&tv, CMSG_DATA(cmsg), sizeof(tv)); // Copy to avoid alignment problems + assert(tv.tv_sec >= 0 && tv.tv_usec >= 0); + } + else + { + assert(0); + return -EIO; + } + + (void) memset(out_frame, 0, sizeof(CanardFrame)); + *out_timestamp_usec = (CanardMicrosecond) (((uint64_t) tv.tv_sec * MEGA) + (uint64_t) tv.tv_usec); } - else - { - assert(0); - return -EIO; - } - - (void) memset(out_frame, 0, sizeof(CanardFrame)); out_frame->extended_can_id = sockcan_frame.can_id & CAN_EFF_MASK; out_frame->payload_size = sockcan_frame.len; out_frame->payload = payload_buffer; @@ -267,7 +276,7 @@ int16_t socketcanPop(const SocketCANFD fd, return poll_result; } -int16_t socketcanFilter(const SocketCANFD fd, const size_t num_configs, const SocketCANFilterConfig* const configs) +int16_t socketcanFilter(const SocketCANFD fd, const size_t num_configs, const CanardFilter* const configs) { if (configs == NULL) { @@ -281,12 +290,12 @@ int16_t socketcanFilter(const SocketCANFD fd, const size_t num_configs, const So struct can_filter cfs[CAN_RAW_FILTER_MAX]; for (size_t i = 0; i < num_configs; i++) { - cfs[i].can_id = (configs[i].extended_id & CAN_EFF_MASK) | CAN_EFF_FLAG; - cfs[i].can_mask = (configs[i].mask & CAN_EFF_MASK) | CAN_EFF_FLAG | CAN_RTR_FLAG; + cfs[i].can_id = (configs[i].extended_can_id & CAN_EFF_MASK) | CAN_EFF_FLAG; + cfs[i].can_mask = (configs[i].extended_mask & CAN_EFF_MASK) | CAN_EFF_FLAG | CAN_RTR_FLAG; } const int ret = - setsockopt(fd, SOL_CAN_RAW, CAN_RAW_FILTER, cfs, (socklen_t)(sizeof(struct can_filter) * num_configs)); + setsockopt(fd, SOL_CAN_RAW, CAN_RAW_FILTER, cfs, (socklen_t) (sizeof(struct can_filter) * num_configs)); return (ret < 0) ? getNegatedErrno() : 0; } diff --git a/examples/CAN/host-example-01-opencyphal-basic-node/socketcan.h b/examples/CAN/host-example-01-opencyphal-basic-node/socketcan.h index 8eb82e6d..0a07e149 100644 --- a/examples/CAN/host-example-01-opencyphal-basic-node/socketcan.h +++ b/examples/CAN/host-example-01-opencyphal-basic-node/socketcan.h @@ -1,10 +1,9 @@ -/// __ __ _______ __ __ _______ _______ __ __ -/// | | | | / _ ` | | | | / ____| / _ ` | ` | | -/// | | | | | |_| | | | | | | | | |_| | | `| | -/// | |_| | | _ | ` `_/ / | |____ | _ | | |` | -/// `_______/ |__| |__| `_____/ `_______| |__| |__| |__| `__| -/// | | | | | | -/// ----o------o------------o---------o------o---------o------- +/// ____ ______ __ __ +/// / __ `____ ___ ____ / ____/_ ______ / /_ ____ / / +/// / / / / __ `/ _ `/ __ `/ / / / / / __ `/ __ `/ __ `/ / +/// / /_/ / /_/ / __/ / / / /___/ /_/ / /_/ / / / / /_/ / / +/// `____/ .___/`___/_/ /_/`____/`__, / .___/_/ /_/`__,_/_/ +/// /_/ /____/_/ /// /// This is a basic adapter library that bridges Libcanard with SocketCAN. /// Read the API documentation for usage information. @@ -14,6 +13,8 @@ /// -------------------------------------------------------------------------------------------------------------------- /// Changelog /// +/// v3.0 - Update for compatibility with Libcanard v3. +/// /// v2.0 - Added loop-back functionality. /// API change in socketcanPop(): loopback flag added. /// - Changed to kernel-based time-stamping for received frames for improved accuracy. @@ -23,67 +24,88 @@ /// -------------------------------------------------------------------------------------------------------------------- /// /// This software is distributed under the terms of the MIT License. -/// Copyright (c) 2020 UAVCAN Development Team. +/// Copyright (c) 2020 OpenCyphal /// Author: Pavel Kirienko #ifndef SOCKETCAN_H_INCLUDED #define SOCKETCAN_H_INCLUDED -#include + +#include "canard.h" #include #include -#include #ifdef __cplusplus extern "C" { #endif -/// File descriptor alias. +/* File descriptor alias. */ typedef int SocketCANFD; -/// Initialize a new non-blocking (sic!) SocketCAN socket and return its handle on success. -/// On failure, a negated errno is returned. -/// To discard the socket just call close() on it; no additional de-initialization activities are required. -/// The argument can_fd enables support for CAN FD frames. +/** + * @brief Initialize a new non-blocking (sic!) SocketCAN socket. + * To discard the socket just call close() on it; no additional de-initialization activities are + * required. The argument can_fd enables support for CAN FD frames. + * + * @param[in] iface_name name of the CAN interface, e.g., "can0, vcan0" + * @param[in] can_fd true for CAN FD mode, false if only classic CAN frames are to be supported. + * + * @return socket handle on success, negated errno on error. + */ SocketCANFD socketcanOpen(const char* const iface_name, const bool can_fd); -/// Enqueue a new extended CAN data frame for transmission. -/// Block until the frame is enqueued or until the timeout is expired. -/// Zero timeout makes the operation non-blocking. -/// Returns 1 on success, 0 on timeout, negated errno on error. +/** + * @brief Enqueue a new extended CAN data frame for transmission. + * Block until the frame is enqueued or until the timeout is expired. + * + * @param fd the socket handle. + * @param[in] frame the frame to be transmitted. Zero timeout makes the operation non-blocking. + * @param timeout_usec timeout in microseconds. + * + * @return 1 on success, 0 on timeout, negated errno on error. + */ int16_t socketcanPush(const SocketCANFD fd, const CanardFrame* const frame, const CanardMicrosecond timeout_usec); -/// Fetch a new extended CAN data frame from the RX queue. -/// If the received frame is not an extended-ID data frame, it will be dropped and the function will return early. -/// The payload pointer of the returned frame will point to the payload_buffer. It can be a stack-allocated array. -/// The payload_buffer_size shall be large enough (64 bytes is enough for CAN FD), otherwise an error is returned. -/// The received frame timestamp will be set to CLOCK_REALTIME by the kernel, sampled near the moment of its arrival. -/// The loopback flag pointer is used to both indicate and control behavior when a looped-back message is received. -/// If the flag pointer is NULL, loopback frames are silently dropped; if not NULL, they are accepted and indicated -/// using this flag. -/// The function will block until a frame is received or until the timeout is expired. It may return early. -/// Zero timeout makes the operation non-blocking. -/// Returns 1 on success, 0 on timeout, negated errno on error. -int16_t socketcanPop(const SocketCANFD fd, - CanardFrame* const out_frame, - const size_t payload_buffer_size, - void* const payload_buffer, - const CanardMicrosecond timeout_usec, - bool* const loopback); - -/// The configuration of a single extended 29-bit data frame acceptance filter. -/// Bits above the 29-th shall be cleared. -typedef struct SocketCANFilterConfig -{ - uint32_t extended_id; - uint32_t mask; -} SocketCANFilterConfig; +/** + * @brief Fetch a new extended CAN data frame from the RX queue. + * If the received frame is not an extended-ID data frame, it will be dropped and the function will + * return early. The function will block until a frame is received or until the timeout is expired. + * + * @param fd the socket handle. + * @param[out] out_frame the frame as CanardFrame. + * @param[out] out_timestamp_usec The received frame timestamp will be set to CLOCK_REALTIME by the kernel, + * sampled near the moment of its arrival. + * @param payload_buffer_size The payload_buffer_size shall be large enough (64 bytes is enough for CAN FD), + * otherwise an error is returned. + * @param[out] payload_buffer The payload pointer of the returned frame will point to the payload_buffer. It + * can be a stack-allocated array. + * @param timeout_usec the timeout in microseconds. Zero timeout makes the operation non-blocking. + * @param[in,out] loopback The loopback flag pointer is used to both indicate and control behavior when a + * looped-back message is received. If the flag pointer is NULL, loopback frames are silently dropped; if not + * NULL, they are accepted and indicated using this flag. + * + * @return 1 on success, 0 on timeout, negated errno on error. + */ +int16_t socketcanPop(const SocketCANFD fd, + CanardFrame* const out_frame, + CanardMicrosecond* const out_timestamp_usec, + const size_t payload_buffer_size, + void* const payload_buffer, + const CanardMicrosecond timeout_usec, + bool* const loopback); -/// Apply the specified acceptance filter configuration. -/// Note that it is only possible to accept extended-format data frames. -/// The default configuration is to accept everything. -/// Returns 0 on success, negated errno on error. -int16_t socketcanFilter(const SocketCANFD fd, const size_t num_configs, const SocketCANFilterConfig* const configs); +/** + * @brief Apply the specified acceptance filter configuration. + * Note that it is only possible to accept extended-format data frames. + * The default configuration is to accept everything. + * + * @param fd the socket handle. + * @param num_configs number of filter configurations. + * @param configs the CanardFilter configurations. + * + * @return 0 on success, negated errno on error. + */ +int16_t socketcanFilter(const SocketCANFD fd, const size_t num_configs, const CanardFilter* const configs); #ifdef __cplusplus } diff --git a/src/Node.cpp b/src/Node.cpp index e9b10006..9f94cfa6 100644 --- a/src/Node.cpp +++ b/src/Node.cpp @@ -55,12 +55,11 @@ Node::Node(uint8_t * heap_ptr, * PUBLIC MEMBER FUNCTIONS **************************************************************************************/ -#if !defined(__GNUC__) || (__GNUC__ >= 11) + Registry Node::create_registry() { return std::make_shared(*this, _micros_func); } -#endif NodeInfo Node::create_node_info(uint8_t const protocol_major, uint8_t const protocol_minor, uint8_t const hardware_major, uint8_t const hardware_minor, diff --git a/src/Node.hpp b/src/Node.hpp index 93bc1444..9657d279 100644 --- a/src/Node.hpp +++ b/src/Node.hpp @@ -102,9 +102,8 @@ class Node template ServiceClient create_service_client(CanardPortID const response_port_id, CanardMicrosecond const tx_timeout_usec, OnResponseCb&& on_response_cb, CanardMicrosecond const tid_timeout_usec = CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC); -#if !defined(__GNUC__) || (__GNUC__ >= 11) + Registry create_registry(); -#endif NodeInfo create_node_info(uint8_t const protocol_major, uint8_t const protocol_minor, uint8_t const hardware_major, uint8_t const hardware_minor, diff --git a/src/Node.ipp b/src/Node.ipp index 955277a6..5e28485a 100644 --- a/src/Node.ipp +++ b/src/Node.ipp @@ -86,7 +86,7 @@ ServiceServer Node::create_service_server(CanardMicrosecond const tx_timeout_use static_assert(T_REQ::_traits_::HasFixedPortID, "T_REQ does not have a fixed port id."); static_assert(T_RSP::_traits_::HasFixedPortID, "T_RSP does not have a fixed port id."); - return create_service_server(T_REQ::_traits_::FixedPortId, tx_timeout_usec, on_request_cb, tid_timeout_usec); + return create_service_server(T_REQ::_traits_::FixedPortId, tx_timeout_usec, std::move(on_request_cb), tid_timeout_usec); } template @@ -102,7 +102,7 @@ ServiceServer Node::create_service_server(CanardPortID const request_port_id, Ca *this, request_port_id, tx_timeout_usec, - std::forward(on_request_cb) + std::move(on_request_cb) ); int8_t const rc = canardRxSubscribe(&_canard_hdl, diff --git a/src/ServiceServer.hpp b/src/ServiceServer.hpp index 9bda1c60..8a32af88 100644 --- a/src/ServiceServer.hpp +++ b/src/ServiceServer.hpp @@ -33,11 +33,11 @@ template class ServiceServer final : public ServiceServerBase { public: - ServiceServer(Node & node_hdl, CanardPortID const request_port_id, CanardMicrosecond const tx_timeout_usec, OnRequestCb on_request_cb) + ServiceServer(Node & node_hdl, CanardPortID const request_port_id, CanardMicrosecond const tx_timeout_usec, OnRequestCb&& on_request_cb) : _node_hdl{node_hdl} , _request_port_id{request_port_id} , _tx_timeout_usec{tx_timeout_usec} - , _on_request_cb{on_request_cb} + , _on_request_cb{std::move(on_request_cb)} { } virtual ~ServiceServer(); diff --git a/src/util/registry/Registry.hpp b/src/util/registry/Registry.hpp index 8e434a59..d278832e 100644 --- a/src/util/registry/Registry.hpp +++ b/src/util/registry/Registry.hpp @@ -16,7 +16,7 @@ #include "registry_impl.hpp" -#if !defined(__GNUC__) || (__GNUC__ >= 11) + /************************************************************************************** * NAMESPACE @@ -117,4 +117,4 @@ class Registry final : public cyphal::registry::Registry } /* impl */ } /* cyphal */ -#endif /* !defined(__GNUC__) || (__GNUC__ >= 11) */ + diff --git a/src/util/registry/cavl.hpp b/src/util/registry/cavl.hpp index 27403582..9ca29121 100644 --- a/src/util/registry/cavl.hpp +++ b/src/util/registry/cavl.hpp @@ -27,7 +27,7 @@ #include #include -#if !defined(__GNUC__) || (__GNUC__ >= 11) + /// If CAVL is used in throughput-critical code, then it is recommended to disable assertion checks as they may /// be costly in terms of execution time. @@ -633,4 +633,4 @@ class Tree final } // namespace cavl -#endif /* !defined(__GNUC__) || (__GNUC__ >= 11) */ + diff --git a/src/util/registry/registry_base.hpp b/src/util/registry/registry_base.hpp index af2bb650..e802037f 100644 --- a/src/util/registry/registry_base.hpp +++ b/src/util/registry/registry_base.hpp @@ -9,7 +9,7 @@ #include "registry_value.hpp" -#if !defined(__GNUC__) || (__GNUC__ >= 11) + namespace cyphal { @@ -86,4 +86,4 @@ class IIntrospectableRegistry : public IRegistry } // namespace registry } // cyphal -#endif /* !defined(__GNUC__) || (__GNUC__ >= 11) */ + diff --git a/src/util/registry/registry_impl.hpp b/src/util/registry/registry_impl.hpp index 8c65603e..bb1612d6 100644 --- a/src/util/registry/registry_impl.hpp +++ b/src/util/registry/registry_impl.hpp @@ -11,7 +11,7 @@ #include "cavl.hpp" // Copy from https://github.com/pavel-kirienko/cavl/blob/main/c%2B%2B/cavl.hpp #include -#if !defined(__GNUC__) || (__GNUC__ >= 11) + namespace cyphal { @@ -391,4 +391,4 @@ using Registry = std::shared_ptr; } // cyphal -#endif /* !defined(__GNUC__) || (__GNUC__ >= 11) */ + diff --git a/src/util/registry/registry_value.hpp b/src/util/registry/registry_value.hpp index a1d86cbc..062c6b28 100644 --- a/src/util/registry/registry_value.hpp +++ b/src/util/registry/registry_value.hpp @@ -17,7 +17,7 @@ #include "../../DSDL_Types.h" -#if !defined(__GNUC__) || (__GNUC__ >= 11) + namespace cyphal { @@ -296,4 +296,4 @@ Value makeValue(const Ts&... src) } // namespace registry } // cyphal -#endif /* !defined(__GNUC__) || (__GNUC__ >= 11) */ + diff --git a/src/util/storage/KeyValueStorage.hpp b/src/util/storage/KeyValueStorage.hpp index 6ddccabd..d2bf1a7f 100644 --- a/src/util/storage/KeyValueStorage.hpp +++ b/src/util/storage/KeyValueStorage.hpp @@ -7,7 +7,7 @@ #pragma once -#if !defined(__GNUC__) || (__GNUC__ >= 11) + #include #include @@ -60,4 +60,4 @@ class KeyValueStorage } /* cyphal::support::platform::storage */ -#endif /* !defined(__GNUC__) || (__GNUC__ >= 11) */ + diff --git a/src/util/storage/register_storage.hpp b/src/util/storage/register_storage.hpp index e27d6c60..38e8d225 100644 --- a/src/util/storage/register_storage.hpp +++ b/src/util/storage/register_storage.hpp @@ -7,7 +7,7 @@ #pragma once -#if !defined(__GNUC__) || (__GNUC__ >= 11) + #include "KeyValueStorage.hpp" @@ -164,4 +164,4 @@ template } /* cyphal::support */ -#endif /* !defined(__GNUC__) || (__GNUC__ >= 11) */ +