Skip to content

Commit 5faadce

Browse files
committed
chore(test_udp): reduce clang-tidy warnings
Signed-off-by: Max SCHMELLER <max.schmeller@tier4.jp>
1 parent 0b5016b commit 5faadce

File tree

1 file changed

+46
-43
lines changed

1 file changed

+46
-43
lines changed

nebula_hw_interfaces/test/common/test_udp.cpp

+46-43
Original file line numberDiff line numberDiff line change
@@ -25,17 +25,17 @@ namespace nebula::drivers::connections
2525

2626
using std::chrono_literals::operator""ms;
2727

28-
static const char localhost_ip[] = "127.0.0.1";
29-
static const char broadcast_ip[] = "255.255.255.255";
30-
static const char any_ip[] = "0.0.0.0";
31-
static const char multicast_group[] = "230.1.2.3";
32-
static const char multicast_group2[] = "230.4.5.6";
28+
static const char * const g_localhost_ip = "127.0.0.1";
29+
static const char * const g_broadcast_ip = "255.255.255.255";
30+
static const char * const g_any_ip = "0.0.0.0";
31+
static const char * const g_multicast_group = "230.1.2.3";
32+
static const char * const g_multicast_group2 = "230.4.5.6";
3333

34-
static const char sender_ip[] = "192.168.201";
35-
static const uint16_t sender_port = 7373;
36-
static const uint16_t host_port = 6262;
34+
static const char * const g_sender_ip = "192.168.201.100";
35+
static const uint16_t g_sender_port = 7373;
36+
static const uint16_t g_host_port = 6262;
3737

38-
static const std::chrono::duration send_receive_timeout = 100ms;
38+
static const std::chrono::duration g_send_receive_timeout = 100ms;
3939

4040
UdpSocket::callback_t empty_cb()
4141
{
@@ -57,19 +57,19 @@ util::expected<uint64_t, std::string> read_sys_param(const std::string & param_f
5757
TEST(TestUdp, TestBasicLifecycle)
5858
{
5959
ASSERT_NO_THROW(
60-
UdpSocket::Builder(localhost_ip, host_port).bind().subscribe(empty_cb()).unsubscribe());
60+
UdpSocket::Builder(g_localhost_ip, g_host_port).bind().subscribe(empty_cb()).unsubscribe());
6161
}
6262

6363
TEST(TestUdp, TestSpecialAddressesBind)
6464
{
65-
ASSERT_THROW(UdpSocket::Builder(broadcast_ip, host_port), UsageError);
66-
ASSERT_NO_THROW(UdpSocket::Builder(any_ip, host_port).bind());
65+
ASSERT_THROW(UdpSocket::Builder(g_broadcast_ip, g_host_port), UsageError);
66+
ASSERT_NO_THROW(UdpSocket::Builder(g_any_ip, g_host_port).bind());
6767
}
6868

6969
TEST(TestUdp, TestJoiningInvalidMulticastGroup)
7070
{
7171
ASSERT_THROW(
72-
UdpSocket::Builder(localhost_ip, host_port).join_multicast_group(broadcast_ip).bind(),
72+
UdpSocket::Builder(g_localhost_ip, g_host_port).join_multicast_group(g_broadcast_ip).bind(),
7373
SocketError);
7474
}
7575

@@ -81,11 +81,11 @@ TEST(TestUdp, TestBufferResize)
8181

8282
// Setting buffer sizes up to and including rmem_max shall succeed
8383
ASSERT_NO_THROW(
84-
UdpSocket::Builder(localhost_ip, host_port).set_socket_buffer_size(rmem_max).bind());
84+
UdpSocket::Builder(g_localhost_ip, g_host_port).set_socket_buffer_size(rmem_max).bind());
8585

