4 from roslaunch.xmlloader
import XmlLoader, loader
5 from rosgraph.names
import get_ros_namespace
11 def _include_tag(self, tag, context, ros_config, default_machine, is_core, verbose):
12 inc_filename = self.resolve_args(tag.attributes[
'file'].value, context)
13 ros_config.push_level(inc_filename, unique=
True)
14 result = super(LaunchtreeLoader, self).
_include_tag(tag, context, ros_config, default_machine, is_core, verbose)
15 ros_config.pop_level()
18 def _node_tag(self, tag, context, ros_config, default_machine, is_test=False, verbose=True):
21 self._check_attrs(tag, context, ros_config, XmlLoader.TEST_ATTRS)
22 (name,) = self.opt_attrs(tag, context, (
'name',))
23 test_name, time_limit, retry = self._test_attrs(tag, context)
27 self._check_attrs(tag, context, ros_config, XmlLoader.NODE_ATTRS)
28 (name,) = self.reqd_attrs(tag, context, (
'name',))
29 except Exception
as e:
32 ros_config.push_level(name)
33 result = super(LaunchtreeLoader, self).
_node_tag(tag, context, ros_config, default_machine, is_test, verbose)
34 ros_config.pop_level()
38 param_file = tag.attributes[
'file'].value \
39 if tag.attributes.has_key(
'file')
else '' 41 param_filename = self.resolve_args(param_file, context)
42 level_name = ros_config.push_level(param_filename, unique=
True)
43 result = super(LaunchtreeLoader, self).
_rosparam_tag(tag, context, ros_config, verbose)
45 ros_config.pop_level()
46 context.add_rosparam(tag.attributes.get(
'command',
'load'), param_filename, level_name)
49 def _load_launch(self, launch, ros_config, is_core=False, filename=None, argv=None, verbose=True):
53 self._launch_tag(launch, ros_config, filename)
55 loader.load_sysargs_into_context(self.
root_context, argv)
57 if len(launch.getElementsByTagName(
'master')) > 0:
58 print "WARNING: ignoring defunct <master /> tag" 59 self._recurse_load(ros_config, launch.childNodes, self.
root_context,
None, is_core, verbose)
def _node_tag(self, tag, context, ros_config, default_machine, is_test=False, verbose=True)
def _include_tag(self, tag, context, ros_config, default_machine, is_core, verbose)
def _rosparam_tag(self, tag, context, ros_config, verbose)
def _load_launch(self, launch, ros_config, is_core=False, filename=None, argv=None, verbose=True)