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


rosmon_core
Author(s): Max Schwarz
autogenerated on Wed Jul 10 2019 03:10:12