node_monitor.cpp
Go to the documentation of this file.
1 // Monitors a single node process
2 // Author: Max Schwarz <max.schwarz@uni-bonn.de>
3 
4 #include "node_monitor.h"
5 
6 #include <cerrno>
7 #include <csignal>
8 #include <cstdarg>
9 #include <cstdio>
10 #include <cstring>
11 #include <sstream>
12 
13 #include <fcntl.h>
14 #include <glob.h>
15 #include <pty.h>
16 #include <sys/types.h>
17 #include <sys/wait.h>
18 #include <sys/resource.h>
19 #include <sys/utsname.h>
20 #include <sys/prctl.h>
21 #include <unistd.h>
22 #include <wordexp.h>
23 
24 #include <boost/tokenizer.hpp>
25 #include <boost/range.hpp>
26 #include <boost/algorithm/string.hpp>
27 
28 #include <boost/filesystem.hpp>
29 
30 #include <fmt/format.h>
31 
32 #define TASK_COMM_LEN 16 // from linux/sched.h
33 
34 namespace fs = boost::filesystem;
35 
36 namespace
37 {
38  template<typename... Args>
39  std::runtime_error error(const char* fmt, const Args& ... args)
40  {
41  return std::runtime_error(fmt::format(fmt, args...));
42  }
43 
44  // finally() from C++ core guidelines
45  template <class F>
46  class final_act
47  {
48  public:
49  explicit final_act(F f) noexcept
50  : f_(std::move(f)), invoke_(true) {}
51 
52  final_act(final_act&& other) noexcept
53  : f_(std::move(other.f_)),
54  invoke_(other.invoke_)
55  {
56  other.invoke_ = false;
57  }
58 
59  final_act(const final_act&) = delete;
60  final_act& operator=(const final_act&) = delete;
61 
62  ~final_act() noexcept
63  {
64  if (invoke_) f_();
65  }
66 
67  private:
68  F f_;
69  bool invoke_;
70  };
71  template <class F>
72  inline final_act<F> finally(const F& f) noexcept
73  {
74  return final_act<F>(f);
75  }
76 
77  template <class F>
78  inline final_act<F> finally(F&& f) noexcept
79  {
80  return final_act<F>(std::forward<F>(f));
81  }
82 
83  static bool g_corePatternAnalyzed = false;
84  static bool g_coreIsRelative = true;
85  static bool g_coreIsSystemd = false;
86 }
87 
88 namespace rosmon
89 {
90 namespace monitor
91 {
92 
93 NodeMonitor::NodeMonitor(launch::Node::ConstPtr launchNode, FDWatcher::Ptr fdWatcher, ros::NodeHandle& nh)
94  : m_launchNode(std::move(launchNode))
95  , m_fdWatcher(std::move(fdWatcher))
96  , m_rxBuffer(4096)
97  , m_stderrBuffer(4096)
98  , m_exitCode(0)
99  , m_command(CMD_STOP) // we start in stopped state
100  , m_restarting(false)
101  , m_muted(m_launchNode->isMuted())
102 {
103  m_restartTimer = nh.createWallTimer(ros::WallDuration(1.0), boost::bind(&NodeMonitor::start, this), false, false);
104  m_stopCheckTimer = nh.createWallTimer(ros::WallDuration(m_launchNode->stopTimeout()), boost::bind(&NodeMonitor::checkStop, this));
105 
106  m_processWorkingDirectory = m_launchNode->workingDirectory();
107 
108  if(!g_corePatternAnalyzed)
109  {
110  char core_pattern[256];
111  int core_fd = open("/proc/sys/kernel/core_pattern", O_RDONLY | O_CLOEXEC);
112  if(core_fd < 0)
113  {
114  logTyped(LogEvent::Type::Error, "could not open /proc/sys/kernel/core_pattern: {}", strerror(errno));
115  return;
116  }
117 
118  int bytes = read(core_fd, core_pattern, sizeof(core_pattern)-1);
119  close(core_fd);
120 
121  if(bytes < 1)
122  {
123  logTyped(LogEvent::Type::Error, "Could not read /proc/sys/kernel/core_pattern: {}", strerror(errno));
124  return;
125  }
126 
127  g_coreIsRelative = (core_pattern[0] != '/');
128 
129  if(std::string(core_pattern).find("systemd-coredump") != std::string::npos)
130  g_coreIsSystemd = true;
131 
132  g_corePatternAnalyzed = true;
133  }
134 }
135 
137 {
138  if(m_pid != -1)
139  {
140  kill(m_pid, SIGKILL);
141  }
142 }
143 
144 std::vector<std::string> NodeMonitor::composeCommand() const
145 {
146  if(m_launchNode->executable().empty())
147  {
148  throw error("Could not find node '{}' in package '{}'",
149  m_launchNode->type(), m_launchNode->package()
150  );
151  }
152 
153  // Start with the launch prefix...
154  std::vector<std::string> cmd = m_launchNode->launchPrefix();
155 
156  // add executable file
157  cmd.push_back(m_launchNode->executable());
158 
159  // add extra arguments from 'args'
160  auto args = m_launchNode->extraArguments();
161  std::copy(args.begin(), args.end(), std::back_inserter(cmd));
162 
163  // add parameter for node name
164  cmd.push_back("__name:=" + m_launchNode->name());
165 
166  // and finally add remappings.
167  for(auto map : m_launchNode->remappings())
168  {
169  cmd.push_back(map.first + ":=" + map.second);
170  }
171 
172  return cmd;
173 }
174 
176 {
177  m_command = CMD_RUN;
178 
181  m_restarting = false;
182 
183  if(running())
184  return;
185 
186  if(m_launchNode->coredumpsEnabled() && g_coreIsRelative && m_processWorkingDirectory.empty())
187  {
188  char tmpfile[256];
189  strncpy(tmpfile, "/tmp/rosmon-node-XXXXXX", sizeof(tmpfile));
190  tmpfile[sizeof(tmpfile)-1] = 0;
191  m_processWorkingDirectory = mkdtemp(tmpfile);
193  }
194 
195  ROS_INFO("rosmon: starting '%s'", fullName().c_str());
196 
197  if(!m_firstStart)
198  logMessageSignal({"[rosmon]", fmt::format("Starting node {}", fullName()), LogEvent::Type::Info});
199 
200  m_firstStart = false;
201 
202  std::vector<std::string> cmd = composeCommand();
203 
204  std::vector<char*> args;
205  auto argsCleaner = finally([&args](){
206  for(char* arg : args)
207  free(arg);
208  });
209 
210  // Open pseudo-terminal
211  // NOTE: We are not using forkpty() here, as it is probably not safe in
212  // a multi-threaded process (see
213  // https://www.linuxprogrammingblog.com/threads-and-fork-think-twice-before-using-them)
214  int master, slave;
215 
216  if(openpty(&master, &slave, nullptr, nullptr, nullptr) == -1)
217  throw error("Could not open pseudo terminal for child process: {}", strerror(errno));
218 
219  // For stderr, we open a separate pipe
220  int stderr_pipe[2];
221  if(pipe(stderr_pipe) != 0)
222  throw error("Could not create stderr pipe: {}", strerror(errno));
223 
224  // Compose args
225  {
226  args.push_back(strdup("rosrun"));
227  args.push_back(strdup("rosmon_core"));
228  args.push_back(strdup("_shim"));
229 
230  args.push_back(strdup("--tty"));
231  args.push_back(strdup(fmt::format("{}", slave).c_str()));
232 
233  args.push_back(strdup("--stderr"));
234  args.push_back(strdup(fmt::format("{}", stderr_pipe[1]).c_str()));
235 
236  if(!m_launchNode->namespaceString().empty())
237  {
238  args.push_back(strdup("--namespace"));
239  args.push_back(strdup(m_launchNode->namespaceString().c_str()));
240  }
241 
242  for(auto& pair : m_launchNode->extraEnvironment())
243  {
244  args.push_back(strdup("--env"));
245  args.push_back(strdup(fmt::format("{}={}", pair.first, pair.second).c_str()));
246  }
247 
248  if(m_launchNode->coredumpsEnabled())
249  {
250  args.push_back(strdup("--coredump"));
251 
252  if(g_coreIsRelative)
253  {
254  args.push_back(strdup("--coredump-relative"));
255  args.push_back(strdup(m_processWorkingDirectory.c_str()));
256  }
257  }
258 
259  args.push_back(strdup("--run"));
260 
261  for(auto& c : cmd)
262  args.push_back(strdup(c.c_str()));
263 
264  args.push_back(nullptr);
265  }
266 
267  // Fork!
268  int pid = fork();
269  if(pid < 0)
270  throw error("Could not fork(): {}", strerror(errno));
271 
272  if(pid == 0)
273  {
274  close(master);
275  close(stderr_pipe[0]);
276 
277  if(execvp("rosrun", args.data()) != 0)
278  {
279  std::stringstream ss;
280  for(const auto& part : cmd)
281  ss << part << " ";
282 
283  fmt::print(stderr, "Could not execute '{}': {}\n", ss.str(), strerror(errno));
284  }
285 
286  // We should not end up here...
287  std::abort();
288  }
289 
290  // Parent
291  close(slave);
292  close(stderr_pipe[1]);
293 
294  m_fd = master;
295  m_stderrFD = stderr_pipe[0];
296  m_pid = pid;
297  m_fdWatcher->registerFD(m_fd, boost::bind(&NodeMonitor::communicate, this));
298  m_fdWatcher->registerFD(m_stderrFD, boost::bind(&NodeMonitor::communicateStderr, this));
299 }
300 
302 {
303  if(restart)
305  else
307 
310 
311  if(!running())
312  return;
313 
314  logMessageSignal({"[rosmon]", fmt::format("Stopping node {}", fullName()), LogEvent::Type::Info});
315 
316  // kill(-pid) sends the signal to all processes in the process group
317  kill(-m_pid, SIGINT);
318 
320 }
321 
323 {
324  if(running())
325  {
326  logTyped(LogEvent::Type::Warning, "required SIGKILL");
327  kill(m_pid, SIGKILL);
328  }
329 
331 }
332 
334 {
337 
338  if(running())
339  stop(true);
340  else
341  start();
342 }
343 
345 {
346  if(m_pid != -1)
347  {
348  kill(-m_pid, SIGINT);
349  }
350 }
351 
353 {
354  if(m_pid != -1)
355  {
356  kill(-m_pid, SIGKILL);
357  }
358 }
359 
361 {
362  return m_pid != -1;
363 }
364 
366 {
367  if(running())
368  return STATE_RUNNING;
369 
370  if(m_restarting)
371  return STATE_WAITING;
372 
373  if(m_exitCode == 0)
374  return STATE_IDLE;
375 
376  return STATE_CRASHED;
377 }
378 
380 {
381  auto handleByte = [&](char c){
382  m_stderrBuffer.push_back(c);
383  if(c == '\n')
384  {
385  m_stderrBuffer.push_back(0);
386  m_stderrBuffer.linearize();
387 
388  auto one = m_stderrBuffer.array_one();
389 
390  LogEvent event{fullName(), one.first};
391  event.muted = isMuted();
392  event.channel = LogEvent::Channel::Stderr;
393 
394  logMessageSignal(std::move(event));
395 
396  m_stderrBuffer.clear();
397  }
398  };
399 
400  char buf[1024];
401  int bytes = read(m_stderrFD, buf, sizeof(buf));
402 
403  if(bytes == 0)
404  {
405  // Flush out any remaining stdout
406  if(!m_stderrBuffer.empty())
407  handleByte('\n');
408 
409  m_fdWatcher->removeFD(m_stderrFD);
410  close(m_stderrFD);
411  m_stderrFD = -1;
412  return; // handled in communicate()
413  }
414 
415  if(bytes < 0)
416  throw error("{}: Could not read: {}", fullName(), strerror(errno));
417 
418  for(int i = 0; i < bytes; ++i)
419  {
420  handleByte(buf[i]);
421  }
422 }
423 
425 {
426  auto handleByte = [&](char c){
427  m_rxBuffer.push_back(c);
428  if(c == '\n')
429  {
430  m_rxBuffer.push_back(0);
431  m_rxBuffer.linearize();
432 
433  auto one = m_rxBuffer.array_one();
434 
435  LogEvent event{fullName(), one.first};
436  event.muted = isMuted();
437  event.channel = LogEvent::Channel::Stdout;
438  event.showStdout = m_launchNode->stdoutDisplayed();
439 
440  logMessageSignal(std::move(event));
441 
442  m_rxBuffer.clear();
443  }
444  };
445 
446  char buf[1024];
447  int bytes = read(m_fd, buf, sizeof(buf));
448 
449  if(bytes == 0 || (bytes < 0 && errno == EIO))
450  {
451  int status;
452 
453  while(true)
454  {
455  if(waitpid(m_pid, &status, 0) > 0)
456  break;
457 
458  if(errno == EINTR || errno == EAGAIN)
459  continue;
460 
461  throw error("{}: Could not waitpid(): {}", fullName(), strerror(errno));
462  }
463 
464  // Flush out any remaining stdout
465  if(!m_rxBuffer.empty())
466  handleByte('\n');
467 
468  if(WIFEXITED(status))
469  {
470  auto type = (WEXITSTATUS(status) == 0) ? LogEvent::Type::Info : LogEvent::Type::Error;
471  logTyped(type, "{} exited with status {}", fullName(), WEXITSTATUS(status));
472  ROS_INFO("rosmon: %s exited with status %d", fullName().c_str(), WEXITSTATUS(status));
473  m_exitCode = WEXITSTATUS(status);
474  }
475  else if(WIFSIGNALED(status))
476  {
477  logTyped(LogEvent::Type::Error, "{} died from signal {}", fullName(), WTERMSIG(status));
478  ROS_ERROR("rosmon: %s died from signal %d", fullName().c_str(), WTERMSIG(status));
479  m_exitCode = 255;
480  }
481 
482 #ifdef WCOREDUMP
483  if(WCOREDUMP(status))
484  {
485  if(!m_launchNode->launchPrefix().empty())
486  {
487  logTyped(LogEvent::Type::Info, "{} used launch-prefix, not collecting core dump as it is probably useless.", fullName());
488  }
489  else
490  {
491  // We have a chance to find the core dump...
492  logTyped(LogEvent::Type::Info, "{} left a core dump", fullName());
493  gatherCoredump(WTERMSIG(status));
494  }
495  }
496 #endif
497 
499  {
500  // Our removal strategy is two-fold: After a process exits,
501  // we immediately try to delete the temporary working directory.
502  // If that fails (e.g. because there is a core dump in there),
503  // we remember the directory in m_lastWorkingDirectory.
504 
505  // and then delete it recursively on the next process exit.
506  // That way, we always keep the last core dump around, but prevent
507  // infinite pile-up.
508  if(!m_lastWorkingDirectory.empty())
509  {
510  boost::system::error_code error;
511  boost::filesystem::remove_all(m_lastWorkingDirectory, error);
512  if(error)
513  {
515  "Could not remove old working directory '{}' after process died twice: {}",
516  m_lastWorkingDirectory, error.message()
517  );
518  }
519 
520  m_lastWorkingDirectory.clear();
521  }
522 
523  if(rmdir(m_processWorkingDirectory.c_str()) != 0)
524  {
525  logTyped(LogEvent::Type::Warning, "Could not remove process working directory '{}' after process exit: {}",
526  m_processWorkingDirectory, strerror(errno)
527  );
528 
530  }
531 
533  }
534 
535  m_pid = -1;
536  m_fdWatcher->removeFD(m_fd);
537  close(m_fd);
538  m_fd = -1;
539 
540  if(m_command == CMD_RESTART || (m_command == CMD_RUN && m_launchNode->respawn()))
541  {
542  if(m_command == CMD_RESTART)
544  else
545  m_restartTimer.setPeriod(m_launchNode->respawnDelay());
546 
547  m_restartCount++;
549  m_restarting = true;
550  }
551 
553 
554  return;
555  }
556 
557  if(bytes < 0)
558  throw error("{}: Could not read: {}", fullName(), strerror(errno));
559 
560  for(int i = 0; i < bytes; ++i)
561  {
562  handleByte(buf[i]);
563  }
564 }
565 
566 template<typename... Args>
567 void NodeMonitor::log(const char* format, Args&& ... args)
568 {
569  logMessageSignal({fullName(), fmt::format(format, std::forward<Args>(args)...)});
570 }
571 
572 template<typename... Args>
573 void NodeMonitor::logTyped(LogEvent::Type type, const char* format, Args&& ... args)
574 {
575  logMessageSignal({fullName(), fmt::format(format, std::forward<Args>(args)...), type});
576 }
577 
578 static boost::iterator_range<std::string::const_iterator>
579 corePatternFormatFinder(std::string::const_iterator begin, std::string::const_iterator end)
580 {
581  for(; begin != end && begin+1 != end; ++begin)
582  {
583  if(*begin == '%')
584  return {begin, begin+2};
585  }
586 
587  return {end, end};
588 }
589 
591 {
592  // If systemd-coredump is enabled, our job is easy
593  if(g_coreIsSystemd)
594  {
595  m_debuggerCommand = fmt::format("coredumpctl gdb COREDUMP_PID={}", m_pid);
596  return;
597  }
598 
599  // Otherwise we have to find the core ourselves...
600  char core_pattern[256];
601  int core_fd = open("/proc/sys/kernel/core_pattern", O_RDONLY | O_CLOEXEC);
602  if(core_fd < 0)
603  {
604  logTyped(LogEvent::Type::Error, "could not open /proc/sys/kernel/core_pattern: {}", strerror(errno));
605  return;
606  }
607 
608  int bytes = read(core_fd, core_pattern, sizeof(core_pattern)-1);
609  close(core_fd);
610 
611  if(bytes < 1)
612  {
613  log("Could not read /proc/sys/kernel/core_pattern: {}", strerror(errno));
614  return;
615  }
616 
617  core_pattern[bytes-1] = 0; // Strip off the newline at the end
618 
619  if(core_pattern[0] == '|')
620  {
621  // This may be apport, but apport still writes a "core" file if the
622  // limit is set appropriately.
623  strncpy(core_pattern, "core", sizeof(core_pattern));
624  }
625 
626  auto formatter = [&](boost::iterator_range<std::string::const_iterator> match) -> std::string {
627  char code = *(match.begin()+1);
628 
629  switch(code)
630  {
631  case '%':
632  return "%";
633  case 'p':
634  return std::to_string(m_pid);
635  case 'u':
636  return std::to_string(getuid());
637  case 'g':
638  return std::to_string(getgid());
639  case 's':
640  return std::to_string(signal);
641  case 't':
642  return "*"; // No chance
643  case 'h':
644  {
645  utsname uts;
646  memset(&uts, 0, sizeof(uts));
647  if(uname(&uts) != 0)
648  return "*";
649 
650  return uts.nodename;
651  }
652  case 'e':
653  return m_launchNode->type().substr(0, TASK_COMM_LEN-1);
654  case 'E':
655  {
656  std::string executable = m_launchNode->executable();
657  boost::replace_all(executable, "/", "!");
658  return executable;
659  }
660  case 'c':
661  {
662  rlimit limit;
663  memset(&limit, 0, sizeof(limit));
664  getrlimit(RLIMIT_CORE, &limit);
665 
666  // core limit is set to the maximum above
667  return std::to_string(limit.rlim_max);
668  }
669  default:
670  return "*";
671  }
672  };
673 
674  std::string coreGlob = boost::find_format_all_copy(std::string(core_pattern), corePatternFormatFinder, formatter);
675 
676  // If the pattern is not absolute, it is relative to our node's cwd.
677  if(coreGlob[0] != '/')
678  coreGlob = m_processWorkingDirectory + "/" + coreGlob;
679 
680  log("Determined pattern '{}'", coreGlob);
681 
682  glob_t results;
683  memset(&results, 0, sizeof(results));
684  int ret = glob(coreGlob.c_str(), GLOB_NOSORT, nullptr, &results);
685 
686  if(ret != 0 || results.gl_pathc == 0)
687  {
688  logTyped(LogEvent::Type::Warning, "Could not find a matching core file :-(");
689  globfree(&results);
690  return;
691  }
692 
693  if(results.gl_pathc > 1)
694  {
695  logTyped(LogEvent::Type::Info, "Found multiple matching core files :-(");
696  globfree(&results);
697  return;
698  }
699 
700  std::string coreFile = results.gl_pathv[0];
701  globfree(&results);
702 
703  logTyped(LogEvent::Type::Info, "Found core file '{}'", coreFile);
704 
705  std::stringstream ss;
706 
707  ss << "gdb " << m_launchNode->executable() << " " << coreFile;
708 
709  m_debuggerCommand = ss.str();
710 }
711 
713 {
714  std::string cmd;
715 
716  if(coredumpAvailable())
717  cmd = m_debuggerCommand;
718  else
719  {
720  std::stringstream ss;
721  ss << "gdb -p " << m_pid;
722  cmd = ss.str();
723  }
724 
725  if(!getenv("DISPLAY"))
726  {
727  logTyped(LogEvent::Type::Info, "No X11 available, run gdb yourself: {}", cmd);
728  }
729  else
730  {
731  char* envTerm = getenv("ROSMON_DEBUGGER_TERMINAL");
732  std::string term = "xterm -e";
733  if(envTerm)
734  term = envTerm;
735  else if(getenv("KONSOLE_DBUS_SESSION"))
736  term = "konsole -e";
737  else if(getenv("VTE_VERSION"))
738  term = "gnome-terminal -e";
739 
740  logTyped(LogEvent::Type::Info, "Launching debugger: '{}'", cmd);
741 
742  // system() is not particularly elegant here, but we trust our cmd.
743  if(system((term + " '" + cmd + "' &").c_str()) != 0)
744  {
745  logTyped(LogEvent::Type::Error, "Could not launch debugger");
746  }
747  }
748 }
749 
750 
752 {
753  m_userTime = 0;
754  m_systemTime = 0;
755  m_memory = 0;
756 }
757 
758 void NodeMonitor::addCPUTime(uint64_t userTime, uint64_t systemTime)
759 {
760  m_userTime += userTime;
761  m_systemTime += systemTime;
762 }
763 
764 void NodeMonitor::addMemory(uint64_t memoryBytes)
765 {
766  m_memory += memoryBytes;
767 }
768 
769 void NodeMonitor::endStatUpdate(double elapsedTimeInTicks)
770 {
771  m_userLoad = m_userTime / elapsedTimeInTicks;
772  m_systemLoad = m_systemTime / elapsedTimeInTicks;
773 }
774 
775 void NodeMonitor::setMuted(bool muted)
776 {
777  m_muted = muted;
778 }
779 
780 }
781 }
std::shared_ptr< const Node > ConstPtr
Definition: node.h:24
boost::signals2::signal< void(std::string)> exitedSignal
Signalled whenever the process exits.
Definition: node_monitor.h:195
void start()
Start the node.
void forceExit()
Finish shutdown sequence.
void setPeriod(const WallDuration &period, bool reset=true)
void addMemory(uint64_t memoryBytes)
void stop(bool restart=false)
Stop the node.
boost::circular_buffer< char > m_rxBuffer
Definition: node_monitor.h:222
boost::circular_buffer< char > m_stderrBuffer
Definition: node_monitor.h:223
std::string m_processWorkingDirectory
Definition: node_monitor.h:247
bool coredumpAvailable() const
Is a core dump available from a crash under rosmon control?
Definition: node_monitor.h:89
void log(const char *format, Args &&...args)
static boost::iterator_range< std::string::const_iterator > corePatternFormatFinder(std::string::const_iterator begin, std::string::const_iterator end)
void addCPUTime(uint64_t userTime, uint64_t systemTime)
Idle (e.g. exited with code 0)
Definition: node_monitor.h:34
float f(float t)
Definition: husl.c:142
void gatherCoredump(int signal)
#define ROS_INFO(...)
void launchDebugger()
Launch gdb interactively.
Waiting for automatic restart after crash.
Definition: node_monitor.h:37
WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
std::runtime_error error(const char *fmt, const Args &...args)
Definition: fd_watcher.cpp:15
#define TASK_COMM_LEN
boost::signals2::signal< void(LogEvent)> logMessageSignal
Logging signal.
Definition: node_monitor.h:192
int pid() const
Node PID.
Definition: node_monitor.h:175
ros::WallTimer m_stopCheckTimer
Definition: node_monitor.h:230
void endStatUpdate(double elapsedTimeInTicks)
std::string fullName() const
Full name including namespace.
Definition: node_monitor.h:169
void shutdown()
Start shutdown sequence.
std::string arg(const std::string &name, const ParseContext &context)
bool running() const
Is the node running?
std::vector< std::string > composeCommand() const
launch::Node::ConstPtr m_launchNode
Definition: node_monitor.h:218
Crashed (i.e. exited with code != 0)
Definition: node_monitor.h:36
State state() const
Get process state.
void logTyped(LogEvent::Type type, const char *format, Args &&...args)
void restart()
Restart the node.
#define ROS_ERROR(...)


rosmon_core
Author(s): Max Schwarz
autogenerated on Sat Jan 9 2021 03:35:43