uavcan_dynamic_node_id_server.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2015 Pavel Kirienko <pavel.kirienko@gmail.com>
3  */
4 
5 #include <iostream>
6 #include <algorithm>
7 #include <sstream>
8 #include <iomanip>
9 #include <string>
10 #include <cstdlib>
11 #include <cstdio>
12 #include <deque>
13 #include <unordered_map>
14 #include <sys/types.h>
15 #include <sys/stat.h>
16 #include <sys/ioctl.h>
17 #include <unistd.h>
18 #include "debug.hpp"
19 // UAVCAN
21 // UAVCAN Linux drivers
23 // UAVCAN POSIX drivers
24 #include <uavcan_posix/dynamic_node_id_server/file_storage_backend.hpp>
25 #include <uavcan_posix/dynamic_node_id_server/file_event_tracer.hpp>
26 
27 namespace
28 {
29 
30 constexpr int MaxNumLastEvents = 30;
31 constexpr int MinUpdateInterval = 100;
32 
33 uavcan_linux::NodePtr initNode(const std::vector<std::string>& ifaces, uavcan::NodeID nid, const std::string& name)
34 {
35  const auto app_id = uavcan_linux::makeApplicationID(uavcan_linux::MachineIDReader().read(), name, nid.get());
36 
37  uavcan::protocol::HardwareVersion hwver;
38  std::copy(app_id.begin(), app_id.end(), hwver.unique_id.begin());
39  std::cout << hwver << std::endl;
40 
41  auto node = uavcan_linux::makeNode(ifaces, name.c_str(), uavcan::protocol::SoftwareVersion(), hwver, nid);
42 
43  node->getLogger().setLevel(uavcan::protocol::debug::LogLevel::DEBUG);
44  node->setModeOperational();
45 
46  return node;
47 }
48 
49 
50 class EventTracer : public uavcan_posix::dynamic_node_id_server::FileEventTracer
51 {
52 public:
53  struct RecentEvent
54  {
55  const uavcan::MonotonicDuration time_since_startup;
56  const uavcan::UtcTime utc_timestamp;
57  const uavcan::dynamic_node_id_server::TraceCode code;
58  const std::int64_t argument;
59 
60  RecentEvent(uavcan::MonotonicDuration arg_time_since_startup,
61  uavcan::UtcTime arg_utc_timestamp,
62  uavcan::dynamic_node_id_server::TraceCode arg_code,
63  std::int64_t arg_argument)
64  : time_since_startup(arg_time_since_startup)
65  , utc_timestamp(arg_utc_timestamp)
66  , code(arg_code)
67  , argument(arg_argument)
68  { }
69 
70  uavcan::MakeString<81>::Type toString() const // Heapless return
71  {
72  char timebuf[12] = { };
73  {
74  const std::time_t rawtime = utc_timestamp.toUSec() * 1e-6;
75  const auto tm = std::localtime(&rawtime);
76  std::strftime(timebuf, 10, "%H:%M:%S.", tm);
77  std::snprintf(&timebuf[9], 3, "%02u", static_cast<unsigned>((utc_timestamp.toMSec() % 1000U) / 10U));
78  }
79 
80  decltype(toString()) out;
81  out.resize(out.capacity());
82  // coverity[overflow : FALSE]
83  (void)std::snprintf(reinterpret_cast<char*>(out.begin()), out.size() - 1U,
84  "%-11s %-28s %-20lld %016llx",
85  timebuf,
86  getEventName(code),
87  static_cast<long long>(argument),
88  static_cast<long long>(argument));
89  return out;
90  }
91 
92  static const char* getTableHeader()
93  {
94  // Matches the string format above
95  return "Timestamp Event name Argument (dec) Argument (hex)";
96  }
97  };
98 
99  struct EventStatisticsRecord
100  {
101  std::uint64_t count;
102  uavcan::MonotonicTime last_occurence;
103 
104  EventStatisticsRecord()
105  : count(0)
106  { }
107 
108  void hit(uavcan::MonotonicTime ts)
109  {
110  count++;
111  last_occurence = ts;
112  }
113  };
114 
115 private:
116  struct EnumKeyHash
117  {
118  template <typename T>
119  std::size_t operator()(T t) const { return static_cast<std::size_t>(t); }
120  };
121 
123  const uavcan::MonotonicTime started_at_ = clock_.getMonotonic();
124  const unsigned num_last_events_;
125 
126  std::deque<RecentEvent> last_events_;
127  std::unordered_map<uavcan::dynamic_node_id_server::TraceCode, EventStatisticsRecord, EnumKeyHash> event_counters_;
128 
129  bool had_events_ = false;
130 
131  void onEvent(uavcan::dynamic_node_id_server::TraceCode code, std::int64_t argument) override
132  {
133  uavcan_posix::dynamic_node_id_server::FileEventTracer::onEvent(code, argument);
134 
135  had_events_ = true;
136 
137  const auto ts_m = clock_.getMonotonic();
138  const auto ts_utc = clock_.getUtc();
139  const auto time_since_startup = ts_m - started_at_;
140 
141  last_events_.emplace_front(time_since_startup, ts_utc, code, argument);
142  if (last_events_.size() > num_last_events_)
143  {
144  last_events_.pop_back();
145  }
146 
147  event_counters_[code].hit(ts_m);
148  }
149 
150 public:
151  EventTracer(unsigned num_last_events_to_keep)
152  : num_last_events_(num_last_events_to_keep)
153  { }
154 
156 
157  const RecentEvent& getEventByIndex(unsigned index) const { return last_events_.at(index); }
158 
159  unsigned getNumEvents() const { return last_events_.size(); }
160 
161  const decltype(event_counters_)& getEventCounters() const { return event_counters_; }
162 
163  bool hadEvents()
164  {
165  if (had_events_)
166  {
167  had_events_ = false;
168  return true;
169  }
170  return false;
171  }
172 };
173 
174 
175 ::winsize getTerminalSize()
176 {
177  auto w = ::winsize();
178  ENFORCE(0 >= ioctl(STDOUT_FILENO, TIOCGWINSZ, &w));
179  ENFORCE(w.ws_col > 0 && w.ws_row > 0);
180  return w;
181 }
182 
183 
184 std::vector<std::pair<uavcan::dynamic_node_id_server::TraceCode, EventTracer::EventStatisticsRecord>>
185 collectRelevantEvents(const EventTracer& event_tracer, const unsigned num_events)
186 {
187  // First, creating a vector of pairs (event code, count)
188  typedef std::pair<uavcan::dynamic_node_id_server::TraceCode, EventTracer::EventStatisticsRecord> Pair;
189  const auto counters = event_tracer.getEventCounters();
190  std::vector<Pair> pairs(counters.size());
191  std::copy(counters.begin(), counters.end(), pairs.begin());
192 
193  // Now, sorting the pairs so that the most recent ones are on top of the list
194  std::sort(pairs.begin(), pairs.end(), [](const Pair& a, const Pair& b) {
195  return a.second.last_occurence > b.second.last_occurence;
196  });
197 
198  // Cutting the oldest events away
199  pairs.resize(std::min(num_events, unsigned(pairs.size())));
200 
201  // Sorting so that the most frequent events are on top of the list
202  std::stable_sort(pairs.begin(), pairs.end(), [](const Pair& a, const Pair& b) {
203  return a.second.count > b.second.count;
204  });
205 
206  return pairs;
207 }
208 
209 enum class CLIColor : unsigned
210 {
211  Red = 31,
212  Green = 32,
213  Yellow = 33,
214  Blue = 34,
215  Magenta = 35,
216  Cyan = 36,
217  White = 37,
218  Default = 39
219 };
220 
221 CLIColor getColorHash(unsigned value) { return CLIColor(31 + value % 7); }
222 
223 class CLIColorizer
224 {
225  const CLIColor color_;
226 public:
227  explicit CLIColorizer(CLIColor c) : color_(c)
228  {
229  std::printf("\033[%um", static_cast<unsigned>(color_));
230  }
231 
232  ~CLIColorizer()
233  {
234  std::printf("\033[%um", static_cast<unsigned>(CLIColor::Default));
235  }
236 };
237 
238 
239 void redraw(const uavcan_linux::NodePtr& node,
240  const uavcan::MonotonicTime timestamp,
241  const EventTracer& event_tracer,
243 {
245 
246  /*
247  * Constants that are permanent for the designed UI layout
248  */
249  constexpr unsigned NumRelevantEvents = 17;
250  constexpr unsigned NumRowsWithoutEvents = 3;
251 
252  /*
253  * Collecting the data
254  */
255  const unsigned num_rows = getTerminalSize().ws_row;
256 
257  const auto relevant_events = collectRelevantEvents(event_tracer, NumRelevantEvents);
258 
260 
261  const auto time_since_last_activity = timestamp - report.last_activity_timestamp;
262 
263  /*
264  * Basic rendering functions
265  */
266  unsigned next_relevant_event_index = 0;
267 
268  const auto render_next_event_counter = [&]()
269  {
270  const char* event_name = "";
271  char event_count_str[10] = { };
272  CLIColor event_color = CLIColor::Default;
273 
274  if (next_relevant_event_index < relevant_events.size())
275  {
276  const auto e = relevant_events[next_relevant_event_index];
277  event_name = uavcan::dynamic_node_id_server::IEventTracer::getEventName(e.first);
278  std::snprintf(event_count_str, sizeof(event_count_str) - 1U, "%llu",
279  static_cast<unsigned long long>(e.second.count));
280  event_color = getColorHash(static_cast<unsigned>(e.first));
281  }
282  next_relevant_event_index++;
283 
284  std::printf(" | ");
285  CLIColorizer izer(event_color);
286  std::printf("%-29s %-9s\n", event_name, event_count_str);
287  };
288 
289  const auto render_top_str = [&](const char* local_state_name, const char* local_state_value, CLIColor color)
290  {
291  {
292  CLIColorizer izer(color);
293  std::printf("%-20s %-16s", local_state_name, local_state_value);
294  }
295  render_next_event_counter();
296  };
297 
298  const auto render_top_int = [&](const char* local_state_name, long long local_state_value, CLIColor color)
299  {
300  char buf[21];
301  std::snprintf(buf, sizeof(buf) - 1U, "%lld", local_state_value);
302  render_top_str(local_state_name, buf, color);
303  };
304 
305  const auto raft_state_to_string = [](uavcan::dynamic_node_id_server::distributed::RaftCore::ServerState s)
306  {
307  switch (s)
308  {
309  case RaftCore::ServerStateFollower: return "Follower";
310  case RaftCore::ServerStateCandidate: return "Candidate";
311  case RaftCore::ServerStateLeader: return "Leader";
312  default: return "BADSTATE";
313  }
314  };
315 
316  const auto duration_to_string = [](uavcan::MonotonicDuration dur)
317  {
318  uavcan::MakeString<16>::Type str; // This is much faster than std::string
319  str.appendFormatted("%.1f", dur.toUSec() / 1e6);
320  return str;
321  };
322 
323  const auto colorize_if = [](bool condition, CLIColor color)
324  {
325  return condition ? color : CLIColor::Default;
326  };
327 
328  /*
329  * Rendering the data to the CLI
330  */
331  std::printf("\x1b[1J"); // Clear screen from the current cursor position to the beginning
332  std::printf("\x1b[H"); // Move cursor to the coordinates 1,1
333 
334  // Local state and relevant event counters - two columns
335  std::printf(" Local state | Event counters\n");
336 
337  render_top_int("Node ID",
338  node->getNodeID().get(),
340 
341  render_top_str("State",
342  raft_state_to_string(report.state),
343  (report.state == RaftCore::ServerStateCandidate) ? CLIColor::Magenta :
344  (report.state == RaftCore::ServerStateLeader) ? CLIColor::Green :
346 
347  render_top_int("Last log index",
348  report.last_log_index,
350 
351  render_top_int("Commit index",
352  report.commit_index,
353  colorize_if(report.commit_index != report.last_log_index, CLIColor::Magenta));
354 
355  render_top_int("Last log term",
356  report.last_log_term,
358 
359  render_top_int("Current term",
360  report.current_term,
362 
363  render_top_int("Voted for",
364  report.voted_for.get(),
366 
367  render_top_str("Since activity",
368  duration_to_string(time_since_last_activity).c_str(),
370 
371  render_top_str("Random timeout",
372  duration_to_string(report.randomized_timeout).c_str(),
374 
375  render_top_int("Unknown nodes",
376  report.num_unknown_nodes,
377  colorize_if(report.num_unknown_nodes != 0, CLIColor::Magenta));
378 
379  render_top_int("Node failures",
380  node->getInternalFailureCount(),
381  colorize_if(node->getInternalFailureCount() != 0, CLIColor::Magenta));
382 
383  const bool all_allocated = server.guessIfAllDynamicNodesAreAllocated();
384  render_top_str("All allocated",
385  all_allocated ? "Yes": "No",
386  colorize_if(!all_allocated, CLIColor::Magenta));
387 
388  // Empty line before the next block
389  std::printf(" ");
390  render_next_event_counter();
391 
392  // Followers block
393  std::printf(" Followers ");
394  render_next_event_counter();
395 
396  const auto render_followers_state = [&](const char* name,
397  const std::function<int (std::uint8_t)> value_getter,
398  const std::function<CLIColor (std::uint8_t)> color_getter)
399  {
400  std::printf("%-17s", name);
401  for (std::uint8_t i = 0; i < 4; i++)
402  {
403  if (i < (report.cluster_size - 1))
404  {
405  CLIColorizer colorizer(color_getter(i));
406  const auto value = value_getter(i);
407  if (value >= 0)
408  {
409  std::printf("%-5d", value);
410  }
411  else
412  {
413  std::printf("N/A ");
414  }
415  }
416  else
417  {
418  std::printf(" ");
419  }
420  }
421  render_next_event_counter();
422  };
423 
424  const auto follower_color_getter = [&](std::uint8_t i)
425  {
426  if (report.state != RaftCore::ServerStateLeader) { return CLIColor::Default; }
427  if (!report.followers[i].node_id.isValid()) { return CLIColor::Red; }
428  if (report.followers[i].match_index != report.last_log_index ||
429  report.followers[i].next_index <= report.last_log_index)
430  {
431  return CLIColor::Magenta;
432  }
433  return CLIColor::Default;
434  };
435 
436  render_followers_state("Node ID", [&](std::uint8_t i)
437  {
438  const auto nid = report.followers[i].node_id;
439  return nid.isValid() ? nid.get() : -1;
440  },
441  follower_color_getter);
442 
443  render_followers_state("Next index",
444  [&](std::uint8_t i) { return report.followers[i].next_index; },
445  follower_color_getter);
446 
447  render_followers_state("Match index",
448  [&](std::uint8_t i) { return report.followers[i].match_index; },
449  follower_color_getter);
450 
451  assert(next_relevant_event_index == NumRelevantEvents); // Ensuring that all events can be printed
452 
453  // Separator
454  std::printf("--------------------------------------+----------------------------------------\n");
455 
456  // Event log
457  std::printf("%s\n", EventTracer::RecentEvent::getTableHeader());
458  const int num_events_to_render = static_cast<int>(num_rows) -
459  static_cast<int>(next_relevant_event_index) -
460  static_cast<int>(NumRowsWithoutEvents) -
461  1; // This allows to keep the last line empty for stdout or UAVCAN_TRACE()
462  for (int i = 0;
463  i < num_events_to_render && i < static_cast<int>(event_tracer.getNumEvents());
464  i++)
465  {
466  const auto e = event_tracer.getEventByIndex(i);
467  CLIColorizer colorizer(getColorHash(static_cast<unsigned>(e.code)));
468  std::printf("%s\n", e.toString().c_str());
469  }
470 
471  std::fflush(stdout);
472 }
473 
474 
476  const std::uint8_t cluster_size,
477  const std::string& event_log_file,
478  const std::string& persistent_storage_path)
479 {
480  /*
481  * Event tracer
482  */
483  EventTracer event_tracer(MaxNumLastEvents);
484  ENFORCE(0 <= event_tracer.init(event_log_file.c_str()));
485 
486  /*
487  * Storage backend
488  */
489  uavcan_posix::dynamic_node_id_server::FileStorageBackend storage_backend;
490  ENFORCE(0 <= storage_backend.init(persistent_storage_path.c_str()));
491 
492  /*
493  * Server
494  */
495  uavcan::dynamic_node_id_server::DistributedServer server(*node, storage_backend, event_tracer);
496 
497  const int server_init_res = server.init(node->getNodeStatusProvider().getHardwareVersion().unique_id, cluster_size);
498  if (server_init_res < 0)
499  {
500  throw std::runtime_error("Failed to start the server; error " + std::to_string(server_init_res));
501  }
502 
503  /*
504  * Preparing the CLI
505  */
506  std::printf("\x1b[2J"); // Clear entire screen; this will preserve initialization output in the scrollback
507 
508  /*
509  * Spinning the node
510  */
511  uavcan::MonotonicTime last_redraw_at;
512 
513  while (true)
514  {
515  const int res = node->spin(uavcan::MonotonicDuration::fromMSec(MinUpdateInterval));
516  if (res < 0)
517  {
518  std::cerr << "Spin error: " << res << std::endl;
519  }
520 
521  const auto ts = node->getMonotonicTime();
522 
523  if (event_tracer.hadEvents() || (ts - last_redraw_at).toMSec() > 1000)
524  {
525  last_redraw_at = ts;
526  redraw(node, ts, event_tracer, server);
527  }
528  }
529 }
530 
531 struct Options
532 {
533  uavcan::NodeID node_id;
534  std::vector<std::string> ifaces;
535  std::uint8_t cluster_size = 0;
536  std::string storage_path;
537 };
538 
539 Options parseOptions(int argc, const char** argv)
540 {
541  const char* const executable_name = *argv++;
542  argc--;
543 
544  const auto enforce = [executable_name](bool condition, const char* error_text) {
545  if (!condition)
546  {
547  std::cerr << error_text << "\n"
548  << "Usage:\n\t"
549  << executable_name
550  << " <node-id> <can-iface-name-1> [can-iface-name-N...] [-c <cluster-size>] -s <storage-path>"
551  << std::endl;
552  std::exit(1);
553  }
554  };
555 
556  enforce(argc >= 3, "Not enough arguments");
557 
558  /*
559  * Node ID is always at the first position
560  */
561  argc--;
562  const int node_id = std::stoi(*argv++);
563  enforce(node_id >= 1 && node_id <= 127, "Invalid node ID");
564 
565  Options out;
566  out.node_id = uavcan::NodeID(std::uint8_t(node_id));
567 
568  while (argc --> 0)
569  {
570  const std::string token(*argv++);
571 
572  if (token[0] != '-')
573  {
574  out.ifaces.push_back(token);
575  }
576  else if (token[1] == 'c')
577  {
578  int cluster_size = 0;
579  if (token.length() > 2) // -c2
580  {
581  cluster_size = std::stoi(token.c_str() + 2);
582  }
583  else // -c 2
584  {
585  enforce(argc --> 0, "Expected cluster size");
586  cluster_size = std::stoi(*argv++);
587  }
588  enforce(cluster_size >= 1 &&
590  "Invalid cluster size");
591  out.cluster_size = std::uint8_t(cluster_size);
592  }
593  else if (token[1] == 's')
594  {
595  if (token.length() > 2) // -s/foo/bar
596  {
597  out.storage_path = token.c_str() + 2;
598  }
599  else // -s /foo/bar
600  {
601  enforce(argc --> 0, "Expected storage path");
602  out.storage_path = *argv++;
603  }
604  }
605  else
606  {
607  enforce(false, "Unexpected argument");
608  }
609  }
610 
611  enforce(!out.storage_path.empty(), "Invalid storage path");
612 
613  return out;
614 }
615 
616 }
617 
618 int main(int argc, const char** argv)
619 {
620  try
621  {
622  std::srand(std::time(nullptr));
623 
624  if (isatty(STDOUT_FILENO) != 1)
625  {
626  std::cerr << "This application cannot run if stdout is not associated with a terminal" << std::endl;
627  std::exit(1);
628  }
629 
630  auto options = parseOptions(argc, argv);
631 
632  std::cout << "Self node ID: " << int(options.node_id.get()) << "\n"
633  "Cluster size: " << int(options.cluster_size) << "\n"
634  "Storage path: " << options.storage_path << "\n"
635  "Num ifaces: " << options.ifaces.size() << "\n"
636 #ifdef NDEBUG
637  "Build mode: Release"
638 #else
639  "Build mode: Debug"
640 #endif
641  << std::endl;
642 
643  /*
644  * Preparing the storage directory
645  */
646  options.storage_path += "/node_" + std::to_string(options.node_id.get());
647 
648  int system_res = std::system(("mkdir -p '" + options.storage_path + "' &>/dev/null").c_str());
649  (void)system_res;
650 
651  const auto event_log_file = options.storage_path + "/events.log";
652  const auto storage_path = options.storage_path + "/storage/";
653 
654  /*
655  * Starting the node
656  */
657  auto node = initNode(options.ifaces, options.node_id, "org.uavcan.linux_app.dynamic_node_id_server");
658  runForever(node, options.cluster_size, event_log_file, storage_path);
659  return 0;
660  }
661  catch (const std::exception& ex)
662  {
663  std::cerr << "Error: " << ex.what() << std::endl;
664  return 1;
665  }
666 }
CLIColor::White
@ White
CLIColor::Magenta
@ Magenta
CLIColor
CLIColor
Definition: uavcan_monitor.cpp:12
uavcan::uint64_t
std::uint64_t uint64_t
Definition: std.hpp:27
uavcan::NodeID::isValid
bool isValid() const
Definition: transfer.hpp:134
std::size_t
unsigned long size_t
Definition: coverity_scan_model.cpp:19
uavcan::dynamic_node_id_server::distributed::RaftCore::ServerState
ServerState
Definition: raft_core.hpp:67
uavcan::UtcTime
Implicitly convertible to/from uavcan.Timestamp.
Definition: time.hpp:191
EventTracer::onEvent
virtual void onEvent(uavcan::dynamic_node_id_server::TraceCode code, uavcan::int64_t argument)
Definition: event_tracer.hpp:42
uavcan::NodeID::get
uint8_t get() const
Definition: transfer.hpp:132
uavcan::NodeID
Definition: transfer.hpp:112
uavcan::DurationBase< MonotonicDuration >::fromMSec
static MonotonicDuration fromMSec(int64_t ms)
Definition: time.hpp:41
CLIColor::Yellow
@ Yellow
main
int main(int argc, const char **argv)
Definition: uavcan_dynamic_node_id_server.cpp:618
uavcan::int64_t
std::int64_t int64_t
Definition: std.hpp:32
uavcan::MonotonicDuration
Definition: time.hpp:182
runForever
static void runForever(const uavcan_linux::NodePtr &node)
Definition: test_node.cpp:42
libuavcan_dsdl_compiler.str
str
Definition: libuavcan_dsdl_compiler/__init__.py:22
uavcan::dynamic_node_id_server::distributed::RaftCore
Definition: raft_core.hpp:64
initNode
static uavcan_linux::NodePtr initNode(const std::vector< std::string > &ifaces, uavcan::NodeID nid, const std::string &name)
Definition: test_node.cpp:10
uavcan::Array
Definition: array.hpp:424
pyuavcan_v0.dsdl.parser.enforce
def enforce(cond, fmt, *args)
Definition: parser.py:726
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
uavcan::snprintf
int snprintf(char *out, std::size_t maxlen, const char *format,...)
Definition: std.hpp:73
uavcan_linux.hpp
CLIColor::Red
@ Red
uavcan::dynamic_node_id_server::distributed::StateReport
Definition: distributed/server.hpp:286
EventTracer::getNumEvents
unsigned getNumEvents() const
Definition: event_tracer.hpp:76
debug.hpp
CLIColor::Green
@ Green
uavcan_linux::makeApplicationID
std::array< std::uint8_t, 16 > makeApplicationID(const MachineIDReader::MachineID &machine_id, const std::string &node_name, const std::uint8_t instance_id=0)
Definition: system_utils.hpp:143
toString
static std::string toString(long x)
Definition: multiset.cpp:16
CLIColor::Default
@ Default
CLIColor::Blue
@ Blue
uavcan::min
const UAVCAN_EXPORT T & min(const T &a, const T &b)
Definition: templates.hpp:281
uavcan::dynamic_node_id_server::distributed::ClusterManager::MaxClusterSize
@ MaxClusterSize
Definition: cluster_manager.hpp:33
uavcan::TimeBase::toMSec
uint64_t toMSec() const
Definition: time.hpp:121
int
int
Definition: libstubs.cpp:120
uavcan::dynamic_node_id_server::distributed::Server::init
int init(const UniqueID &own_unique_id, const uint8_t cluster_size=ClusterManager::ClusterSizeUnknown, const TransferPriority priority=TransferPriority::OneHigherThanLowest)
Definition: distributed/server.hpp:235
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
pyuavcan_v0.dsdl.signature.s
s
Definition: signature.py:73
std
uavcan_linux::MachineIDReader
Definition: system_utils.hpp:32
uavcan_linux::NodePtr
std::shared_ptr< Node > NodePtr
Definition: platform_specific_components/linux/libuavcan/include/uavcan_linux/helpers.hpp:354
uavcan_kinetis::clock::init
void init()
Definition: clock.cpp:43
pyuavcan_v0.introspect.node
node
Definition: introspect.py:398
uavcan::MonotonicTime
Definition: time.hpp:184
uavcan::dynamic_node_id_server::distributed::Server
Definition: distributed/server.hpp:25
uavcan::dynamic_node_id_server::AbstractServer::guessIfAllDynamicNodesAreAllocated
bool guessIfAllDynamicNodesAreAllocated(const MonotonicDuration &allocation_activity_timeout=MonotonicDuration::fromMSec(Allocation::MAX_REQUEST_PERIOD_MS *2), const MonotonicDuration &min_uptime=MonotonicDuration::fromMSec(6000)) const
Definition: abstract_server.hpp:68
CLIColor::Cyan
@ Cyan
uavcan::copy
UAVCAN_EXPORT OutputIt copy(InputIt first, InputIt last, OutputIt result)
Definition: templates.hpp:238
distributed.hpp
uavcan_linux::makeNode
static NodePtr makeNode(const std::vector< std::string > &iface_names, ClockAdjustmentMode clock_adjustment_mode=SystemClock::detectPreferredClockAdjustmentMode())
Definition: platform_specific_components/linux/libuavcan/include/uavcan_linux/helpers.hpp:363
EventTracer
Definition: event_tracer.hpp:15
uavcan::TimeBase::toUSec
uint64_t toUSec() const
Definition: time.hpp:120
EventTracer::EventTracer
EventTracer()
Definition: event_tracer.hpp:33


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