launch_config.cpp
Go to the documentation of this file.
1 // Aggregates all information needed to start and monitor nodes
2 // Author: Max Schwarz <max.schwarz@uni-bonn.de>
3 
4 #include "launch_config.h"
5 #include "substitution.h"
6 #include "yaml_params.h"
7 #include "bytes_parser.h"
8 #include "string_utils.h"
9 
10 #include <ros/package.h>
11 #include <ros/names.h>
12 
13 #include <cctype>
14 #include <cstdarg>
15 #include <cstdio>
16 #include <fstream>
17 
18 #include <sys/wait.h>
19 
20 #include <boost/regex.hpp>
21 #include <boost/algorithm/string/case_conv.hpp>
22 #include <boost/algorithm/string/trim.hpp>
23 #include <boost/lexical_cast.hpp>
24 
25 #include <yaml-cpp/yaml.h>
26 
27 namespace rosmon
28 {
29 namespace launch
30 {
31 
32 const char* UNSET_MARKER = "~~~~~ ROSMON-UNSET ~~~~~";
33 
34 ParseContext ParseContext::enterScope(const std::string& prefix)
35 {
36  ParseContext ret = *this;
37 
38  const bool global_prefix = (!prefix.empty() && prefix.front() == '/');
39  ret.m_prefix = ros::names::clean(global_prefix ? prefix : (ret.m_prefix + prefix)) + "/";
40 
41  return ret;
42 }
43 
44 void ParseContext::parseScopeAttributes(TiXmlElement* e, ParseContext& attr_ctx)
45 {
46  if(const char* stopTimeout = e->Attribute("rosmon-stop-timeout"))
47  {
48  double seconds;
49  try
50  {
51  seconds = boost::lexical_cast<double>(attr_ctx.evaluate(stopTimeout));
52  }
53  catch(boost::bad_lexical_cast&)
54  {
55  throw error("bad rosmon-stop-timeout value '{}'", stopTimeout);
56  }
57  if(seconds < 0)
58  throw error("negative rosmon-stop-timeout value '{}'", stopTimeout);
59 
60  m_stopTimeout = seconds;
61  }
62 
63  if(const char* memoryLimit = e->Attribute("rosmon-memory-limit"))
64  {
65  uint64_t memoryLimitByte;
66  bool ok;
67  std::tie(memoryLimitByte, ok) = parseMemory(static_cast<std::string>(memoryLimit));
68  if(!ok)
69  {
70  throw error("{} cannot be parsed as a memory limit", memoryLimit);
71  }
72 
73  m_memoryLimit = memoryLimitByte;
74  }
75 
76  if(const char* cpuLimit = e->Attribute("rosmon-cpu-limit"))
77  {
78  double cpuLimitPct;
79  try
80  {
81  cpuLimitPct = boost::lexical_cast<double>(attr_ctx.evaluate(cpuLimit));
82  }
83  catch(boost::bad_lexical_cast&)
84  {
85  throw error("bad rosmon-cpu-limit value '{}'", cpuLimit);
86  }
87 
88  if(cpuLimitPct < 0)
89  throw error("negative rosmon-cpu-limit value'{}'", cpuLimit);
90 
91  m_cpuLimit = cpuLimitPct;
92  }
93 
94  if(const char* coredumpsEnabled = e->Attribute("enable-coredumps"))
95  {
96  m_coredumpsEnabled = attr_ctx.parseBool(coredumpsEnabled, e->Row());
97  }
98 }
99 
100 std::string ParseContext::evaluate(const std::string& tpl, bool simplifyWhitespace)
101 {
102  std::string simplified;
103  if(simplifyWhitespace)
104  simplified = string_utils::simplifyWhitespace(tpl);
105  else
106  simplified = tpl;
107 
108  try
109  {
110  return parseSubstitutionArgs(simplified, *this);
111  }
112  catch(SubstitutionException& e)
113  {
114  throw error("Substitution error: {}", e.what());
115  }
116 }
117 
118 bool ParseContext::parseBool(const std::string& value, int line)
119 {
120  std::string expansion = evaluate(value);
121 
122  // We are lenient here and accept the pythonic forms "True" and "False"
123  // as well, since roslaunch seems to do the same. Even the roslaunch/XML
124  // spec mentions True/False in the examples, even though they are not
125  // valid options for if/unless and other boolean attributes...
126  // http://wiki.ros.org/roslaunch/XML/rosparam
127 
128  if(expansion == "1" || expansion == "true" || expansion == "True")
129  return true;
130 
131  if(expansion == "0" || expansion == "false" || expansion == "False")
132  return false;
133 
134  throw error("Unknown truth value '%s'", expansion.c_str());
135 }
136 
137 bool ParseContext::shouldSkip(TiXmlElement* e)
138 {
139  const char* if_cond = e->Attribute("if");
140  const char* unless_cond = e->Attribute("unless");
141 
142  if(if_cond && unless_cond)
143  {
144  throw error("both if= and unless= specified, don't know what to do");
145  }
146 
147  if(if_cond)
148  {
149  return !parseBool(if_cond, e->Row());
150  }
151 
152  if(unless_cond)
153  {
154  return parseBool(unless_cond, e->Row());
155  }
156 
157  return false;
158 }
159 
160 void ParseContext::setArg(const std::string& name, const std::string& value, bool override)
161 {
162  auto it = m_args.find(name);
163  if(it == m_args.end())
164  m_args[name] = value;
165  else if(override || it->second == UNSET_MARKER)
166  m_args[name] = value;
167 }
168 
169 void ParseContext::setEnvironment(const std::string& name, const std::string& value)
170 {
171  m_environment[name] = value;
172 }
173 
174 void ParseContext::setRemap(const std::string& from, const std::string& to)
175 {
176  m_remappings[from] = to;
177 }
178 
179 std::string ParseContext::anonName(const std::string& base)
180 {
181  auto it = m_anonNames.find(base);
182  if(it == m_anonNames.end())
183  {
184  auto name = base + "_" + m_config->generateAnonHash();
185 
186  it = m_anonNames.emplace(base, name).first;
187  }
188 
189  return it->second;
190 }
191 
192 
194  : m_rootContext(this)
195  , m_anonGen(std::random_device()())
196 {
197  const char* ROS_NAMESPACE = getenv("ROS_NAMESPACE");
198  if(ROS_NAMESPACE)
199  {
200  // Someone set ROS_NAMESPACE, we should respect it.
201  // This may happen in nested situations, e.g. rosmon launching rosmon.
202  m_rootContext = m_rootContext.enterScope(ROS_NAMESPACE);
203  }
204 }
205 
206 void LaunchConfig::setArgument(const std::string& name, const std::string& value)
207 {
208  m_rootContext.setArg(name, value, true);
209 }
210 
212 {
213  m_rootContext.setStopTimeout(timeout);
214 }
215 
216 void LaunchConfig::setDefaultCPULimit(double CPULimit)
217 {
218  m_rootContext.setCPULimit(CPULimit);
219 }
220 
221 void LaunchConfig::setDefaultMemoryLimit(uint64_t memoryLimit)
222 {
223  m_rootContext.setMemoryLimit(memoryLimit);
224 }
225 
226 void LaunchConfig::parse(const std::string& filename, bool onlyArguments)
227 {
228  m_rootContext.setFilename(filename);
229 
230  TiXmlDocument document(filename);
231 
232  TiXmlBase::SetCondenseWhiteSpace(false);
233 
234  if(!document.LoadFile())
235  {
236  throw m_rootContext.error("Could not load launch file: {}", document.ErrorDesc());
237  }
238 
240  parse(document.RootElement(), &m_rootContext, onlyArguments);
241 
242  // Parse top-level rosmon-specific attributes
243  parseTopLevelAttributes(document.RootElement());
244 
245  if(!onlyArguments)
246  fmt::print("Loaded launch file in {:f}s\n", (ros::WallTime::now() - start).toSec());
247 }
248 
249 void LaunchConfig::parseString(const std::string& input, bool onlyArguments)
250 {
251  m_rootContext.setFilename("[string]");
252 
253  TiXmlDocument document;
254 
255  TiXmlBase::SetCondenseWhiteSpace(false);
256 
257  document.Parse(input.c_str());
258 
259  if(document.Error())
260  {
261  throw m_rootContext.error("Could not parse string input: {}", document.ErrorDesc());
262  }
263 
265  parse(document.RootElement(), &m_rootContext, onlyArguments);
266 
267  // Parse top-level rosmon-specific attributes
268  parseTopLevelAttributes(document.RootElement());
269 
270  if(!onlyArguments)
271  fmt::print("Loaded launch file in {:f}s\n", (ros::WallTime::now() - start).toSec());
272 }
273 
275 {
276  ros::WallDuration currentDelay(0, 0);
277 
278  for(auto& node : m_nodes)
279  {
280  if(node->spawnDelay().isZero())
281  {
282  node->setSpawnDelay(currentDelay);
283  currentDelay += autoIncrementSpawnDelay;
284  }
285  }
286 }
287 
288 void LaunchConfig::parseTopLevelAttributes(TiXmlElement* element)
289 {
290  const char* name = element->Attribute("rosmon-name");
291  if(name)
292  m_rosmonNodeName = name;
293 
294  const char* windowTitle = element->Attribute("rosmon-window-title");
295  if(windowTitle)
297 
298  const char* disableUI = element->Attribute("rosmon-disable-ui");
299  if(disableUI)
300  m_disableUI = m_rootContext.parseBool(disableUI, element->Row());
301 }
302 
303 void LaunchConfig::parse(TiXmlElement* element, ParseContext* ctx, bool onlyArguments)
304 {
305  ctx->parseScopeAttributes(element, *ctx);
306 
307  // First pass: Parse arguments
308  for(TiXmlNode* n = element->FirstChild(); n; n = n->NextSibling())
309  {
310  TiXmlElement* e = n->ToElement();
311  if(!e)
312  continue;
313 
314  if(ctx->shouldSkip(e))
315  continue;
316 
317  ctx->setCurrentElement(e);
318 
319  if(e->ValueStr() == "arg")
320  parseArgument(e, *ctx);
321  }
322 
323  if(onlyArguments)
324  return;
325 
326  // Second pass: everything else
327  for(TiXmlNode* n = element->FirstChild(); n; n = n->NextSibling())
328  {
329  TiXmlElement* e = n->ToElement();
330  if(!e)
331  continue;
332 
333  if(ctx->shouldSkip(e))
334  continue;
335 
336  ctx->setCurrentElement(e);
337 
338  if(e->ValueStr() == "node")
339  parseNode(e, *ctx);
340  else if(e->ValueStr() == "param")
341  parseParam(e, *ctx);
342  else if(e->ValueStr() == "rosparam")
343  parseROSParam(e, *ctx);
344  else if(e->ValueStr() == "group")
345  {
346  ParseContext cctx = *ctx;
347 
348  if(const char* ns = e->Attribute("ns"))
349  cctx = cctx.enterScope(ctx->evaluate(ns));
350 
351  cctx.parseScopeAttributes(e, *ctx);
352 
353  parse(e, &cctx);
354  }
355  else if(e->ValueStr() == "include")
356  parseInclude(e, *ctx);
357  else if(e->ValueStr() == "env")
358  parseEnv(e, *ctx);
359  else if(e->ValueStr() == "remap")
360  parseRemap(e, *ctx);
361  }
362 }
363 
364 void LaunchConfig::parseNode(TiXmlElement* element, ParseContext& attr_ctx)
365 {
366  const char* name = element->Attribute("name");
367  const char* pkg = element->Attribute("pkg");
368  const char* type = element->Attribute("type");
369  const char* args = element->Attribute("args");
370  const char* ns = element->Attribute("ns");
371  const char* respawn = element->Attribute("respawn");
372  const char* respawnDelay = element->Attribute("respawn_delay");
373  const char* nRespawnsAllowed = element->Attribute("rosmon-restart-warn-threshold");
374  const char* required = element->Attribute("required");
375  const char* launchPrefix = element->Attribute("launch-prefix");
376  const char* cwd = element->Attribute("cwd");
377  const char* clearParams = element->Attribute("clear_params");
378  const char* output = element->Attribute("output");
379  const char* spawnDelay = element->Attribute("rosmon-spawn-delay");
380 
381  if(!name || !pkg || !type)
382  {
383  throw attr_ctx.error("name, pkg, type are mandatory for node elements!");
384  }
385 
386  // Attributes are evaluated *outside* of the node context, so keep that one
387  ParseContext ctx = attr_ctx;
388 
389  if(ns)
390  ctx = ctx.enterScope(ctx.evaluate(ns));
391 
392  std::string fullNamespace = ctx.prefix().substr(0, ctx.prefix().length()-1);
393 
394  // Enter scope
395  ctx = ctx.enterScope(ctx.evaluate(name));
396 
397  // Parse scoped attributes such as rosmon-stop-timeout
398  ctx.parseScopeAttributes(element, attr_ctx);
399 
400  Node::Ptr node = std::make_shared<Node>(
401  attr_ctx.evaluate(name), attr_ctx.evaluate(pkg), attr_ctx.evaluate(type)
402  );
403 
404  // Check name uniqueness
405  {
406  auto it = std::find_if(m_nodes.begin(), m_nodes.end(), [&](const Node::Ptr& n) {
407  return n->namespaceString() == fullNamespace && n->name() == node->name();
408  });
409 
410  if(it != m_nodes.end())
411  {
412  throw ctx.error("node name '{}' is not unique", node->name());
413  }
414  }
415 
416  node->setStopTimeout(ctx.stopTimeout());
417  node->setMemoryLimit(ctx.memoryLimit());
418  node->setCPULimit(ctx.cpuLimit());
419  node->setCoredumpsEnabled(ctx.coredumpsEnabled());
420 
421  if(args)
422  node->addExtraArguments(ctx.evaluate(args));
423 
424  if(!fullNamespace.empty())
425  node->setNamespace(fullNamespace);
426 
427  if(respawn)
428  {
429  node->setRespawn(attr_ctx.parseBool(respawn, element->Row()));
430 
431  if(respawnDelay)
432  {
433  double seconds;
434  try
435  {
436  seconds = boost::lexical_cast<double>(attr_ctx.evaluate(respawnDelay));
437  }
438  catch(boost::bad_lexical_cast&)
439  {
440  throw ctx.error("bad respawn_delay value '{}'", respawnDelay);
441  }
442 
443  node->setRespawnDelay(ros::WallDuration(seconds));
444  }
445 
446  if (nRespawnsAllowed)
447  {
448  int n_respawns;
449  try
450  {
451  n_respawns = boost::lexical_cast<int>(attr_ctx.evaluate(nRespawnsAllowed));
452  }
453  catch(boost::bad_lexical_cast&)
454  {
455  throw ctx.error("bad rosmon-restart-warn-threshold value '{}'", nRespawnsAllowed);
456  }
457 
458  node->setNumRespawnsAllowed(n_respawns);
459  }
460  }
461 
462  if(spawnDelay)
463  {
464  double seconds;
465  try
466  {
467  seconds = boost::lexical_cast<double>(attr_ctx.evaluate(spawnDelay));
468  }
469  catch(boost::bad_lexical_cast&)
470  {
471  throw ctx.error("bad spawn_delay value '{}'", spawnDelay);
472  }
473 
474  node->setSpawnDelay(ros::WallDuration(seconds));
475  }
476 
477  if(required && attr_ctx.parseBool(required, element->Row()))
478  {
479  node->setRequired(true);
480  }
481 
482  // We have to parse rosparam tags first, see #118
483  for(TiXmlNode* n = element->FirstChild(); n; n = n->NextSibling())
484  {
485  TiXmlElement* e = n->ToElement();
486  if(!e)
487  continue;
488 
489  if(ctx.shouldSkip(e))
490  continue;
491 
492  ctx.setCurrentElement(e);
493 
494  if(e->ValueStr() == "rosparam")
495  parseROSParam(e, ctx);
496  }
497 
498  // Now we can parse everything else.
499  for(TiXmlNode* n = element->FirstChild(); n; n = n->NextSibling())
500  {
501  TiXmlElement* e = n->ToElement();
502  if(!e)
503  continue;
504 
505  if(ctx.shouldSkip(e))
506  continue;
507 
508  ctx.setCurrentElement(e);
509 
510  if(e->ValueStr() == "param")
511  parseParam(e, ctx, PARAM_IN_NODE);
512  else if(e->ValueStr() == "remap")
513  parseRemap(e, ctx);
514  else if(e->ValueStr() == "env")
515  parseEnv(e, ctx);
516  }
517 
518  ctx.setCurrentElement(element);
519 
520  // Set environment *after* parsing the node children (may contain env tags)
521  node->setExtraEnvironment(ctx.environment());
522 
523  if(launchPrefix)
524  node->setLaunchPrefix(attr_ctx.evaluate(launchPrefix));
525 
526  if(cwd)
527  node->setWorkingDirectory(attr_ctx.evaluate(cwd));
528 
529  if(clearParams)
530  node->setClearParams(attr_ctx.parseBool(clearParams, element->Row()));
531 
533  {
534  node->setStdoutDisplayed(false); // output=log is default
535  }
536 
537  if(output)
538  {
539  std::string outputStr = attr_ctx.evaluate(output);
540  if(outputStr == "screen")
541  node->setStdoutDisplayed(true);
542  else if(outputStr == "log")
543  node->setStdoutDisplayed(false);
544  else
545  throw ctx.error("Invalid output attribute value: '{}'", outputStr);
546  }
547 
548  node->setRemappings(ctx.remappings());
549 
550  m_nodes.push_back(node);
551 }
552 
553 static XmlRpc::XmlRpcValue autoXmlRpcValue(const std::string& fullValue)
554 {
555  std::string fullValueLowercase = boost::algorithm::to_lower_copy(fullValue);
556  if(fullValueLowercase == "true")
557  return XmlRpc::XmlRpcValue(true);
558  else if(fullValueLowercase == "false")
559  return XmlRpc::XmlRpcValue(false);
560  else
561  {
562  try { return boost::lexical_cast<int>(fullValue); }
563  catch(boost::bad_lexical_cast&) {}
564 
565  try { return boost::lexical_cast<double>(fullValue); }
566  catch(boost::bad_lexical_cast&) {}
567 
568  return fullValue;
569  }
570 }
571 
572 void LaunchConfig::parseParam(TiXmlElement* element, ParseContext& ctx, ParamContext paramContext)
573 {
574  const char* name = element->Attribute("name");
575  const char* value = element->Attribute("value");
576  const char* command = element->Attribute("command");
577  const char* textfile = element->Attribute("textfile");
578  const char* binfile = element->Attribute("binfile");
579  const char* type = element->Attribute("type");
580 
581  if(!name)
582  {
583  throw ctx.error("name is mandatory for param elements");
584  }
585 
586  int numCommands = (value ? 1 : 0) + (command ? 1 : 0) + (textfile ? 1 : 0) + (binfile ? 1 : 0);
587  if(numCommands > 1) // == 0 is checked below, don't duplicate.
588  {
589  throw ctx.error("<param> tags need exactly one of value=, command=, textfile=, binfile= attributes.");
590  }
591 
592  std::string fullName = ctx.evaluate(name);
593  if(fullName.empty())
594  {
595  throw ctx.error("param name is empty");
596  }
597 
598  // Expand relative paths. roslaunch ignores leading / when inside a
599  // <node> tag - god only knows why.
600  if(fullName[0] != '/' || paramContext == PARAM_IN_NODE)
601  {
602  // Same with "/" (see above)
603  if(paramContext == PARAM_IN_NODE && fullName[0] == '/')
604  {
605  ctx.warning("leading slashes in <param> names are ignored inside <node> contexts for roslaunch compatibility.");
606  fullName = fullName.substr(1);
607  }
608  else if(fullName[0] == '~')
609  {
610  // We silently ignore "~" at the beginning of the name
611  fullName = fullName.substr(1);
612  }
613 
614  fullName = ctx.prefix() + fullName;
615  }
616 
617  std::string errorStr;
618  if(!ros::names::validate(fullName, errorStr))
619  {
620  throw ctx.error("Expanded parameter name '{}' is invalid: {}",
621  fullName, errorStr
622  );
623  }
624 
625  std::string fullType;
626  if(type)
627  fullType = ctx.evaluate(type);
628 
629  if(value)
630  {
631  // Simple case - immediate value.
632  if(fullType == "yaml")
633  {
634  std::string fullValue = ctx.evaluate(value, false);
635 
636  YAML::Node n;
637  try
638  {
639  n = YAML::Load(fullValue);
640  }
641  catch(YAML::ParserException& e)
642  {
643  throw ctx.error("Invalid YAML: {}", e.what());
644  }
645 
646  loadYAMLParams(ctx, n, fullName);
647  }
648  else
649  {
650  // Note: roslaunch strips leading/trailing whitespace of all simple
651  // parameters. Furthermore, line feeds and tabs are replaced with
652  // space characters.
653  m_params[fullName] = paramToXmlRpc(ctx,
655  string_utils::strip(ctx.evaluate(value, false))
656  ),
657  fullType
658  );
659 
660  // A dynamic parameter of the same name gets overwritten now
661  m_paramJobs.erase(fullName);
662  }
663 
664  return;
665  }
666 
667  if(binfile)
668  {
669  // Also simple - binary files are always mapped to base64 XmlRpcValue.
670 
671  std::string fullFile = ctx.evaluate(binfile);
672 
673  m_paramJobs[fullName] = std::async(std::launch::deferred,
674  [=]() -> XmlRpc::XmlRpcValue {
675  std::ifstream stream(fullFile, std::ios::binary | std::ios::ate);
676  if(!stream)
677  throw ctx.error("Could not open file '{}'", fullFile);
678 
679  std::vector<char> data(stream.tellg(), 0);
680  stream.seekg(0, std::ios::beg);
681 
682  stream.read(data.data(), data.size());
683 
684  // Creates base64 XmlRpcValue
685  return {data.data(), static_cast<int>(data.size())};
686  }
687  );
688 
689  m_params.erase(fullName);
690  return;
691  }
692 
693  // Dynamic parameters are more complicated. We split the computation in
694  // two parts:
695  // 1) Compute the value as std::string
696  // 2) Convert to desired type (or dissect into multiple parameters in
697  // case of YAML-typed parameters).
698 
699  auto computeString = std::make_shared<std::future<std::string>>();
700 
701  // On ROS < Lunar, type="..." is not respected for command= and textfile=
702  // attributes. We support that anyway, but print a nice warning for users.
703  // See GH issue #138.
704 
705 #if !ROS_VERSION_MINIMUM(1,13,0)
706  if(type)
707  {
708  ctx.warning(
709  "On ROS versions prior to Lunar, roslaunch does not respect the "
710  "type attribute on <param> tags with command= or textfile= "
711  "actions. However, rosmon does support it and will create the "
712  "properly typed parameter {}.",
713  fullName
714  );
715  }
716 #endif
717 
718  if(command)
719  {
720  // Run a command and retrieve the results.
721  std::string fullCommand = ctx.evaluate(command);
722 
723  // Commands may take a while - that is why we use std::async here.
724  *computeString = std::async(std::launch::deferred,
725  [=]() -> std::string {
726  std::stringstream buffer;
727 
728  int pipe_fd[2];
729  if(pipe(pipe_fd) != 0)
730  throw ctx.error("Could not create pipe: {}", strerror(errno));
731 
732  int pid = fork();
733  if(pid < 0)
734  throw ctx.error("Could not fork: {}", strerror(errno));
735 
736  if(pid == 0)
737  {
738  // Child
739  close(pipe_fd[0]);
740  if(pipe_fd[1] != STDOUT_FILENO)
741  {
742  dup2(pipe_fd[1], STDOUT_FILENO);
743  close(pipe_fd[1]);
744  }
745 
746  char* argp[] = {strdup("sh"), strdup("-c"), strdup(fullCommand.c_str()), nullptr};
747 
748  execvp("sh", argp); // should never return
749  throw ctx.error("Could not execvp '{}': {}", fullCommand, strerror(errno));
750  }
751 
752  close(pipe_fd[1]);
753 
754  timeval timeout;
755  memset(&timeout, 0, sizeof(timeout));
756  timeout.tv_sec = 0;
757  timeout.tv_usec = 500 * 1000;
758 
759  while(true)
760  {
761  fd_set fds;
762  FD_ZERO(&fds);
763  FD_SET(pipe_fd[0], &fds);
764 
765  int ret = select(pipe_fd[0]+1, &fds, nullptr, nullptr, &timeout);
766  if(ret < 0)
767  throw ctx.error("Could not select(): {}", strerror(errno));
768 
769  if(ret == 0)
770  {
771  fmt::print("Still loading parameter '{}'...\n", fullName);
772 
773  timeout.tv_sec = 3;
774  continue;
775  }
776 
777  char buf[1024];
778  ret = read(pipe_fd[0], buf, sizeof(buf)-1);
779  if(ret < 0)
780  throw ctx.error("Could not read: {}", strerror(errno));
781  if(ret == 0)
782  break;
783 
784  buf[ret] = 0;
785  buffer << buf;
786  }
787 
788  close(pipe_fd[0]);
789 
790  int status = 0;
791  if(waitpid(pid, &status, 0) < 0)
792  throw ctx.error("Could not waitpid(): {}", strerror(errno));
793 
794  if(!WIFEXITED(status) || WEXITSTATUS(status) != 0)
795  {
796  throw ctx.error("<param> command failed (exit status {})",
797  WEXITSTATUS(status)
798  );
799  }
800 
801  return buffer.str();
802  }
803  );
804 
805  // A fixed parameter of the same name gets overwritten now
806  m_params.erase(fullName);
807  }
808  else if(textfile)
809  {
810  std::string fullFile = ctx.evaluate(textfile);
811 
812  *computeString = std::async(std::launch::deferred,
813  [=]() -> std::string {
814  std::ifstream stream(fullFile);
815  if(!stream)
816  throw ctx.error("Could not open file '{}'", fullFile);
817 
818  std::stringstream buffer;
819  buffer << stream.rdbuf();
820 
821  return buffer.str();
822  }
823  );
824  }
825  else
826  {
827  throw ctx.error("<param> needs either command, value, binfile, or textfile");
828  }
829 
830  if(fullType == "yaml")
831  {
832  m_yamlParamJobs.push_back(std::async(std::launch::deferred,
833  [=]() -> YAMLResult {
834  std::string yamlString = computeString->get();
835 
836  YAML::Node n;
837  try
838  {
839  n = YAML::Load(yamlString);
840  }
841  catch(YAML::ParserException& e)
842  {
843  throw ctx.error("Read invalid YAML from process or file: {}",
844  e.what()
845  );
846  }
847 
848  return {fullName, n};
849  }
850  ));
851  }
852  else
853  {
854  m_paramJobs[fullName] = std::async(std::launch::deferred,
855  [=]() -> XmlRpc::XmlRpcValue {
856  return paramToXmlRpc(ctx, computeString->get(), fullType);
857  }
858  );
859 
860  // A fixed parameter of the same name gets overwritten now
861  m_params.erase(fullName);
862  }
863 }
864 
865 XmlRpc::XmlRpcValue LaunchConfig::paramToXmlRpc(const ParseContext& ctx, const std::string& value, const std::string& type)
866 {
867  if(type.empty())
868  return autoXmlRpcValue(value);
869 
870  // Fixed type.
871  try
872  {
873  if(type == "int")
874  return boost::lexical_cast<int>(string_utils::strip(value));
875  else if(type == "double")
876  return boost::lexical_cast<double>(string_utils::strip(value));
877  else if(type == "bool" || type == "boolean")
878  {
879  std::string value_lowercase = boost::algorithm::to_lower_copy(
880  string_utils::strip(value)
881  );
882 
883  if(value_lowercase == "true")
884  return true;
885  else if(value_lowercase == "false")
886  return false;
887  else
888  throw ctx.error("invalid boolean value '{}'", value);
889  }
890  else if(type == "str" || type == "string")
891  return value;
892  else
893  {
894  throw ctx.error("invalid param type '{}'", type);
895  }
896  }
897  catch(boost::bad_lexical_cast& e)
898  {
899  throw ctx.error("could not convert param value '{}' to type '{}'",
900  value, type
901  );
902  }
903 }
904 
905 void LaunchConfig::parseROSParam(TiXmlElement* element, ParseContext& ctx)
906 {
907  const char* command = element->Attribute("command");
908 
909  if(!command || strcmp(command, "load") == 0)
910  {
911  const char* file = element->Attribute("file");
912  std::string fullFile;
913 
914  std::string contents;
915  if(file)
916  {
917  fullFile = ctx.evaluate(file);
918  std::ifstream stream(fullFile);
919  if(!stream)
920  throw ctx.error("Could not open file '{}'", fullFile);
921 
922  std::stringstream buffer;
923  buffer << stream.rdbuf();
924 
925  contents = buffer.str();
926  }
927  else
928  {
929  if(const char* t = element->GetText())
930  contents = t;
931  }
932 
933  // roslaunch silently ignores empty files (which are not valid YAML),
934  // so do the same here.
935  if(string_utils::isOnlyWhitespace(contents))
936  return;
937 
938  const char* subst_value = element->Attribute("subst_value");
939  if(subst_value && ctx.parseBool(subst_value, element->Row()))
940  contents = ctx.evaluate(contents, false);
941 
942  YAML::Node n;
943  try
944  {
945  n = YAML::Load(contents);
946  }
947  catch(YAML::ParserException& e)
948  {
949  throw ctx.error("Could not parse YAML: {}", e.what());
950  }
951 
952  ParseContext nameContext = ctx;
953  const char* ns = element->Attribute("ns");
954  if(ns)
955  nameContext = nameContext.enterScope(ctx.evaluate(ns));
956 
957  const char* name = element->Attribute("param");
958  if(name)
959  nameContext = nameContext.enterScope(ctx.evaluate(name));
960 
961  // Remove trailing / from prefix to get param name
962  try
963  {
964  loadYAMLParams(ctx, n, nameContext.prefix().substr(0, nameContext.prefix().length()-1));
965  }
966  catch(ParseException& e)
967  {
968  if(file)
969  {
970  throw ctx.error("error while parsing rosparam input file {}: {}",
971  fullFile, e.what()
972  );
973  }
974  else
975  {
976  throw ctx.error("error while parsing YAML input from launch file: {}",
977  e.what()
978  );
979  }
980  }
981  }
982  else
983  throw ctx.error("Unsupported rosparam command '{}'", command);
984 }
985 
986 void LaunchConfig::loadYAMLParams(const ParseContext& ctx, const YAML::Node& n, const std::string& prefix)
987 {
988  switch(n.Type())
989  {
990  case YAML::NodeType::Map:
991  {
992  // Pass 1: Load any anchor references
993  for(YAML::const_iterator it = n.begin(); it != n.end(); ++it)
994  {
995  if(it->first.as<std::string>() == "<<")
996  {
997  loadYAMLParams(ctx, it->second, prefix);
998  }
999  }
1000 
1001  // Pass 2: Everything else.
1002  for(YAML::const_iterator it = n.begin(); it != n.end(); ++it)
1003  {
1004  auto key = it->first.as<std::string>();
1005  if(key != "<<")
1006  {
1007  // Load "global" params without prefix (see #130)
1008  if(!key.empty() && key[0] == '/')
1009  loadYAMLParams(ctx, it->second, key);
1010  else
1011  loadYAMLParams(ctx, it->second, prefix + "/" + it->first.as<std::string>());
1012  }
1013  }
1014 
1015  break;
1016  }
1017  case YAML::NodeType::Sequence:
1018  case YAML::NodeType::Scalar:
1019  {
1020  m_params[prefix] = yamlToXmlRpc(ctx, n);
1021 
1022  // A dynamic parameter of the same name gets overwritten now
1023  m_paramJobs.erase(prefix);
1024  break;
1025  }
1026  case YAML::NodeType::Null:
1027  {
1028  // Nothing to do, empty node
1029  break;
1030  }
1031  default:
1032  {
1033  throw ctx.error("invalid yaml node type");
1034  }
1035  }
1036 }
1037 
1038 void LaunchConfig::parseInclude(TiXmlElement* element, ParseContext& ctx)
1039 {
1040  const char* file = element->Attribute("file");
1041  const char* ns = element->Attribute("ns");
1042  const char* passAllArgs = element->Attribute("pass_all_args");
1043  const char* clearParams = element->Attribute("clear_params");
1044  const char* importArgs = element->Attribute("rosmon-import-args");
1045 
1046  if(!file)
1047  throw ctx.error("<include> file attribute is mandatory");
1048 
1049  if(clearParams && ctx.parseBool(clearParams, element->Row()))
1050  {
1051  throw ctx.error("<include clear_params=\"true\" /> is not supported and probably a bad idea.");
1052  }
1053 
1054  std::string fullFile = ctx.evaluate(file);
1055 
1056  ParseContext childCtx = ctx;
1057  if(ns)
1058  childCtx = childCtx.enterScope(ctx.evaluate(ns));
1059 
1060  // Parse any arguments
1061  childCtx.parseScopeAttributes(element, ctx);
1062 
1063  // If pass_all_args is not set, delete the current arguments.
1064  if(!passAllArgs || !ctx.parseBool(passAllArgs, element->Row()))
1065  childCtx.clearArguments();
1066 
1067  // Now set all explicitly mentioned arguments.
1068  for(TiXmlNode* n = element->FirstChild(); n; n = n->NextSibling())
1069  {
1070  TiXmlElement* e = n->ToElement();
1071  if(!e)
1072  continue;
1073 
1074  if(ctx.shouldSkip(e))
1075  continue;
1076 
1077  if(e->ValueStr() == "arg")
1078  {
1079  const char* name = e->Attribute("name");
1080  const char* value = e->Attribute("value");
1081  const char* defaultValue = e->Attribute("default");
1082 
1083  if(!name)
1084  throw ctx.error("<arg> inside include needs a name attribute");
1085 
1086  if(!value && defaultValue)
1087  {
1088  // roslaunch allows this - god knows why.
1089  ctx.warning(
1090  "You are using <arg> inside an <include> tag with the "
1091  "default=XY attribute - which is superfluous. "
1092  "Use value=XY instead for less confusion. "
1093  "Attribute name: {}",
1094  name
1095  );
1096  value = defaultValue;
1097  }
1098 
1099  if(!name || !value)
1100  throw ctx.error("<arg> inside include needs name and value");
1101 
1102  childCtx.setArg(ctx.evaluate(name), ctx.evaluate(value), true);
1103  }
1104  }
1105 
1106  TiXmlDocument document(fullFile);
1107  if(!document.LoadFile())
1108  throw ctx.error("Could not load launch file '{}': {}", fullFile, document.ErrorDesc());
1109 
1110  childCtx.setFilename(fullFile);
1111 
1112  parse(document.RootElement(), &childCtx);
1113 
1114  // Import args from child context if requested
1115  if(importArgs && ctx.parseBool(importArgs, element->Row()))
1116  {
1117  for(auto& pair : childCtx.arguments())
1118  ctx.setArg(pair.first, pair.second, true);
1119  }
1120 }
1121 
1122 void LaunchConfig::parseArgument(TiXmlElement* element, ParseContext& ctx)
1123 {
1124  const char* name = element->Attribute("name");
1125  const char* value = element->Attribute("value");
1126  const char* def = element->Attribute("default");
1127 
1128  if(!name)
1129  throw ctx.error("<arg> needs name attribute");
1130 
1131  if(value)
1132  {
1133  std::string fullValue = ctx.evaluate(value);
1134  ctx.setArg(name, fullValue, true);
1135  }
1136  else if(def)
1137  {
1138  std::string fullValue = ctx.evaluate(def);
1139  ctx.setArg(name, fullValue, false);
1140  }
1141  else
1142  {
1143  ctx.setArg(name, UNSET_MARKER, false);
1144  }
1145 }
1146 
1147 void LaunchConfig::parseEnv(TiXmlElement* element, ParseContext& ctx)
1148 {
1149  const char* name = element->Attribute("name");
1150  const char* value = element->Attribute("value");
1151 
1152  if(!name || !value)
1153  throw ctx.error("<env> needs name, value attributes");
1154 
1155  ctx.setEnvironment(ctx.evaluate(name), ctx.evaluate(value));
1156 }
1157 
1158 void LaunchConfig::parseRemap(TiXmlElement* element, ParseContext& ctx)
1159 {
1160  const char* from = element->Attribute("from");
1161  const char* to = element->Attribute("to");
1162 
1163  if(!from || !to)
1164  throw ctx.error("remap needs 'from' and 'to' arguments");
1165 
1166  ctx.setRemap(ctx.evaluate(from), ctx.evaluate(to));
1167 }
1168 
1170 {
1171  return fmt::format("{:08X}", m_anonGen());
1172 }
1173 
1174 template<class Iterator>
1175 void safeAdvance(Iterator& it, const Iterator& end, size_t i)
1176 {
1177  for(size_t j = 0; j < i; ++j)
1178  {
1179  if(it == end)
1180  return;
1181  ++it;
1182  }
1183 }
1184 
1186 {
1187  // This function is optimized for speed, since we usually have a lot of
1188  // parameters and some of those take time (>2s) to compute and upload
1189  // (e.g. xacro).
1190 
1191  // The optimization is two-fold: we use std::future to avoid useless
1192  // computations of parameters which are re-set later on anyways, and
1193  // we use a thread pool to evaluate the futures below.
1194 
1195  const int NUM_THREADS = std::thread::hardware_concurrency();
1196 
1197  std::vector<std::thread> threads(NUM_THREADS);
1198 
1199  std::mutex mutex;
1200 
1201  bool caughtExceptionFlag = false;
1202  ParseException caughtException("");
1203 
1204  for(int i = 0; i < NUM_THREADS; ++i)
1205  {
1206  threads[i] = std::thread([this,i,NUM_THREADS,&mutex,&caughtException,&caughtExceptionFlag]() {
1207  try
1208  {
1209  // Thread number i starts at position i and moves in NUM_THREADS
1210  // increments.
1211  auto it = m_paramJobs.begin();
1212  safeAdvance(it, m_paramJobs.end(), i);
1213 
1214  while(it != m_paramJobs.end())
1215  {
1216  XmlRpc::XmlRpcValue val = it->second.get();
1217  {
1218  std::lock_guard<std::mutex> guard(mutex);
1219  m_params[it->first] = val;
1220  }
1221  safeAdvance(it, m_paramJobs.end(), NUM_THREADS);
1222  }
1223 
1224  // YAML parameters have to be handled separately, since we may need
1225  // to splice them into individual XmlRpcValues.
1226  auto yamlIt = m_yamlParamJobs.begin();
1227  safeAdvance(yamlIt, m_yamlParamJobs.end(), i);
1228 
1229  while(yamlIt != m_yamlParamJobs.end())
1230  {
1231  YAMLResult yaml = yamlIt->get();
1232  {
1233  std::lock_guard<std::mutex> guard(mutex);
1234  loadYAMLParams(m_rootContext, yaml.yaml, yaml.name);
1235  }
1236  safeAdvance(yamlIt, m_yamlParamJobs.end(), NUM_THREADS);
1237  }
1238  }
1239  catch(ParseException& e)
1240  {
1241  std::lock_guard<std::mutex> guard(mutex);
1242  caughtException = e;
1243  caughtExceptionFlag = true;
1244  }
1245  });
1246  }
1247 
1248  // and wait for completion for the threads.
1249  for(auto& t : threads)
1250  t.join();
1251 
1252  if(caughtExceptionFlag)
1253  throw caughtException;
1254 
1255  m_paramJobs.clear();
1256 }
1257 
1259 {
1260  m_outputAttrMode = mode;
1261 }
1262 
1263 void LaunchConfig::setWarningOutput(std::ostream* output)
1264 {
1265  m_warningOutput = output;
1266 }
1267 
1268 void LaunchConfig::setNodeLogDir(const std::string& dir)
1269 {
1270  m_nodeLogDir = dir;
1271 }
1272 
1273 }
1274 }
void setEnvironment(const std::string &name, const std::string &value)
virtual const char * what() const noexcept
Definition: launch_config.h:42
std::map< std::string, std::string > m_anonNames
bool shouldSkip(TiXmlElement *e)
std::string windowTitle() const
std::string simplifyWhitespace(const std::string &input)
Compress any sequence of whitespace to single spaces.
void setFilename(const std::string &filename)
Definition: launch_config.h:70
ROSCPP_DECL void start()
ParseContext enterScope(const std::string &prefix)
uint64_t memoryLimit() const
std::string anonName(const std::string &base)
void setArg(const std::string &name, const std::string &value, bool override)
virtual const char * what() const noexcept override
Definition: substitution.h:29
void setDefaultCPULimit(double CPULimit)
std::shared_ptr< Node > Ptr
Definition: node.h:23
ParseException error(const char *fmt, const Args &... args) const
std::map< std::string, ParameterFuture > m_paramJobs
ROSCPP_DECL bool validate(const std::string &name, std::string &error)
ROSCPP_DECL std::string clean(const std::string &name)
void setWarningOutput(std::ostream *warningStream)
void parseROSParam(TiXmlElement *element, ParseContext &ctx)
void parseInclude(TiXmlElement *element, ParseContext &ctx)
const std::map< std::string, std::string > & arguments() const
Definition: launch_config.h:96
void parseEnv(TiXmlElement *element, ParseContext &ctx)
std::string convertWhitespace(const std::string &input)
Convert any whitespace to space characters.
std::vector< std::future< YAMLResult > > m_yamlParamJobs
void parseString(const std::string &input, bool onlyArguments=false)
void setDefaultMemoryLimit(uint64_t memoryLimit)
const char * UNSET_MARKER
void parseArgument(TiXmlElement *element, ParseContext &ctx)
std::map< std::string, std::string > m_args
const std::string & prefix() const
Definition: launch_config.h:64
ROSLIB_DECL std::string command(const std::string &cmd)
std::map< std::string, std::string > m_environment
std::string evaluate(const std::string &tpl, bool simplifyWhitespace=true)
ROSCPP_DECL bool ok()
void setCPULimit(double limit)
void parse(const std::string &filename, bool onlyArguments=false)
void setCurrentElement(TiXmlElement *e)
Definition: launch_config.h:73
void setOutputAttrMode(OutputAttr mode)
void applyAutoIncrementSpawnDelayToAll(const ros::WallDuration &autoIncrementSpawnDelay)
static XmlRpc::XmlRpcValue autoXmlRpcValue(const std::string &fullValue)
void parseParam(TiXmlElement *element, ParseContext &ctx, ParamContext paramContext=PARAM_GENERAL)
static WallTime now()
void warning(const char *fmt, const Args &... args) const
void parseTopLevelAttributes(TiXmlElement *element)
XmlRpc::XmlRpcValue yamlToXmlRpc(const ParseContext &ctx, const YAML::Node &n)
Definition: yaml_params.cpp:41
void setArgument(const std::string &name, const std::string &value)
std::string parseSubstitutionArgs(const std::string &input, ParseContext &context)
std::vector< Node::Ptr > m_nodes
void setRemap(const std::string &from, const std::string &to)
const std::map< std::string, std::string > environment() const
void setNodeLogDir(const std::string &logDir)
void parseNode(TiXmlElement *element, ParseContext &ctx)
void setMemoryLimit(uint64_t limit)
void setStopTimeout(double timeout)
std::string strip(const std::string &input)
void parseRemap(TiXmlElement *element, ParseContext &ctx)
bool parseBool(const std::string &value, int line)
std::tuple< uint64_t, bool > parseMemory(const std::string &memory)
std::map< std::string, std::string > m_remappings
void setDefaultStopTimeout(double timeout)
const std::map< std::string, std::string > & remappings()
void safeAdvance(Iterator &it, const Iterator &end, size_t i)
XmlRpc::XmlRpcValue paramToXmlRpc(const ParseContext &ctx, const std::string &value, const std::string &type="")
void loadYAMLParams(const ParseContext &ctx, const YAML::Node &n, const std::string &prefix)
void parseScopeAttributes(TiXmlElement *e, ParseContext &attr_ctx)
bool isOnlyWhitespace(const std::string &input)
Check if string is whitespace only (includes &#39; &#39;)


rosmon_core
Author(s): Max Schwarz
autogenerated on Fri Jun 16 2023 02:15:06