test_multithreading.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2015 Pavel Kirienko <pavel.kirienko@gmail.com>
3  */
4 
5 #ifndef NDEBUG
6 # define UAVCAN_DEBUG 1
7 #endif
8 
9 #include <iostream>
10 #include <thread>
11 #include <condition_variable>
13 #include <uavcan/node/sub_node.hpp>
15 #include <uavcan/protocol/debug/KeyValue.hpp>
16 #include "debug.hpp"
17 
22 template <typename T>
23 class Queue
24 {
25  struct Item : public uavcan::LinkedListNode<Item>
26  {
28 
29  template <typename... Args>
30  Item(Args... args) : payload(args...) { }
31  };
32 
35 
36 public:
37  Queue(uavcan::IPoolAllocator& arg_allocator, std::size_t block_allocation_quota) :
38  allocator_(arg_allocator, block_allocation_quota)
39  {
41  }
42 
43  bool isEmpty() const { return list_.isEmpty(); }
44 
50  template <typename... Args>
51  bool tryEmplace(Args... args)
52  {
53  // Allocating memory
54  void* const ptr = allocator_.allocate(sizeof(Item));
55  if (ptr == nullptr)
56  {
57  return false;
58  }
59 
60  // Constructing the new item
61  Item* const item = new (ptr) Item(args...);
62  assert(item != nullptr);
63 
64  // Inserting the new item at the end of the list
65  Item* p = list_.get();
66  if (p == nullptr)
67  {
68  list_.insert(item);
69  }
70  else
71  {
72  while (p->getNextListNode() != nullptr)
73  {
74  p = p->getNextListNode();
75  }
76  assert(p->getNextListNode() == nullptr);
77  p->setNextListNode(item);
78  assert(p->getNextListNode()->getNextListNode() == nullptr);
79  }
80 
81  return true;
82  }
83 
89  T* peek() { return isEmpty() ? nullptr : &list_.get()->payload; }
90  const T* peek() const { return isEmpty() ? nullptr : &list_.get()->payload; }
91 
97  void pop()
98  {
99  Item* const item = list_.get();
100  assert(item != nullptr);
101  if (item != nullptr)
102  {
103  list_.remove(item);
104  item->~Item();
105  allocator_.deallocate(item);
106  }
107  }
108 };
109 
113 static void testQueue()
114 {
117  ENFORCE(q.isEmpty());
118  ENFORCE(q.peek() == nullptr);
119  ENFORCE(q.tryEmplace("One"));
120  ENFORCE(q.tryEmplace("Two"));
121  ENFORCE(q.tryEmplace("Three"));
122  ENFORCE(q.tryEmplace("Four"));
123  ENFORCE(!q.tryEmplace("Five"));
124  ENFORCE(*q.peek() == "One");
125  q.pop();
126  ENFORCE(*q.peek() == "Two");
127  q.pop();
128  ENFORCE(*q.peek() == "Three");
129  q.pop();
130  ENFORCE(*q.peek() == "Four");
131  q.pop();
132  ENFORCE(q.isEmpty());
133  ENFORCE(q.peek() == nullptr);
134 }
135 
142 {
143  struct RxItem
144  {
147 
148  RxItem(const uavcan::CanRxFrame& arg_frame, uavcan::CanIOFlags arg_flags) :
149  frame(arg_frame),
150  flags(arg_flags)
151  { }
152  };
153 
154  std::mutex& mutex_;
157 
159  {
160  std::lock_guard<std::mutex> lock(mutex_);
161  prioritized_tx_queue_.push(frame, tx_deadline, uavcan::CanTxQueue::Volatile, flags);
162  return 1;
163  }
164 
165  int16_t receive(uavcan::CanFrame& out_frame, uavcan::MonotonicTime& out_ts_monotonic,
166  uavcan::UtcTime& out_ts_utc, uavcan::CanIOFlags& out_flags) override
167  {
168  std::lock_guard<std::mutex> lock(mutex_);
169 
170  if (rx_queue_.isEmpty())
171  {
172  return 0;
173  }
174 
175  const auto item = *rx_queue_.peek();
176  rx_queue_.pop();
177 
178  out_frame = item.frame;
179  out_ts_monotonic = item.frame.ts_mono;
180  out_ts_utc = item.frame.ts_utc;
181  out_flags = item.flags;
182 
183  return 1;
184  }
185 
186  int16_t configureFilters(const uavcan::CanFilterConfig*, std::uint16_t) override { return -uavcan::ErrDriver; }
187  uint16_t getNumFilters() const override { return 0; }
188  uint64_t getErrorCount() const override { return 0; }
189 
190 public:
192  std::mutex& arg_mutex, unsigned quota_per_queue) :
193  mutex_(arg_mutex),
194  prioritized_tx_queue_(allocator, clock, quota_per_queue),
195  rx_queue_(allocator, quota_per_queue)
196  { }
197 
204  {
205  std::lock_guard<std::mutex> lock(mutex_);
206  if (!rx_queue_.tryEmplace(frame, flags) && !rx_queue_.isEmpty())
207  {
208  rx_queue_.pop();
209  (void)rx_queue_.tryEmplace(frame, flags);
210  }
211  }
212 
217  void flushTxQueueTo(uavcan::INode& main_node, std::uint8_t iface_index)
218  {
219  std::lock_guard<std::mutex> lock(mutex_);
220 
221  const std::uint8_t iface_mask = static_cast<std::uint8_t>(1U << iface_index);
222 
223  while (auto e = prioritized_tx_queue_.peek())
224  {
225  UAVCAN_TRACE("VirtualCanIface", "TX injection [iface=0x%02x]: %s",
226  unsigned(iface_mask), e->toString().c_str());
227 
228  const int res = main_node.injectTxFrame(e->frame, e->deadline, iface_mask,
229  uavcan::CanTxQueue::Qos(e->qos), e->flags);
230  prioritized_tx_queue_.remove(e);
231  if (res <= 0)
232  {
233  break;
234  }
235  }
236  }
237 
242  bool hasDataInRxQueue() const
243  {
244  std::lock_guard<std::mutex> lock(mutex_);
245  return !rx_queue_.isEmpty();
246  }
247 };
248 
254 {
255 public:
256  virtual ~ITxQueueInjector() { }
257 
262  virtual void injectTxFramesInto(uavcan::INode& main_node) = 0;
263 };
264 
272 template <unsigned SharedMemoryPoolSize>
275  public ITxQueueInjector,
277 {
278  class Event
279  {
280  std::mutex m_;
281  std::condition_variable cv_;
282 
283  public:
288  {
289  std::unique_lock<std::mutex> lk(m_);
290  (void)cv_.wait_for(lk, std::chrono::microseconds(duration.toUSec()));
291  }
292 
293  void signal() { cv_.notify_all(); }
294  };
295 
297  std::mutex mutex_;
300  const unsigned num_ifaces_;
302 
303  uavcan::ICanIface* getIface(uint8_t iface_index) override
304  {
305  return (iface_index < num_ifaces_) ? ifaces_[iface_index].operator VirtualCanIface*() : nullptr;
306  }
307 
308  uint8_t getNumIfaces() const override { return num_ifaces_; }
309 
315  uavcan::MonotonicTime blocking_deadline) override
316  {
317  bool need_block = (inout_masks.write == 0); // Write queue is infinite
318  for (unsigned i = 0; need_block && (i < num_ifaces_); i++)
319  {
320  const bool need_read = inout_masks.read & (1U << i);
321  if (need_read && ifaces_[i]->hasDataInRxQueue())
322  {
323  need_block = false;
324  }
325  }
326 
327  if (need_block)
328  {
329  event_.waitFor(blocking_deadline - clock_.getMonotonic());
330  }
331 
332  inout_masks = uavcan::CanSelectMasks();
333  for (unsigned i = 0; i < num_ifaces_; i++)
334  {
335  const std::uint8_t iface_mask = 1U << i;
336  inout_masks.write |= iface_mask; // Always ready to write
337  if (ifaces_[i]->hasDataInRxQueue())
338  {
339  inout_masks.read |= iface_mask;
340  }
341  }
342 
343  return num_ifaces_; // We're always ready to write, hence > 0.
344  }
345 
350  {
351  UAVCAN_TRACE("VirtualCanDriver", "RX [flags=%u]: %s", unsigned(flags), frame.toString().c_str());
352  if (frame.iface_index < num_ifaces_)
353  {
354  ifaces_[frame.iface_index]->addRxFrame(frame, flags);
355  event_.signal();
356  }
357  }
358 
362  void injectTxFramesInto(uavcan::INode& main_node) override
363  {
364  for (unsigned i = 0; i < num_ifaces_; i++)
365  {
366  ifaces_[i]->flushTxQueueTo(main_node, i);
367  }
368  event_.signal();
369  }
370 
371 public:
372  VirtualCanDriver(unsigned arg_num_ifaces) : num_ifaces_(arg_num_ifaces)
373  {
374  assert(num_ifaces_ > 0 && num_ifaces_ <= uavcan::MaxCanIfaces);
375 
376  const unsigned quota_per_iface = allocator_.getBlockCapacity() / num_ifaces_;
377  const unsigned quota_per_queue = quota_per_iface; // 2x overcommit
378 
379  UAVCAN_TRACE("VirtualCanDriver", "Total blocks: %u, quota per queue: %u",
380  unsigned(allocator_.getBlockCapacity()), unsigned(quota_per_queue));
381 
382  for (unsigned i = 0; i < num_ifaces_; i++)
383  {
384  ifaces_[i].template construct<uavcan::IPoolAllocator&, uavcan::ISystemClock&,
385  std::mutex&, unsigned>(allocator_, clock_, mutex_, quota_per_queue);
386  }
387  }
388 };
389 
390 static uavcan_linux::NodePtr initMainNode(const std::vector<std::string>& ifaces, uavcan::NodeID nid,
391  const std::string& name)
392 {
393  std::cout << "Initializing main node" << std::endl;
394 
395  auto node = uavcan_linux::makeNode(ifaces, name.c_str(),
396  uavcan::protocol::SoftwareVersion(), uavcan::protocol::HardwareVersion(), nid);
397  node->getLogger().setLevel(uavcan::protocol::debug::LogLevel::DEBUG);
398  node->setModeOperational();
399  return node;
400 }
401 
402 template <unsigned QueuePoolSize>
403 static uavcan_linux::SubNodePtr initSubNode(unsigned num_ifaces, uavcan::INode& main_node)
404 {
405  std::cout << "Initializing sub node" << std::endl;
406 
407  typedef VirtualCanDriver<QueuePoolSize> Driver;
408 
409  std::shared_ptr<Driver> driver(new Driver(num_ifaces));
410 
411  auto node = uavcan_linux::makeSubNode(driver, main_node.getNodeID());
412 
413  main_node.getDispatcher().installRxFrameListener(driver.get());
414 
415  return node;
416 }
417 
419 {
420  std::cout << "Running main node" << std::endl;
421 
422  auto timer = node->makeTimer(uavcan::MonotonicDuration::fromMSec(10000), [&node](const uavcan::TimerEvent&)
423  {
424  node->logInfo("timer", "Your time is running out.");
425  // coverity[dont_call]
426  node->setVendorSpecificStatusCode(static_cast<std::uint16_t>(std::rand()));
427  });
428 
429  /*
430  * We know that in this implementation, VirtualCanDriver inherits uavcan::IRxFrameListener, so we can simply
431  * restore the reference to ITxQueueInjector using dynamic_cast. In other implementations this may be
432  * unacceptable, so a reference to ITxQueueInjector will have to be passed using some other means.
433  */
434  if (node->getDispatcher().getRxFrameListener() == nullptr)
435  {
436  throw std::logic_error("RX frame listener is not configured");
437  }
438  ITxQueueInjector& tx_injector = dynamic_cast<ITxQueueInjector&>(*node->getDispatcher().getRxFrameListener());
439 
440  while (true)
441  {
442  const int res = node->spin(uavcan::MonotonicDuration::fromMSec(1));
443  if (res < 0)
444  {
445  node->logError("spin", "Error %*", res);
446  }
447  // TX queue transfer occurs here.
448  tx_injector.injectTxFramesInto(*node);
449  }
450 }
451 
453 {
454  std::cout << "Running sub node" << std::endl;
455 
456  /*
457  * Log subscriber
458  */
459  auto log_sub = node->makeSubscriber<uavcan::protocol::debug::LogMessage>(
461  {
462  std::cout << msg << std::endl;
463  });
464 
465  /*
466  * Node status monitor
467  */
468  struct NodeStatusMonitor : public uavcan::NodeStatusMonitor
469  {
470  explicit NodeStatusMonitor(uavcan::INode& node) : uavcan::NodeStatusMonitor(node) { }
471 
472  virtual void handleNodeStatusChange(const NodeStatusChangeEvent& event) override
473  {
474  std::cout << "Remote node NID " << int(event.node_id.get()) << " changed status: "
475  << event.old_status.toString() << " --> " << event.status.toString() << std::endl;
476  }
477  };
478  NodeStatusMonitor nsm(*node);
479  ENFORCE(0 == nsm.start());
480 
481  /*
482  * KV subscriber
483  */
484  auto kv_sub = node->makeSubscriber<uavcan::protocol::debug::KeyValue>(
486  {
487  std::cout << msg << std::endl;
488  });
489 
490  /*
491  * KV publisher
492  */
493  unsigned kv_value = 0;
494  auto kv_pub = node->makePublisher<uavcan::protocol::debug::KeyValue>();
495  auto timer = node->makeTimer(uavcan::MonotonicDuration::fromMSec(5000), [&](const uavcan::TimerEvent&)
496  {
497  uavcan::protocol::debug::KeyValue kv;
498  kv.key = "five_seconds";
499  kv.value = kv_value++;
500  const int res = kv_pub->broadcast(kv);
501  if (res < 0)
502  {
503  std::cerr << "Sub KV pub err " << res << std::endl;
504  }
505  });
506 
507  while (true)
508  {
509  const int res = node->spin(uavcan::MonotonicDuration::fromMSec(1000));
510  if (res < 0)
511  {
512  std::cerr << "SubNode spin error: " << res << std::endl;
513  }
514  }
515 }
516 
517 int main(int argc, const char** argv)
518 {
519  try
520  {
521  testQueue();
522 
523  constexpr unsigned VirtualIfacePoolSize = 32768;
524 
525  if (argc < 3)
526  {
527  std::cerr << "Usage:\n\t" << argv[0] << " <node-id> <can-iface-name-1> [can-iface-name-N...]" << std::endl;
528  return 1;
529  }
530 
531  const int self_node_id = std::stoi(argv[1]);
532  std::vector<std::string> iface_names(argv + 2, argv + argc);
533 
534  auto node = initMainNode(iface_names, self_node_id, "org.uavcan.linux_test_node");
535  auto sub_node = initSubNode<VirtualIfacePoolSize>(iface_names.size(), *node);
536 
537  std::thread sub_thread([&sub_node](){ runSubNode(sub_node); });
538 
539  runMainNode(node);
540 
541  if (sub_thread.joinable())
542  {
543  std::cout << "Waiting for the sub thread to join" << std::endl;
544  sub_thread.join();
545  }
546 
547  return 0;
548  }
549  catch (const std::exception& ex)
550  {
551  std::cerr << "Exception: " << ex.what() << std::endl;
552  return 1;
553  }
554 }
void injectTxFramesInto(uavcan::INode &main_node) override
std::uint8_t uint8_t
Definition: std.hpp:24
virtual void deallocate(const void *ptr)
void addRxFrame(const uavcan::CanRxFrame &frame, uavcan::CanIOFlags flags)
Dispatcher & getDispatcher()
CanTxQueueEntry * peek()
Definition: uc_can_io.cpp:143
void push(const CanFrame &frame, MonotonicTime tx_deadline, CanIOFlags flags)
Definition: uc_can_io.cpp:104
static void testQueue()
VirtualCanDriver(unsigned arg_num_ifaces)
int16_t select(uavcan::CanSelectMasks &inout_masks, const uavcan::CanFrame *(&)[uavcan::MaxCanIfaces], uavcan::MonotonicTime blocking_deadline) override
void waitFor(uavcan::MonotonicDuration duration)
static uavcan_linux::NodePtr initMainNode(const std::vector< std::string > &ifaces, uavcan::NodeID nid, const std::string &name)
static void runMainNode(const uavcan_linux::NodePtr &node)
Queue< RxItem > rx_queue_
Queue(uavcan::IPoolAllocator &arg_allocator, std::size_t block_allocation_quota)
void installRxFrameListener(IRxFrameListener *listener)
Definition: dispatcher.hpp:211
uint8_t iface_index
Definition: can_io.hpp:29
int16_t configureFilters(const uavcan::CanFilterConfig *, std::uint16_t) override
uavcan_linux::SystemClock clock_
int64_t toUSec() const
Definition: time.hpp:43
virtual void injectTxFramesInto(uavcan::INode &main_node)=0
unsigned long size_t
static uavcan_linux::SubNodePtr initSubNode(unsigned num_ifaces, uavcan::INode &main_node)
void remove(CanTxQueueEntry *entry)
Definition: uc_can_io.cpp:132
int16_t receive(uavcan::CanFrame &out_frame, uavcan::MonotonicTime &out_ts_monotonic, uavcan::UtcTime &out_ts_utc, uavcan::CanIOFlags &out_flags) override
Implicitly convertible to/from uavcan.Timestamp.
Definition: time.hpp:191
uint8_t getNumIfaces() const override
void handleRxFrame(const uavcan::CanRxFrame &frame, uavcan::CanIOFlags flags) override
uavcan::PoolAllocator< SharedMemoryPoolSize, uavcan::MemPoolBlockSize > allocator_
Shared across all ifaces.
int rand()
Definition: main.cpp:28
static SubNodePtr makeSubNode(const std::vector< std::string > &iface_names, ClockAdjustmentMode clock_adjustment_mode=SystemClock::detectPreferredClockAdjustmentMode())
void flushTxQueueTo(uavcan::INode &main_node, std::uint8_t iface_index)
VirtualCanIface(uavcan::IPoolAllocator &allocator, uavcan::ISystemClock &clock, std::mutex &arg_mutex, unsigned quota_per_queue)
static void runSubNode(const uavcan_linux::SubNodePtr &node)
NodeID getNodeID() const
std::uint64_t uint64_t
Definition: std.hpp:27
const T * peek() const
uint16_t getNumFilters() const override
const uavcan::CanRxFrame frame
virtual void * allocate(std::size_t size)
uavcan::CanTxQueue prioritized_tx_queue_
std::mutex mutex_
Shared across all ifaces.
const unsigned num_ifaces_
uavcan::ICanIface * getIface(uint8_t iface_index) override
bool hasDataInRxQueue() const
static NodePtr makeNode(const std::vector< std::string > &iface_names, ClockAdjustmentMode clock_adjustment_mode=SystemClock::detectPreferredClockAdjustmentMode())
uavcan::CanFrame frame
Definition: can.cpp:78
int injectTxFrame(const CanFrame &frame, MonotonicTime tx_deadline, uint8_t iface_mask, CanIOFlags flags=0)
uavcan::LinkedListRoot< Item > list_
int main(int argc, const char **argv)
std::condition_variable cv_
virtual uint16_t getBlockCapacity() const
std::uint16_t uint16_t
Definition: std.hpp:25
static MonotonicDuration fromMSec(int64_t ms)
Definition: time.hpp:41
void remove(const T *node)
std::int16_t int16_t
Definition: std.hpp:30
int16_t send(const uavcan::CanFrame &frame, uavcan::MonotonicTime tx_deadline, uavcan::CanIOFlags flags) override
uint64_t getErrorCount() const override
const uavcan::CanIOFlags flags
bool tryEmplace(Args... args)
Item(Args... args)
uavcan::LimitedPoolAllocator allocator_
Event event_
Used to unblock the select() call when IO happens.
bool isEmpty() const
int
Definition: libstubs.cpp:120
RxItem(const uavcan::CanRxFrame &arg_frame, uavcan::CanIOFlags arg_flags)


uavcan_communicator
Author(s):
autogenerated on Wed Jan 11 2023 03:59:40