test_socket.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014 Pavel Kirienko <pavel.kirienko@gmail.com>
3  */
4 
5 #include <iostream>
6 #include <vector>
7 #include <cerrno>
9 #include "debug.hpp"
10 
11 static uavcan::CanFrame makeFrame(std::uint32_t id, const std::string& data)
12 {
13  return uavcan::CanFrame(id, reinterpret_cast<const std::uint8_t*>(data.c_str()), data.length());
14 }
15 
17 {
19 }
20 
21 static void testNonexistentIface()
22 {
23  const int sock1 = uavcan_linux::SocketCanIface::openSocket("noif9");
24  ENFORCE(sock1 < 0);
25  const int sock2 = uavcan_linux::SocketCanIface::openSocket("verylongifacenameverylongifacenameverylongifacename");
26  ENFORCE(sock2 < 0);
27 }
28 
29 static void testSocketRxTx(const std::string& iface_name)
30 {
31  const int sock1 = uavcan_linux::SocketCanIface::openSocket(iface_name);
32  const int sock2 = uavcan_linux::SocketCanIface::openSocket(iface_name);
33  ENFORCE(sock1 >= 0 && sock2 >= 0);
34 
35  /*
36  * Clocks will have some offset from the true system time
37  * SocketCAN driver must handle this correctly
38  */
40  clock_impl.adjustUtc(uavcan::UtcDuration::fromMSec(100000));
41  const uavcan_linux::SystemClock& clock = clock_impl;
42 
43  uavcan_linux::SocketCanIface if1(clock, sock1);
44  uavcan_linux::SocketCanIface if2(clock, sock2);
45 
46  /*
47  * Sending two frames, one of which must be returned back
48  */
49  ENFORCE(1 == if1.send(makeFrame(123, "if1-1"), tsMonoOffsetMs(100), 0));
50  ENFORCE(1 == if1.send(makeFrame(456, "if1-2"), tsMonoOffsetMs(100), uavcan::CanIOFlagLoopback));
51  if1.poll(true, true);
52  if1.poll(true, true);
53  ENFORCE(0 == if1.getErrorCount());
54  ENFORCE(!if1.hasReadyTx());
55  ENFORCE(if1.hasReadyRx()); // Second loopback
56 
57  /*
58  * Second iface, same thing
59  */
60  ENFORCE(1 == if2.send(makeFrame(321, "if2-1"), tsMonoOffsetMs(100), 0));
61  ENFORCE(1 == if2.send(makeFrame(654, "if2-2"), tsMonoOffsetMs(100), uavcan::CanIOFlagLoopback));
62  ENFORCE(1 == if2.send(makeFrame(1, "discard"), tsMonoOffsetMs(-1), uavcan::CanIOFlagLoopback)); // Will timeout
63  if2.poll(true, true);
64  if2.poll(true, true);
65  ENFORCE(1 == if2.getErrorCount()); // One timed out
66  ENFORCE(!if2.hasReadyTx());
67  ENFORCE(if2.hasReadyRx());
68 
69  /*
70  * No-op
71  */
72  if1.poll(true, true);
73  if2.poll(true, true);
74 
76  uavcan::MonotonicTime ts_mono;
77  uavcan::UtcTime ts_utc;
78  uavcan::CanIOFlags flags = 0;
79 
80  /*
81  * Read first
82  */
83  ENFORCE(1 == if1.receive(frame, ts_mono, ts_utc, flags));
84  ENFORCE(frame == makeFrame(456, "if1-2"));
86  ENFORCE((clock.getMonotonic() - ts_mono).getAbs().toMSec() < 10);
87  ENFORCE((clock.getUtc() - ts_utc).getAbs().toMSec() < 10);
88 
89  ENFORCE(1 == if1.receive(frame, ts_mono, ts_utc, flags));
90  ENFORCE(frame == makeFrame(321, "if2-1"));
91  ENFORCE(flags == 0);
92  ENFORCE(!ts_mono.isZero());
93  ENFORCE(!ts_utc.isZero());
94  ENFORCE((clock.getMonotonic() - ts_mono).getAbs().toMSec() < 10);
95  ENFORCE((clock.getUtc() - ts_utc).getAbs().toMSec() < 10);
96 
97  ENFORCE(1 == if1.receive(frame, ts_mono, ts_utc, flags));
98  ENFORCE(frame == makeFrame(654, "if2-2"));
99  ENFORCE(flags == 0);
100  ENFORCE((clock.getMonotonic() - ts_mono).getAbs().toMSec() < 10);
101  ENFORCE((clock.getUtc() - ts_utc).getAbs().toMSec() < 10);
102 
103  ENFORCE(0 == if1.receive(frame, ts_mono, ts_utc, flags));
104  ENFORCE(!if1.hasReadyTx());
105  ENFORCE(!if1.hasReadyRx());
106 
107  /*
108  * Read second
109  */
110  ENFORCE(1 == if2.receive(frame, ts_mono, ts_utc, flags));
111  ENFORCE(frame == makeFrame(123, "if1-1"));
112  ENFORCE(flags == 0);
113  ENFORCE((clock.getMonotonic() - ts_mono).getAbs().toMSec() < 10);
114  ENFORCE((clock.getUtc() - ts_utc).getAbs().toMSec() < 10);
115 
116  ENFORCE(1 == if2.receive(frame, ts_mono, ts_utc, flags));
117  ENFORCE(frame == makeFrame(456, "if1-2"));
118  ENFORCE(flags == 0);
119  ENFORCE((clock.getMonotonic() - ts_mono).getAbs().toMSec() < 10);
120  ENFORCE((clock.getUtc() - ts_utc).getAbs().toMSec() < 10);
121 
122  ENFORCE(1 == if2.receive(frame, ts_mono, ts_utc, flags));
123  ENFORCE(frame == makeFrame(654, "if2-2"));
125  ENFORCE((clock.getMonotonic() - ts_mono).getAbs().toMSec() < 10);
126  ENFORCE((clock.getUtc() - ts_utc).getAbs().toMSec() < 10);
127 
128  ENFORCE(0 == if2.receive(frame, ts_mono, ts_utc, flags));
129  ENFORCE(!if2.hasReadyTx());
130  ENFORCE(!if2.hasReadyRx());
131 }
132 
133 static void testSocketFilters(const std::string& iface_name)
134 {
135  using uavcan::CanFrame;
136 
137  const int sock1 = uavcan_linux::SocketCanIface::openSocket(iface_name);
138  const int sock2 = uavcan_linux::SocketCanIface::openSocket(iface_name);
139  ENFORCE(sock1 >= 0 && sock2 >= 0);
140 
141  /*
142  * Clocks will have some offset from the true system time
143  * SocketCAN driver must handle this correctly
144  */
146  clock_impl.adjustUtc(uavcan::UtcDuration::fromMSec(-1000));
147  const uavcan_linux::SystemClock& clock = clock_impl;
148 
149  uavcan_linux::SocketCanIface if1(clock, sock1);
150  uavcan_linux::SocketCanIface if2(clock, sock2);
151 
152  /*
153  * Configuring filters
154  */
156  // STD/EXT 123
157  fcs[0].id = 123;
158  fcs[0].mask = CanFrame::MaskExtID;
159  // Only EXT 456789
160  fcs[1].id = 456789 | CanFrame::FlagEFF;
161  fcs[1].mask = CanFrame::MaskExtID | CanFrame::FlagEFF;
162  // Only STD 0
163  fcs[2].id = 0;
164  fcs[2].mask = CanFrame::MaskExtID | CanFrame::FlagEFF;
165 
166  ENFORCE(0 == if2.configureFilters(fcs, 3));
167 
168  /*
169  * Sending data from 1 to 2, making sure only filtered data will be accepted
170  */
171  const auto EFF = CanFrame::FlagEFF;
172  ENFORCE(1 == if1.send(makeFrame(123, "1"), tsMonoOffsetMs(100), 0)); // Accept 0
173  ENFORCE(1 == if1.send(makeFrame(123 | EFF, "2"), tsMonoOffsetMs(100), 0)); // Accept 0
174  ENFORCE(1 == if1.send(makeFrame(456, "3"), tsMonoOffsetMs(100), 0)); // Drop
175  ENFORCE(1 == if1.send(makeFrame(456789, "4"), tsMonoOffsetMs(100), 0)); // Drop
176  ENFORCE(1 == if1.send(makeFrame(456789 | EFF, "5"), tsMonoOffsetMs(100), 0)); // Accept 1
177  ENFORCE(1 == if1.send(makeFrame(0, "6"), tsMonoOffsetMs(100), 0)); // Accept 2
178  ENFORCE(1 == if1.send(makeFrame(EFF, "7"), tsMonoOffsetMs(100), 0)); // Drop
179 
180  for (int i = 0; i < 7; i++)
181  {
182  if1.poll(true, true);
183  if2.poll(true, false);
184  }
185  ENFORCE(!if1.hasReadyTx());
186  ENFORCE(!if1.hasReadyRx());
187  ENFORCE(0 == if1.getErrorCount());
188  ENFORCE(if2.hasReadyRx());
189 
190  /*
191  * Checking RX on 2
192  */
194  uavcan::MonotonicTime ts_mono;
195  uavcan::UtcTime ts_utc;
196  uavcan::CanIOFlags flags = 0;
197 
198  ENFORCE(1 == if2.receive(frame, ts_mono, ts_utc, flags));
199  ENFORCE(frame == makeFrame(123, "1"));
200 
201  ENFORCE(1 == if2.receive(frame, ts_mono, ts_utc, flags));
202  ENFORCE(frame == makeFrame(123 | EFF, "2"));
203 
204  ENFORCE(1 == if2.receive(frame, ts_mono, ts_utc, flags));
205  ENFORCE(frame == makeFrame(456789 | EFF, "5"));
206 
207  ENFORCE(1 == if2.receive(frame, ts_mono, ts_utc, flags));
208  ENFORCE(frame == makeFrame(0, "6"));
209  ENFORCE(flags == 0);
210 
211  ENFORCE(!if2.hasReadyRx());
212 }
213 
214 static void testDriver(const std::vector<std::string>& iface_names)
215 {
216  /*
217  * Clocks will have some offset from the true system time
218  * SocketCAN driver must handle this correctly
219  */
221  clock_impl.adjustUtc(uavcan::UtcDuration::fromMSec(9000000));
222  const uavcan_linux::SystemClock& clock = clock_impl;
223 
224  uavcan_linux::SocketCanDriver driver(clock);
225  for (auto ifn : iface_names)
226  {
227  std::cout << "Adding iface " << ifn << std::endl;
228  ENFORCE(0 == driver.addIface(ifn));
229  }
230 
231  ENFORCE(-1 == driver.addIface("noif9"));
232  ENFORCE(-1 == driver.addIface("noif9"));
233  ENFORCE(-1 == driver.addIface("noif9"));
234 
235  ENFORCE(driver.getNumIfaces() == iface_names.size());
236  ENFORCE(nullptr == driver.getIface(255));
237  ENFORCE(nullptr == driver.getIface(driver.getNumIfaces()));
238 
239  const uavcan::CanFrame* pending_tx[uavcan::MaxCanIfaces] = {};
240 
241  const unsigned AllIfacesMask = (1 << driver.getNumIfaces()) - 1;
242 
243  /*
244  * Send, no loopback
245  */
246  std::cout << "select() 1" << std::endl;
247  uavcan::CanSelectMasks masks; // Driver provides masks for all available events
248  ENFORCE(driver.getNumIfaces() == driver.select(masks, pending_tx, tsMonoOffsetMs(1000)));
249  ENFORCE(masks.read == 0);
250  ENFORCE(masks.write == AllIfacesMask);
251 
252  for (int i = 0; i < driver.getNumIfaces(); i++)
253  {
254  ENFORCE(1 == driver.getIface(i)->send(makeFrame(123, std::to_string(i)), tsMonoOffsetMs(10), 0));
255  }
256 
257  std::cout << "select() 2" << std::endl;
258  ENFORCE(driver.getNumIfaces() == driver.select(masks, pending_tx, tsMonoOffsetMs(1000)));
259  ENFORCE(masks.read == 0);
260  ENFORCE(masks.write == AllIfacesMask);
261 
262  /*
263  * Send with loopback
264  */
265  for (int i = 0; i < driver.getNumIfaces(); i++)
266  {
267  ENFORCE(1 == driver.getIface(i)->send(makeFrame(456, std::to_string(i)), tsMonoOffsetMs(10),
269  ENFORCE(1 == driver.getIface(i)->send(makeFrame(789, std::to_string(i)), tsMonoOffsetMs(-1), // Will timeout
271  }
272 
273  std::cout << "select() 3" << std::endl;
274  ENFORCE(driver.getNumIfaces() == driver.select(masks, pending_tx, tsMonoOffsetMs(1000)));
275  ENFORCE(masks.read == AllIfacesMask);
276  ENFORCE(masks.write == AllIfacesMask);
277 
278  /*
279  * Receive loopback
280  */
281  for (int i = 0; i < driver.getNumIfaces(); i++)
282  {
284  uavcan::MonotonicTime ts_mono;
285  uavcan::UtcTime ts_utc;
286  uavcan::CanIOFlags flags = 0;
287  ENFORCE(1 == driver.getIface(i)->receive(frame, ts_mono, ts_utc, flags));
288  ENFORCE(frame == makeFrame(456, std::to_string(i)));
290  ENFORCE((clock.getMonotonic() - ts_mono).getAbs().toMSec() < 10);
291  ENFORCE((clock.getUtc() - ts_utc).getAbs().toMSec() < 10);
292 
293  ENFORCE(!driver.getIface(i)->hasReadyTx());
294  ENFORCE(!driver.getIface(i)->hasReadyRx());
295  }
296 
297  std::cout << "select() 4" << std::endl;
298  masks.write = 0;
299  ENFORCE(driver.getNumIfaces() == driver.select(masks, pending_tx, tsMonoOffsetMs(1000)));
300  ENFORCE(masks.read == 0);
301  ENFORCE(masks.write == AllIfacesMask);
302 
303  std::cout << "exit" << std::endl;
304 
305  /*
306  * Error checks
307  */
308  for (int i = 0; i < driver.getNumIfaces(); i++)
309  {
310  for (auto kv : driver.getIface(i)->getErrors())
311  {
312  switch (kv.first)
313  {
316  {
317  ENFORCE(kv.second == 0);
318  break;
319  }
321  {
322  ENFORCE(kv.second == 1); // One timed out frame from the above
323  break;
324  }
325  default:
326  {
327  ENFORCE(false);
328  break;
329  }
330  }
331  }
332  }
333 }
334 
335 int main(int argc, const char** argv)
336 {
337  try
338  {
339  if (argc < 2)
340  {
341  std::cerr << "Usage:\n\t" << argv[0] << " <can-iface-name-1> [can-iface-name-N...]" << std::endl;
342  return 1;
343  }
344 
345  std::vector<std::string> iface_names;
346  for (int i = 1; i < argc; i++)
347  {
348  iface_names.emplace_back(argv[i]);
349  }
350 
352  testSocketRxTx(iface_names[0]);
353  testSocketFilters(iface_names[0]);
354 
355  testDriver(iface_names);
356 
357  return 0;
358  }
359  catch (const std::exception& ex)
360  {
361  std::cerr << "Exception: " << ex.what() << std::endl;
362  return 1;
363  }
364 }
main
int main(int argc, const char **argv)
Definition: test_socket.cpp:335
uavcan_linux::SocketCanError::SocketReadFailure
@ SocketReadFailure
uavcan_linux::SocketCanIface::configureFilters
std::int16_t configureFilters(const uavcan::CanFilterConfig *const filter_configs, const std::uint16_t num_configs) override
Definition: socketcan.hpp:451
uavcan::uint32_t
std::uint32_t uint32_t
Definition: std.hpp:26
uavcan_linux::SocketCanIface::receive
std::int16_t receive(uavcan::CanFrame &out_frame, uavcan::MonotonicTime &out_ts_monotonic, uavcan::UtcTime &out_ts_utc, uavcan::CanIOFlags &out_flags) override
Definition: socketcan.hpp:406
uavcan::UtcTime
Implicitly convertible to/from uavcan.Timestamp.
Definition: time.hpp:191
uavcan::DurationBase< MonotonicDuration >::fromMSec
static MonotonicDuration fromMSec(int64_t ms)
Definition: time.hpp:41
testDriver
static void testDriver(const std::vector< std::string > &iface_names)
Definition: test_socket.cpp:214
uavcan_linux::SocketCanDriver::addIface
int addIface(const std::string &iface_name)
Definition: socketcan.hpp:765
uavcan::CanFilterConfig
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:99
uavcan::CanFrame
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:24
uavcan::CanIOFlagLoopback
static const CanIOFlags CanIOFlagLoopback
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:141
uavcan::int64_t
std::int64_t int64_t
Definition: std.hpp:32
uavcan_linux::SocketCanIface::getErrors
const decltype(errors_) & getErrors() const
Definition: socketcan.hpp:509
uavcan::MaxCanIfaces
@ MaxCanIfaces
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:19
uavcan_linux::SocketCanDriver
Definition: socketcan.hpp:618
uavcan_linux::SocketCanIface::getErrorCount
std::uint64_t getErrorCount() const override
Definition: socketcan.hpp:499
uavcan_linux::SocketCanIface::hasReadyTx
bool hasReadyTx() const
Definition: socketcan.hpp:446
uavcan::CanSelectMasks::read
uint8_t read
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:121
ENFORCE
#define ENFORCE(x)
Definition: platform_specific_components/linux/libuavcan/apps/debug.hpp:13
uavcan::uint8_t
std::uint8_t uint8_t
Definition: std.hpp:24
tsMonoOffsetMs
static uavcan::MonotonicTime tsMonoOffsetMs(std::int64_t ms)
Definition: test_socket.cpp:16
uavcan_linux.hpp
uavcan::CanFilterConfig::mask
uint32_t mask
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:102
testNonexistentIface
static void testNonexistentIface()
Definition: test_socket.cpp:21
uavcan_linux::SocketCanDriver::getNumIfaces
std::uint8_t getNumIfaces() const override
Definition: socketcan.hpp:757
uavcan_linux::SocketCanIface::hasReadyRx
bool hasReadyRx() const
Definition: socketcan.hpp:445
debug.hpp
testSocketFilters
static void testSocketFilters(const std::string &iface_name)
Definition: test_socket.cpp:133
uavcan_linux::ClockAdjustmentMode::PerDriverPrivate
@ PerDriverPrivate
Adjust the clock only for the current driver instance.
uavcan::CanSelectMasks
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:119
uavcan_linux::SocketCanIface::send
std::int16_t send(const uavcan::CanFrame &frame, const uavcan::MonotonicTime tx_deadline, const uavcan::CanIOFlags flags) override
Definition: socketcan.hpp:392
uavcan::CanSelectMasks::write
uint8_t write
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:122
uavcan::TimeBase::isZero
bool isZero() const
Definition: time.hpp:123
uavcan_linux::SocketCanIface
Definition: socketcan.hpp:60
uavcan_linux::SocketCanDriver::getIface
SocketCanIface * getIface(std::uint8_t iface_index) override
Definition: socketcan.hpp:752
testSocketRxTx
static void testSocketRxTx(const std::string &iface_name)
Definition: test_socket.cpp:29
frame
uavcan::CanFrame frame
Definition: can.cpp:78
uavcan_linux::SystemClock
Definition: platform_specific_components/linux/libuavcan/include/uavcan_linux/clock.hpp:33
uavcan_linux::SystemClock::getMonotonic
uavcan::MonotonicTime getMonotonic() const override
Definition: platform_specific_components/linux/libuavcan/include/uavcan_linux/clock.hpp:83
uavcan_linux::SystemClock::getUtc
uavcan::UtcTime getUtc() const override
Definition: platform_specific_components/linux/libuavcan/include/uavcan_linux/clock.hpp:97
uavcan_linux::SocketCanError::TxTimeout
@ TxTimeout
uavcan_linux::SocketCanDriver::select
std::int16_t select(uavcan::CanSelectMasks &inout_masks, const uavcan::CanFrame *(&)[uavcan::MaxCanIfaces], uavcan::MonotonicTime blocking_deadline) override
Definition: socketcan.hpp:664
uavcan_linux::SocketCanError::SocketWriteFailure
@ SocketWriteFailure
uavcan::CanIOFlags
uint16_t CanIOFlags
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:140
uavcan_linux::SocketCanIface::openSocket
static int openSocket(const std::string &iface_name)
Definition: socketcan.hpp:518
uavcan::MonotonicTime
Definition: time.hpp:184
uavcan_linux::SystemClock::adjustUtc
void adjustUtc(const uavcan::UtcDuration adjustment) override
Definition: platform_specific_components/linux/libuavcan/include/uavcan_linux/clock.hpp:124
uavcan_linux::SocketCanIface::poll
void poll(bool read, bool write)
Definition: socketcan.hpp:433
uavcan::CanFilterConfig::id
uint32_t id
Definition: libuavcan/libuavcan/include/uavcan/driver/can.hpp:101
makeFrame
static uavcan::CanFrame makeFrame(std::uint32_t id, const std::string &data)
Definition: test_socket.cpp:11


uavcan_communicator
Author(s):
autogenerated on Fri Dec 13 2024 03:10:03