main.cpp
Go to the documentation of this file.
1 // rosmon - versatile ROS node launcher & monitor
2 // Author: Max Schwarz <max.schwarz@uni-bonn.de>
3 
4 #include <ros/init.h>
5 #include <ros/master.h>
6 #include <ros/rate.h>
7 #include <ros/node_handle.h>
8 #include <ros/package.h>
9 #include <ros/console_backend.h>
10 #include <ros/this_node.h>
11 
12 #include <boost/filesystem.hpp>
13 #include <boost/lexical_cast.hpp>
14 
15 #include <unistd.h>
16 #include <getopt.h>
17 #include <csignal>
18 
19 #include <iostream>
20 
21 #include <fmt/format.h>
22 
23 #include "launch/launch_config.h"
24 #include "launch/bytes_parser.h"
25 #include "monitor/monitor.h"
26 #include "ui.h"
27 #include "ros_interface.h"
28 #include "package_registry.h"
29 #include "fd_watcher.h"
30 #include "logger.h"
31 
32 namespace fs = boost::filesystem;
33 
34 bool g_shouldStop = false;
35 bool g_flushStdout = false;
36 
37 static fs::path findFile(const fs::path& base, const std::string& name)
38 {
39  for(fs::directory_iterator it(base); it != fs::directory_iterator(); ++it)
40  {
41  if(fs::is_directory(*it))
42  {
43  fs::path p = findFile(*it, name);
44  if(!p.empty())
45  return p;
46  }
47  else if(it->path().leaf() == name)
48  return *it;
49  }
50 
51  return fs::path();
52 }
53 
54 void usage()
55 {
56  fprintf(stderr,
57  "Usage:\n"
58  " rosmon [actions] [options] some_package test.launch [arg1:=value1 ...]\n"
59  " rosmon [actions] [options] path/to/test.launch [arg1:=value1 ...]\n"
60  "\n"
61  "Actions (default is to launch the launch file):\n"
62  " --benchmark Exit after loading the launch file\n"
63  " --list-args List launch file arguments\n"
64  "\n"
65  "Options:\n"
66  " --disable-ui Disable fancy terminal UI\n"
67  " --flush-log Flush logfile after writing an entry\n"
68  " --flush-stdout Flush stdout after writing an entry\n"
69  " --help This help screen\n"
70  " --log=FILE Write log file to FILE\n"
71  " --name=NAME Use NAME as ROS node name. By default, an anonymous\n"
72  " name is chosen.\n"
73  " --no-start Don't automatically start the nodes in the beginning\n"
74  " --stop-timeout=SECONDS\n"
75  " Kill a process if it is still running this long\n"
76  " after the initial signal is send.\n"
77  " --disable-diagnostics\n"
78  " Disable publication of ros diagnostics message about\n"
79  " monitored nodes\n"
80  " --diagnostics-prefix=PREFIX\n"
81  " Prefix for the ros diagnostics generated by this node.\n"
82  " By default this will be the node name.\n"
83  " --cpu-limit=[0-n]\n"
84  " Default CPU Usage limit of monitored process. n is the\n"
85  " number of CPU cores. This is the sum of system and user\n"
86  " CPU usage.\n"
87  " --memory-limit=15MB\n"
88  " Default memory limit usage of monitored process.\n"
89  " --output-attr=obey|ignore\n"
90  " Obey or ignore output=\"*\" attributes on node tags.\n"
91  " Default is to ignore.\n"
92  "\n"
93  "rosmon also obeys some environment variables:\n"
94  " ROSMON_COLOR_MODE Can be set to 'truecolor', '256colors', 'ansi'\n"
95  " to force a specific color mode\n"
96  " If unset, rosmon tries to detect the best\n"
97  " available color mode.\n"
98  );
99 }
100 
101 void handleSignal(int)
102 {
103  g_shouldStop = true;
104 }
105 
106 void logToStdout(const rosmon::LogEvent& event, const int max_width)
107 {
108  fmt::print("{:>{}}: {}", event.source, max_width, event.message);
109 
110  if(!event.message.empty() && event.message.back() != '\n')
111  std::cout << '\n';
112 
113  if(g_flushStdout)
114  fflush(stdout);
115 }
116 
117 // Options
118 static const struct option OPTIONS[] = {
119  {"disable-ui", no_argument, nullptr, 'd'},
120  {"benchmark", no_argument, nullptr, 'b'},
121  {"flush-log", no_argument, nullptr, 'f'},
122  {"flush-stdout", no_argument, nullptr, 'F'},
123  {"help", no_argument, nullptr, 'h'},
124  {"list-args", no_argument, nullptr, 'L'},
125  {"log", required_argument, nullptr, 'l'},
126  {"name", required_argument, nullptr, 'n'},
127  {"no-start", no_argument, nullptr, 'S'},
128  {"stop-timeout", required_argument, nullptr, 's'},
129  {"disable-diagnostics", no_argument, nullptr, 'D'},
130  {"cpu-limit", required_argument, nullptr, 'c'},
131  {"memory-limit", required_argument, nullptr, 'm'},
132  {"diagnostics-prefix", required_argument, nullptr, 'p'},
133  {"output-attr", required_argument, nullptr, 'o'},
134  {nullptr, 0, nullptr, 0}
135 };
136 
137 enum Action {
141 };
142 
143 static int get_max_node_name(const rosmon::monitor::Monitor &monitor)
144 {
145  std::size_t max_width = 0;
146 
147  for(const auto& node : monitor.nodes())
148  {
149  max_width = std::max(max_width, node->fullName().size());
150  }
151 
152  return max_width;
153 }
154 
155 int main(int argc, char** argv)
156 {
157  std::string name;
158  std::string logFile;
159  std::string launchFilePath;
160 
161  Action action = ACTION_LAUNCH;
162  bool enableUI = true;
163  bool flushLog = false;
164  bool startNodes = true;
165  double stopTimeout = rosmon::launch::DEFAULT_STOP_TIMEOUT;
166  uint64_t memoryLimit = rosmon::launch::DEFAULT_MEMORY_LIMIT;
167  float cpuLimit = rosmon::launch::DEFAULT_CPU_LIMIT;
168  bool disableDiagnostics = false;
169  std::string diagnosticsPrefix;
171 
172  // Parse options
173  while(true)
174  {
175  int option_index;
176  int c = getopt_long(argc, argv, "h", OPTIONS, &option_index);
177 
178  if(c == -1)
179  break;
180 
181  switch(c)
182  {
183  case 'h':
184  usage();
185  return 0;
186  case 'n':
187  name = optarg;
188  break;
189  case 'l':
190  logFile = optarg;
191  break;
192  case 'L':
193  action = ACTION_LIST_ARGS;
194  break;
195  case 'b':
196  action = ACTION_BENCHMARK;
197  break;
198  case 'd':
199  enableUI = false;
200  break;
201  case 'f':
202  flushLog = true;
203  break;
204  case 'F':
205  g_flushStdout = true;
206  break;
207  case 'S':
208  startNodes = false;
209  break;
210  case 's':
211  try
212  {
213  stopTimeout = boost::lexical_cast<double>(optarg);
214  }
215  catch(boost::bad_lexical_cast&)
216  {
217  fmt::print(stderr, "Bad value for --stop-timeout argument: '{}'\n", optarg);
218  return 1;
219  }
220 
221  if(stopTimeout < 0)
222  {
223  fmt::print(stderr, "Stop timeout cannot be negative\n");
224  return 1;
225  }
226  break;
227  case 'D' :
228  disableDiagnostics = true;
229  break;
230  case 'c':
231  try
232  {
233  cpuLimit = boost::lexical_cast<float>(optarg);
234  }
235  catch(boost::bad_lexical_cast&)
236  {
237  fmt::print(stderr, "Bad value for --cpu-limit argument: '{}'\n", optarg);
238  return 1;
239  }
240 
241  if(cpuLimit < 0)
242  {
243  fmt::print(stderr, "CPU Limit cannot be negative\n");
244  return 1;
245  }
246  break;
247  case 'm':
248  {
249  bool ok;
250  std::tie(memoryLimit, ok) = rosmon::launch::parseMemory(optarg);
251  if(!ok)
252  {
253  fmt::print(stderr, "Bad value for --memory-limit argument: '{}'\n", optarg);
254  return 1;
255  }
256  break;
257  }
258  case 'o':
259  if(optarg == std::string("obey"))
261  else if(optarg == std::string("ignore"))
263  else
264  {
265  fmt::print(stderr, "Bad value for --output-attr argument: '{}'\n", optarg);
266  return 1;
267  }
268  break;
269  case 'p':
270  fmt::print(stderr, "Prefix : {}", optarg);
271  diagnosticsPrefix = std::string(optarg);
272  break;
273  }
274  }
275 
276  // Parse the positional arguments
277  if(optind == argc)
278  {
279  usage();
280  return 1;
281  }
282 
283  // Find first launch file argument (must contain ':=')
284  int firstArg = optind + 1;
285  for(; firstArg < argc; ++firstArg)
286  {
287  if(strstr(argv[firstArg], ":="))
288  break;
289  }
290 
291  // From the position of the argument (or the end-of-options), we know
292  // if we were called with a) package + filename or b) just a path.
293 
294  if(firstArg - optind == 1)
295  {
296  launchFilePath = argv[optind];
297  }
298  else if(firstArg - optind == 2)
299  {
300  const char* packageName = argv[optind];
301  const char* fileName = argv[optind + 1];
302 
303  std::string package = rosmon::PackageRegistry::getPath(packageName);
304  if(package.empty())
305  {
306  fmt::print(stderr, "Could not find path of package '{}'\n", packageName);
307  return 1;
308  }
309 
310  fs::path path = findFile(package, fileName);
311  if(path.empty())
312  {
313  fmt::print(stderr, "Could not find launch file '{}' in package '{}'\n",
314  fileName, packageName
315  );
316  return 1;
317  }
318 
319  launchFilePath = path.string();
320  }
321  else
322  {
323  usage();
324  return 1;
325  }
326 
327  // Setup logging
328  boost::scoped_ptr<rosmon::Logger> logger;
329  {
330  // Setup a sane ROSCONSOLE_FORMAT if the user did not already
331  setenv("ROSCONSOLE_FORMAT", "[${function}]: ${message}", 0);
332 
333  // Disable direct logging to stdout
335 
336  // Open logger
337  if(logFile.empty())
338  {
339  // Log to /tmp by default
340 
341  time_t t = time(nullptr);
342  tm currentTime;
343  memset(&currentTime, 0, sizeof(currentTime));
344  localtime_r(&t, &currentTime);
345 
346  char buf[256];
347  strftime(buf, sizeof(buf), "/tmp/rosmon_%Y_%m_%d_%H_%M_%S.log", &currentTime);
348 
349  logFile = buf;
350  }
351 
352  logger.reset(new rosmon::Logger(logFile, flushLog));
353  }
354 
356 
358  config->setDefaultStopTimeout(stopTimeout);
359  config->setDefaultCPULimit(cpuLimit);
360  config->setDefaultMemoryLimit(memoryLimit);
361  config->setOutputAttrMode(outputAttrMode);
362 
363  // Parse launch file arguments from command line
364  for(int i = firstArg; i < argc; ++i)
365  {
366  char* arg = strstr(argv[i], ":=");
367 
368  if(!arg)
369  {
370  fmt::print(stderr, "You specified a non-argument after an argument\n");
371  return 1;
372  }
373 
374  char* name = argv[i];
375 
376  *arg = 0;
377 
378  char* value = arg + 2;
379 
380  config->setArgument(name, value);
381  }
382 
383  bool onlyArguments = (action == ACTION_LIST_ARGS);
384 
385  try
386  {
387  config->parse(launchFilePath, onlyArguments);
388  config->evaluateParameters();
389  }
391  {
392  fmt::print(stderr, "Could not load launch file: {}\n", e.what());
393  return 1;
394  }
395 
396  switch(action)
397  {
398  case ACTION_BENCHMARK:
399  return 0;
400  case ACTION_LIST_ARGS:
401  for(const auto& arg : config->arguments())
402  std::cout << arg.first << std::endl;
403 
404  return 0;
405  case ACTION_LAUNCH:
406  break;
407  }
408 
409  if(config->disableUI())
410  enableUI = false;
411 
412  // Initialize the ROS node.
413  {
414  uint32_t init_options = ros::init_options::NoSigintHandler;
415 
416  // If the user did not specify a node name on the command line, look in
417  // the launch file
418  if(name.empty())
419  name = config->rosmonNodeName();
420 
421  // As last fallback, choose anonymous name.
422  if(name.empty())
423  {
424  name = "rosmon";
425  init_options |= ros::init_options::AnonymousName;
426  }
427 
428  // prevent ros::init from parsing the launch file arguments as remappings
429  int dummyArgc = 1;
430  ros::init(dummyArgc, argv, name, init_options);
431  }
432 
433  // Check connectivity to ROS master
434  {
435  fmt::print("ROS_MASTER_URI: '{}'\n", ros::master::getURI());
436  if(ros::master::check())
437  {
438  fmt::print("roscore is already running.\n");
439  }
440  else
441  {
442  fmt::print("roscore is not runnning.\n");
443  fmt::print("Waiting until it is up (abort with CTRL+C)...\n");
444 
445  while(!ros::master::check())
446  ros::WallDuration(0.5).sleep();
447 
448  fmt::print("roscore is running now.\n");
449  }
450  }
451 
452  ros::NodeHandle nh;
453 
454  fmt::print("Running as '{}'\n", ros::this_node::getName());
455 
456  rosmon::monitor::Monitor monitor(config, watcher);
457  monitor.logMessageSignal.connect(boost::bind(&rosmon::Logger::log, logger.get(), _1));
458 
459  fmt::print("\n\n");
460  monitor.setParameters();
461 
462  if(config->nodes().empty())
463  {
464  fmt::print("No ROS nodes to be launched. Finished...\n");
465  return 0;
466  }
467 
468  // Should we automatically start the nodes?
469  if(startNodes)
470  monitor.start();
471 
472  // Start the ncurses UI
473  boost::scoped_ptr<rosmon::UI> ui;
474  if(enableUI)
475  {
476  ui.reset(new rosmon::UI(&monitor, watcher));
477  }
478  else
479  {
480  monitor.logMessageSignal.connect(
481  boost::bind(
482  logToStdout,
483  _1,
484  get_max_node_name(monitor)));
485  }
486 
487  // ROS interface
488  rosmon::ROSInterface rosInterface(&monitor, !disableDiagnostics, diagnosticsPrefix);
489 
490  ros::WallDuration waitDuration(0.1);
491 
492  // On SIGINT, SIGTERM, SIGHUP we stop gracefully.
493  signal(SIGINT, handleSignal);
494  signal(SIGHUP, handleSignal);
495  signal(SIGTERM, handleSignal);
496 
497  // Main loop
498  while(ros::ok() && monitor.ok() && !g_shouldStop)
499  {
500  ros::spinOnce();
501  watcher->wait(waitDuration);
502 
503  if(ui)
504  ui->update();
505  }
506 
507  if(ui)
508  ui->log({"[rosmon]", "Shutting down..."});
509  monitor.shutdown();
510 
511  // Wait for graceful shutdown
513  while(!monitor.allShutdown() && ros::WallTime::now() - start < ros::WallDuration(monitor.shutdownTimeout()))
514  {
515  watcher->wait(waitDuration);
516 
517  if(ui)
518  ui->update();
519  }
520 
521  // If we timed out, force exit (kill the nodes with SIGKILL)
522  if(!monitor.allShutdown())
523  monitor.forceExit();
524 
525  rosInterface.shutdown();
526 
527  // Wait until that is finished (should always work)
528  while(!monitor.allShutdown())
529  {
530  watcher->wait(waitDuration);
531 
532  if(enableUI)
533  ui->update();
534  }
535 
536  // If coredumps are available, be helpful and display gdb commands
537  bool coredumpsAvailable = std::any_of(monitor.nodes().begin(), monitor.nodes().end(),
538  [](const rosmon::monitor::NodeMonitor::Ptr& n) { return n->coredumpAvailable(); }
539  );
540 
541  if(ui && coredumpsAvailable)
542  {
543  ui->log({"[rosmon]", "\n"});
544  ui->log({"[rosmon]", "If you want to debug one of the crashed nodes, you can use the following commands"});
545  for(auto& node : monitor.nodes())
546  {
547  if(node->coredumpAvailable())
548  {
549  ui->log({
550  "[rosmon]",
551  fmt::format("{:20}: # {}", node->name(), node->debuggerCommand())
552  });
553  }
554  }
555  }
556 
557  return 0;
558 }
virtual const char * what() const noexcept
Definition: launch_config.h:42
Definition: ui.h:20
const std::vector< NodeMonitor::Ptr > & nodes() const
Definition: monitor.h:41
ROSCPP_DECL const std::string & getURI()
boost::signals2::signal< void(LogEvent)> logMessageSignal
Definition: monitor.h:49
ROSCPP_DECL bool check()
void(* function_print)(void *,::ros::console::Level, const char *, const char *, const char *, int)
ROSCPP_DECL void start()
string package
int main(int argc, char **argv)
Definition: main.cpp:155
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void usage()
Definition: main.cpp:54
ROSCPP_DECL const std::string & getName()
std::shared_ptr< LaunchConfig > Ptr
static fs::path findFile(const fs::path &base, const std::string &name)
Definition: main.cpp:37
Write log messages into a log file.
Definition: logger.h:17
bool sleep() const
constexpr double DEFAULT_STOP_TIMEOUT
Definition: launch_config.h:30
ROSCPP_DECL bool ok()
void log(const LogEvent &event)
Log message.
Definition: logger.cpp:37
bool g_flushStdout
Definition: main.cpp:35
bool ok() const
Definition: monitor.h:38
void handleSignal(int)
Definition: main.cpp:101
constexpr uint64_t DEFAULT_MEMORY_LIMIT
Definition: launch_config.h:29
Action
Definition: main.cpp:137
static const struct option OPTIONS[]
Definition: main.cpp:118
bool g_shouldStop
Definition: main.cpp:34
static WallTime now()
std::string arg(const std::string &name, const ParseContext &context)
constexpr double DEFAULT_CPU_LIMIT
Definition: launch_config.h:28
static int get_max_node_name(const rosmon::monitor::Monitor &monitor)
Definition: main.cpp:143
std::tuple< uint64_t, bool > parseMemory(const std::string &memory)
ROSCPP_DECL void spinOnce()
std::string source
Definition: log_event.h:38
void logToStdout(const rosmon::LogEvent &event, const int max_width)
Definition: main.cpp:106
std::shared_ptr< NodeMonitor > Ptr
Definition: node_monitor.h:28
std::string message
Definition: log_event.h:39


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