Skip to content

Commit

Permalink
fix(udp): return correctly truncated buffer when oversized packet is …
Browse files Browse the repository at this point in the history
…received

Signed-off-by: Max SCHMELLER <[email protected]>
  • Loading branch information
mojomex committed Nov 22, 2024
1 parent 86961ef commit 205c5dc
Show file tree
Hide file tree
Showing 3 changed files with 23 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include <sys/socket.h>
#include <unistd.h>

#include <algorithm>
#include <atomic>
#include <cassert>
#include <cerrno>
Expand Down Expand Up @@ -286,15 +287,17 @@ class UdpSocket
buffer.resize(buffer_size_);
auto msg_header = make_msg_header(buffer);

ssize_t received = recvmsg(sock_fd_, &msg_header.msg, MSG_TRUNC);
if (received < 0) throw SocketError(errno);
ssize_t recv_result = recvmsg(sock_fd_, &msg_header.msg, MSG_TRUNC);
if (recv_result < 0) throw SocketError(errno);
size_t untruncated_packet_length = recv_result;

if (!is_accepted_sender(msg_header.sender_addr)) continue;

ReceiveMetadata metadata;
get_receive_metadata(msg_header.msg, metadata);
metadata.truncated = static_cast<size_t>(received) > buffer_size_;
metadata.truncated = untruncated_packet_length > buffer_size_;

buffer.resize(received);
buffer.resize(std::min(buffer_size_, untruncated_packet_length));
callback_(buffer, metadata);
}
});
Expand Down
16 changes: 15 additions & 1 deletion nebula_hw_interfaces/test/common/test_udp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -159,7 +159,7 @@ TEST(test_udp, test_receiving_oversized)
{
const size_t mtu = 1500;
std::vector<uint8_t> payload;
payload.resize(mtu + 1);
payload.resize(mtu + 1, 0x42);
UdpSocket sock{};
sock.init(localhost_ip, host_port).set_mtu(mtu).bind();

Expand All @@ -170,11 +170,25 @@ TEST(test_udp, test_receiving_oversized)

ASSERT_TRUE(result_opt.has_value());
auto const & [recv_payload, metadata] = result_opt.value();
ASSERT_EQ(recv_payload.size(), mtu);
ASSERT_TRUE(std::equal(recv_payload.begin(), recv_payload.end(), payload.begin()));
ASSERT_TRUE(metadata.truncated);
ASSERT_EQ(metadata.drops_since_last_receive, 0);
}

TEST(test_udp, test_filtering_sender)
{
std::vector<uint8_t> payload{1, 2, 3};
UdpSocket sock{};
sock.init(localhost_ip, host_port).bind().limit_to_sender(sender_ip, sender_port);

auto err_no_opt = udp_send(localhost_ip, host_port, payload);
if (err_no_opt.has_value()) GTEST_SKIP() << strerror(err_no_opt.value());

auto result_opt = receive_once(sock, send_receive_timeout);
ASSERT_FALSE(result_opt.has_value());
}

} // namespace nebula::drivers::connections

int main(int argc, char * argv[])
Expand Down
1 change: 1 addition & 0 deletions nebula_hw_interfaces/test/common/test_udp/utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include <cstdint>
#include <cstring>
#include <optional>
#include <utility>
#include <vector>

std::optional<int> udp_send(
Expand Down

0 comments on commit 205c5dc

Please sign in to comment.