Skip to content

Commit

Permalink
Reserve current behavior with handling strip cleanly
Browse files Browse the repository at this point in the history
  • Loading branch information
wkentaro committed May 16, 2017
1 parent ea65411 commit b746f71
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 9 deletions.
1 change: 1 addition & 0 deletions tools/roslaunch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
<run_depend version_gte="1.13.3">rosunit</run_depend>

<test_depend>rosbuild</test_depend>
<test_depend>rospy</test_depend>

<export>
<rosdoc config="rosdoc.yaml"/>
Expand Down
18 changes: 9 additions & 9 deletions tools/roslaunch/src/roslaunch/loader.py
Original file line number Diff line number Diff line change
Expand Up @@ -70,25 +70,25 @@ def convert_value(value, type_):
#attempt numeric conversion
try:
if '.' in value:
return float(value)
return float(value.strip())
else:
return int(value)
return int(value.strip())
except ValueError as e:
pass
#bool
lval = value.lower()
lval = value.strip().lower()
if lval == 'true' or lval == 'false':
return convert_value(value, 'bool')
#string
return value
elif type_ == 'str' or type_ == 'string':
return value
elif type_ == 'int':
return int(value)
return int(value.strip())
elif type_ == 'double':
return float(value)
return float(value.strip())
elif type_ == 'bool' or type_ == 'boolean':
value = value.lower()
value = value.strip().lower()
if value == 'true' or value == '1':
return True
elif value == 'false' or value == '0':
Expand Down Expand Up @@ -471,10 +471,10 @@ def param_value(self, verbose, name, ptype, value, textfile, binfile, command):
@raise ValueError: if parameters are invalid
"""
if value is not None:
return convert_value(value.strip(), ptype)
return convert_value(value, ptype)
elif textfile is not None:
with open(textfile, 'r') as f:
return convert_value(f.read().strip(), ptype)
return convert_value(f.read(), ptype)
elif binfile is not None:
try:
from xmlrpc.client import Binary
Expand Down Expand Up @@ -504,7 +504,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 convert_value(c_value.strip(), ptype)
return convert_value(c_value, ptype)
else: #_param_tag prevalidates, so this should not be reachable
raise ValueError("unable to determine parameter value")

0 comments on commit b746f71

Please sign in to comment.