8686
// Linux only supports sizes up to INT32_MAX
8787
ASSERT_THROW(
88-
UdpSocket::Builder(localhost_ip, host_port)
88+
UdpSocket::Builder(g_localhost_ip, g_host_port)
8989
.set_socket_buffer_size(static_cast<size_t>(INT32_MAX) + 1)
9090
.bind(),
9191
UsageError);
@@ -94,49 +94,51 @@ TEST(TestUdp, TestBufferResize)
9494
TEST(TestUdp, TestCorrectUsageIsEnforced)
9595
{
9696
// The following functions can be called in any order, any number of times
97-
ASSERT_NO_THROW(UdpSocket::Builder(localhost_ip, host_port)
97+
ASSERT_NO_THROW(UdpSocket::Builder(g_localhost_ip, g_host_port)
9898
.set_polling_interval(20)
9999
.set_socket_buffer_size(3000)
100100
.set_mtu(1600)
101-
.limit_to_sender(sender_ip, sender_port)
101+
.limit_to_sender(g_sender_ip, g_sender_port)
102102
.set_polling_interval(20)
103103
.set_socket_buffer_size(3000)
104104
.set_mtu(1600)
105-
.set_send_destination(sender_ip, sender_port)
106-
.limit_to_sender(sender_ip, sender_port)
105+
.set_send_destination(g_sender_ip, g_sender_port)
106+
.limit_to_sender(g_sender_ip, g_sender_port)
107107
.bind());
108108

109109
// Only one multicast group can be joined
110110
ASSERT_THROW(
111-
UdpSocket::Builder(localhost_ip, host_port)
112-
.join_multicast_group(multicast_group)
113-
.join_multicast_group(multicast_group2),
111+
UdpSocket::Builder(g_localhost_ip, g_host_port)
112+
.join_multicast_group(g_multicast_group)
113+
.join_multicast_group(g_multicast_group2),
114114
UsageError);
115115

116116
// Pre-existing subscriptions shall be gracefully unsubscribed when a new subscription is created
117-
ASSERT_NO_THROW(
118-
UdpSocket::Builder(localhost_ip, host_port).bind().subscribe(empty_cb()).subscribe(empty_cb()));
117+
ASSERT_NO_THROW(UdpSocket::Builder(g_localhost_ip, g_host_port)
118+
.bind()
119+
.subscribe(empty_cb())
120+
.subscribe(empty_cb()));
119121

120122
// Explicitly unsubscribing shall be supported
121-
ASSERT_NO_THROW(UdpSocket::Builder(localhost_ip, host_port)
123+
ASSERT_NO_THROW(UdpSocket::Builder(g_localhost_ip, g_host_port)
122124
.bind()
123125
.subscribe(empty_cb())
124126
.unsubscribe()
125127
.subscribe(empty_cb()));
126128

127129
// Unsubscribing on a non-subscribed socket shall also be supported
128-
ASSERT_NO_THROW(UdpSocket::Builder(localhost_ip, host_port).bind().unsubscribe());
130+
ASSERT_NO_THROW(UdpSocket::Builder(g_localhost_ip, g_host_port).bind().unsubscribe());
129131
}
130132

131133
TEST(TestUdp, TestReceiving)
132134
{
133135
const std::vector<uint8_t> payload{1, 2, 3};
134-
auto sock = UdpSocket::Builder(localhost_ip, host_port).bind();
136+
auto sock = UdpSocket::Builder(g_localhost_ip, g_host_port).bind();
135137

136-
auto err_no_opt = udp_send(localhost_ip, host_port, payload);
138+
auto err_no_opt = udp_send(g_localhost_ip, g_host_port, payload);
137139
if (err_no_opt.has_value()) GTEST_SKIP() << strerror(err_no_opt.value());
138140

139-
auto result_opt = receive_once(sock, send_receive_timeout);
141+
auto result_opt = receive_once(sock, g_send_receive_timeout);
140142

141143
ASSERT_TRUE(result_opt.has_value());
142144
auto const & [recv_payload, metadata] = result_opt.value();
@@ -152,12 +154,12 @@ TEST(TestUdp, TestReceivingOversized)
152154
const size_t mtu = 1500;
153155
std::vector<uint8_t> payload;
154156
payload.resize(mtu + 1, 0x42);
155-
auto sock = UdpSocket::Builder(localhost_ip, host_port).set_mtu(mtu).bind();
157+
auto sock = UdpSocket::Builder(g_localhost_ip, g_host_port).set_mtu(mtu).bind();
156158

157-
auto err_no_opt = udp_send(localhost_ip, host_port, payload);
159+
auto err_no_opt = udp_send(g_localhost_ip, g_host_port, payload);
158160
if (err_no_opt.has_value()) GTEST_SKIP() << strerror(err_no_opt.value());
159161

160-
auto result_opt = receive_once(sock, send_receive_timeout);
162+
auto result_opt = receive_once(sock, g_send_receive_timeout);
161163

162164
ASSERT_TRUE(result_opt.has_value());
163165
auto const & [recv_payload, metadata] = result_opt.value();
@@ -170,13 +172,14 @@ TEST(TestUdp, TestReceivingOversized)
170172
TEST(TestUdp, TestFilteringSender)
171173
{
172174
std::vector<uint8_t> payload{1, 2, 3};
173-
auto sock =
174-
UdpSocket::Builder(localhost_ip, host_port).limit_to_sender(sender_ip, sender_port).bind();
175+
auto sock = UdpSocket::Builder(g_localhost_ip, g_host_port)
176+
.limit_to_sender(g_sender_ip, g_sender_port)
177+
.bind();
175178

176-
auto err_no_opt = udp_send(localhost_ip, host_port, payload);
179+
auto err_no_opt = udp_send(g_localhost_ip, g_host_port, payload);
177180
if (err_no_opt.has_value()) GTEST_SKIP() << strerror(err_no_opt.value());
178181

179-
auto result_opt = receive_once(sock, send_receive_timeout);
182+
auto result_opt = receive_once(sock, g_send_receive_timeout);
180183
ASSERT_FALSE(result_opt.has_value());
181184
}
182185

@@ -186,17 +189,17 @@ TEST(TestUdp, TestMoveable)
186189

187190
size_t n_received = 0;
188191

189-
auto sock = UdpSocket::Builder(localhost_ip, host_port).bind();
192+
auto sock = UdpSocket::Builder(g_localhost_ip, g_host_port).bind();
190193
sock.subscribe([&n_received](const auto &, const auto &) { n_received++; });
191194

192-
auto err_no_opt = udp_send(localhost_ip, host_port, payload);
195+
auto err_no_opt = udp_send(g_localhost_ip, g_host_port, payload);
193196
if (err_no_opt.has_value()) GTEST_SKIP() << strerror(err_no_opt.value());
194197

195198
// The subscription moves to the new socket object
196199
UdpSocket sock2{std::move(sock)};
197200
ASSERT_TRUE(sock2.is_subscribed());
198201

199-
err_no_opt = udp_send(localhost_ip, host_port, payload);
202+
err_no_opt = udp_send(g_localhost_ip, g_host_port, payload);
200203
if (err_no_opt.has_value()) GTEST_SKIP() << strerror(err_no_opt.value());
201204

202205
std::this_thread::sleep_for(100ms);
@@ -208,17 +211,17 @@ TEST(TestUdp, TestSending)
208211
const std::vector<uint8_t> payload{1, 2, 3};
209212

210213
// A socket without a send destination shall not be able to send
211-
auto sock = UdpSocket::Builder(localhost_ip, host_port).bind();
214+
auto sock = UdpSocket::Builder(g_localhost_ip, g_host_port).bind();
212215
ASSERT_THROW(sock.send(payload), UsageError);
213216

214217
// A socket with a send destination shall be able to send
215-
auto sock2 = UdpSocket::Builder(localhost_ip, host_port)
216-
.set_send_destination(localhost_ip, host_port)
218+
auto sock2 = UdpSocket::Builder(g_localhost_ip, g_host_port)
219+
.set_send_destination(g_localhost_ip, g_host_port)
217220
.bind();
218221
ASSERT_NO_THROW(sock2.send(payload));
219222

220223
// The sent payload shall be received by the destination
221-
auto result3 = receive_once(sock2, send_receive_timeout);
224+
auto result3 = receive_once(sock2, g_send_receive_timeout);
222225
ASSERT_TRUE(result3.has_value());
223226
auto const & [recv_payload, metadata] = result3.value();
224227
ASSERT_EQ(recv_payload, payload);

0 commit comments

Comments
 (0)