From ed904bd5df95613208388f0570f1f969054c0eaa Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 13 Dec 2024 18:35:02 +0900 Subject: [PATCH] chore(udp): rename ReceiveMetadata to RxMetadata Signed-off-by: Max SCHMELLER --- .../nebula_hw_interfaces_common/connections/udp.hpp | 8 ++++---- nebula_hw_interfaces/test/common/test_udp/utils.hpp | 5 ++--- 2 files changed, 6 insertions(+), 7 deletions(-) diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_common/connections/udp.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_common/connections/udp.hpp index 1493f0f26..fb7e0e0e2 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_common/connections/udp.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_common/connections/udp.hpp @@ -115,14 +115,14 @@ class UdpSocket static constexpr std::string_view broadcast_ip{"255.255.255.255"}; public: - struct ReceiveMetadata + struct RxMetadata { std::optional timestamp_ns; uint64_t drops_since_last_receive{0}; bool truncated; }; - using callback_t = std::function &, const ReceiveMetadata &)>; + using callback_t = std::function &, const RxMetadata &)>; /** * @brief Construct a UDP socket with timestamp measuring enabled. The minimal way to start @@ -329,7 +329,7 @@ class UdpSocket if (!is_accepted_sender(msg_header.sender_addr)) continue; - ReceiveMetadata metadata; + RxMetadata metadata; get_receive_metadata(msg_header.msg, metadata); metadata.truncated = untruncated_packet_length > buffer_size_; @@ -339,7 +339,7 @@ class UdpSocket }); } - void get_receive_metadata(msghdr & msg, ReceiveMetadata & inout_metadata) + void get_receive_metadata(msghdr & msg, RxMetadata & inout_metadata) { for (cmsghdr * cmsg = CMSG_FIRSTHDR(&msg); cmsg != nullptr; cmsg = CMSG_NXTHDR(&msg, cmsg)) { if (cmsg->cmsg_level != SOL_SOCKET) continue; diff --git a/nebula_hw_interfaces/test/common/test_udp/utils.hpp b/nebula_hw_interfaces/test/common/test_udp/utils.hpp index dc9a08c0e..a4d8878ce 100644 --- a/nebula_hw_interfaces/test/common/test_udp/utils.hpp +++ b/nebula_hw_interfaces/test/common/test_udp/utils.hpp @@ -55,14 +55,13 @@ std::optional udp_send( } template -std::optional< - std::pair, nebula::drivers::connections::UdpSocket::ReceiveMetadata>> +std::optional, nebula::drivers::connections::UdpSocket::RxMetadata>> receive_once(nebula::drivers::connections::UdpSocket & sock, std::chrono::duration<_T, _R> timeout) { std::condition_variable cv_received_result; std::mutex mtx_result; std::optional< - std::pair, nebula::drivers::connections::UdpSocket::ReceiveMetadata>> + std::pair, nebula::drivers::connections::UdpSocket::RxMetadata>> result; sock.subscribe([&](const auto & data, const auto & metadata) {