Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[roslaunch] Add yaml type for <param> tag #1045

Merged
18 changes: 10 additions & 8 deletions tools/roslaunch/src/roslaunch/loader.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,12 +39,13 @@
import os
from copy import deepcopy

import yaml

from roslaunch.core import Param, RosbinExecutable, RLException, PHASE_SETUP

from rosgraph.names import make_global_ns, ns_join, PRIV_NAME, load_mappings, is_legal_name, canonicalize_name

#lazy-import global for yaml and rosparam
yaml = None
rosparam = None

class LoadException(RLException):
Expand Down Expand Up @@ -88,12 +89,17 @@ def convert_value(value, type_):
elif type_ == 'double':
return float(value)
elif type_ == 'bool' or type_ == 'boolean':
value = value.lower()
value = value.lower().strip()
if value == 'true' or value == '1':
return True
elif value == 'false' or value == '0':
return False
raise ValueError("%s is not a '%s' type"%(value, type_))
elif type_ == 'yaml':
try:
return yaml.load(value)
except yaml.parser.ParserError as e:
raise ValueError(e)
else:
raise ValueError("Unknown type '%s'"%type_)

Expand Down Expand Up @@ -395,10 +401,6 @@ def load_rosparam(self, context, ros_config, cmd, param, file_, text, verbose=Tr
text = f.read()

# parse YAML text
# - lazy import
global yaml
if yaml is None:
import yaml
# - lazy import: we have to import rosparam in oder to to configure the YAML constructors
global rosparam
if rosparam is None:
Expand Down Expand Up @@ -468,7 +470,7 @@ def param_value(self, verbose, name, ptype, value, textfile, binfile, command):
return convert_value(value.strip(), ptype)
elif textfile is not None:
with open(textfile, 'r') as f:
return f.read()
return convert_value(f.read(), ptype)
elif binfile is not None:
try:
from xmlrpc.client import Binary
Expand Down Expand Up @@ -498,7 +500,7 @@ def param_value(self, verbose, name, ptype, value, textfile, binfile, command):
raise
if c_value is None:
raise ValueError("parameter: unable to get output of command [%s]"%command)
return c_value
return convert_value(c_value, ptype)
else: #_param_tag prevalidates, so this should not be reachable
raise ValueError("unable to determine parameter value")

9 changes: 9 additions & 0 deletions tools/roslaunch/test/xml/test-params-valid.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,9 @@

<param name="somefloat1" value="3.14159" type="double" />
<param name="somefloat2" value="5.0" />

<param name="someyaml1" value="[0, 1, 2]" type="yaml" />
<param name="someyaml2" value="{string1: bar2, string2: '10', integer1: 1, float1: 3.14, list1: [0, 1, 2], list2: ['a', 'b', 'c']}" type="yaml" />

<!-- you can set parameters in child namespaces -->
<param name="wg/wgchildparam" value="a child namespace parameter 1" />
Expand All @@ -32,6 +35,12 @@
<!-- upload the output of a command as a param. -->
<param name="commandoutput" command="cat &quot;$(find roslaunch)/resources/example.launch&quot;" />

<!-- upload the output of a command as a param as types. -->
<param name="commandoutputinteger" type="int" command="echo 0" />
<param name="commandoutputdouble" type="double" command="echo 10" />
<param name="commandoutputbool" type="bool" command="echo true" />
<param name="commandoutputyaml" type="yaml" command="cat &quot;$(find roslaunch)/test/params.yaml&quot;" />


<!-- test that we can override params -->
<param name="override" value="fail" />
Expand Down