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

Switch to yaml.safe_load(_all) to prevent YAMLLoadWarning #1688

Merged
merged 7 commits into from
Apr 23, 2019
Merged
Show file tree
Hide file tree
Changes from 4 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion clients/rospy/src/rospy/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ def load_command_line_node_params(argv):
src, dst = [x.strip() for x in arg.split(rosgraph.names.REMAP)]
if src and dst:
if len(src) > 1 and src[0] == '_' and src[1] != '_':
mappings[src[1:]] = yaml.load(dst)
mappings[src[1:]] = yaml.safe_load(dst)
return mappings
except Exception as e:
raise rospy.exceptions.ROSInitException("invalid command-line parameters: %s"%(str(e)))
Expand Down
2 changes: 1 addition & 1 deletion test/test_roslib_comm/test/test_roslib_message.py
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ def test_strify_message(self):
def roundtrip(m):
yaml_text = strify_message(m)
print(yaml_text)
loaded = yaml.load(yaml_text)
loaded = yaml.safe_load(yaml_text)
print("loaded", loaded)
new_inst = m.__class__()
if loaded is not None:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ def __init__(self, *args, **kwds):
def load_profile(self, filename):
import yaml
with open(filename) as f:
d = yaml.load(f)
d = yaml.safe_load(f)
self.required_pubs = d.get('pubs', {})
self.required_subs = d.get('subs', {})

Expand Down
8 changes: 4 additions & 4 deletions test/test_rosparam/test/check_rosparam.py
Original file line number Diff line number Diff line change
Expand Up @@ -227,7 +227,7 @@ def test_rosparam_get(self):
with fakestdout() as b:
rosparam.yamlmain([cmd, 'get', "g1"])
import yaml
d = yaml.load(b.getvalue())
d = yaml.safe_load(b.getvalue())
self.assertEquals(d['float'], 10.0)
self.assertEquals(d['int'], 10.0)
self.assertEquals(d['string'], "g1-foo-value")
Expand Down Expand Up @@ -346,18 +346,18 @@ def test_rosparam_dump(self):
import yaml
with open(f_out) as b:
with open(f) as b2:
self.assertEquals(yaml.load(b.read()), yaml.load(b2.read()))
self.assertEquals(yaml.safe_load(b.read()), yaml.safe_load(b2.read()))

rosparam.yamlmain([cmd, 'dump', '-v', f_out, 'rosparam_dump'])
with open(f_out) as b:
with open(f) as b2:
self.assertEquals(yaml.load(b.read()), yaml.load(b2.read()))
self.assertEquals(yaml.safe_load(b.read()), yaml.safe_load(b2.read()))

# yaml file and std_out should be the same
with fakestdout() as b:
rosparam.yamlmain([cmd, 'dump'])
with open(f) as b2:
self.assertEquals(yaml.load(b.getvalue())['rosparam_dump'], yaml.load(b2.read()))
self.assertEquals(yaml.safe_load(b.getvalue())['rosparam_dump'], yaml.safe_load(b2.read()))

def test_fullusage(self):
import rosparam
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,7 @@ def test_rosparam(self):
# - dictionary
output = Popen([cmd, 'get', "g1"], stdout=PIPE).communicate()[0]
import yaml
d = yaml.load(output)
d = yaml.safe_load(output)
self.assertEquals(d['float'], 10.0)
self.assertEquals(d['int'], 10.0)
self.assertEquals(d['string'], "g1-foo-value")
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ def test_rosservice(self):
output = Popen([cmd, 'call', name, v], stdout=PIPE).communicate()[0]
output = output.strip()
self.assert_(output, output)
val = yaml.load(output)['header']
val = yaml.safe_load(output)['header']
self.assertEquals('', val['frame_id'])
self.assert_(val['seq'] >= 0)
self.assertEquals(0, val['stamp']['secs'])
Expand All @@ -131,7 +131,7 @@ def test_rosservice(self):
# test with auto headers
for v in ['{header: auto}', '{header: {stamp: now}}']:
output = Popen([cmd, 'call', name, v], stdout=PIPE).communicate()[0]
val = yaml.load(output.strip())['header']
val = yaml.safe_load(output.strip())['header']
self.assertEquals('', val['frame_id'])
self.assert_(val['seq'] >= 0)
self.assert_(val['stamp']['secs'] >= int(t))
Expand Down
30 changes: 15 additions & 15 deletions test/test_rostopic/test/test_rostopic_unit.py
Original file line number Diff line number Diff line change
Expand Up @@ -249,16 +249,16 @@ def test_strify_message(self):
m = String('foo')
self.assertEquals('data: "foo"', strify_message(m, field_filter=f))
m = TVals(Time(123, 456), Duration(78, 90))
v = yaml.load(strify_message(m, field_filter=f))
v = yaml.safe_load(strify_message(m, field_filter=f))
self.assertEquals({'t': {'secs': 123, 'nsecs': 456}, 'd': {'secs': 78, 'nsecs': 90}}, v)
m = simple_v
v = yaml.load(strify_message(m, field_filter=f))
v = yaml.safe_load(strify_message(m, field_filter=f))
self.assertEquals(simple_d, v)
m = arrays_v
v = yaml.load(strify_message(m, field_filter=f))
v = yaml.safe_load(strify_message(m, field_filter=f))
self.assertEquals(arrays_d, v)
m = embed_v
v = yaml.load(strify_message(m, field_filter=f))
v = yaml.safe_load(strify_message(m, field_filter=f))
self.assertEquals(embed_d, v)

f = create_field_filter(echo_nostr=True, echo_noarr=False)
Expand All @@ -267,16 +267,16 @@ def test_strify_message(self):
m = String('foo')
self.assertEquals('', strify_message(m, field_filter=f))
m = TVals(Time(123, 456), Duration(78, 90))
v = yaml.load(strify_message(m, field_filter=f))
v = yaml.safe_load(strify_message(m, field_filter=f))
self.assertEquals({'t': {'secs': 123, 'nsecs': 456}, 'd': {'secs': 78, 'nsecs': 90}}, v)
m = simple_v
v = yaml.load(strify_message(m, field_filter=f))
v = yaml.safe_load(strify_message(m, field_filter=f))
self.assertEquals(simple_nostr, v)
m = arrays_v
v = yaml.load(strify_message(m, field_filter=f))
v = yaml.safe_load(strify_message(m, field_filter=f))
self.assertEquals(arrays_nostr, v)
m = embed_v
v = yaml.load(strify_message(m, field_filter=f))
v = yaml.safe_load(strify_message(m, field_filter=f))
self.assertEquals({'simple': simple_nostr, 'arrays': arrays_nostr}, v)

f = create_field_filter(echo_nostr=False, echo_noarr=True)
Expand All @@ -285,16 +285,16 @@ def test_strify_message(self):
m = String('foo')
self.assertEquals('data: "foo"', strify_message(m, field_filter=f))
m = TVals(Time(123, 456), Duration(78, 90))
v = yaml.load(strify_message(m, field_filter=f))
v = yaml.safe_load(strify_message(m, field_filter=f))
self.assertEquals({'t': {'secs': 123, 'nsecs': 456}, 'd': {'secs': 78, 'nsecs': 90}}, v)
m = simple_v
v = yaml.load(strify_message(m, field_filter=f))
v = yaml.safe_load(strify_message(m, field_filter=f))
self.assertEquals(simple_d, v)
m = arrays_v
v = yaml.load(strify_message(m, field_filter=f))
v = yaml.safe_load(strify_message(m, field_filter=f))
self.assertEquals(None, v)
m = embed_v
v = yaml.load(strify_message(m, field_filter=f))
v = yaml.safe_load(strify_message(m, field_filter=f))
self.assertEquals({'simple': simple_d, 'arrays': None}, v)

f = create_field_filter(echo_nostr=True, echo_noarr=True)
Expand All @@ -303,13 +303,13 @@ def test_strify_message(self):
m = String('foo')
self.assertEquals('', strify_message(m, field_filter=f))
m = TVals(Time(123, 456), Duration(78, 90))
v = yaml.load(strify_message(m, field_filter=f))
v = yaml.safe_load(strify_message(m, field_filter=f))
self.assertEquals({'t': {'secs': 123, 'nsecs': 456}, 'd': {'secs': 78, 'nsecs': 90}}, v)
m = simple_v
v = yaml.load(strify_message(m, field_filter=f))
v = yaml.safe_load(strify_message(m, field_filter=f))
self.assertEquals(simple_nostr, v)
m = embed_v
v = yaml.load(strify_message(m, field_filter=f))
v = yaml.safe_load(strify_message(m, field_filter=f))
self.assertEquals({'simple': simple_nostr, 'arrays': None}, v)

def test_create_field_filter(self):
Expand Down
2 changes: 1 addition & 1 deletion tools/rosbag/src/rosbag/bag.py
Original file line number Diff line number Diff line change
Expand Up @@ -1250,7 +1250,7 @@ def __init__(self, d):
else:
setattr(self, a, DictObject(b) if isinstance(b, dict) else b)

obj = DictObject(yaml.load(s))
obj = DictObject(yaml.safe_load(s))
try:
val = eval('obj.' + key)
except Exception as ex:
Expand Down
2 changes: 1 addition & 1 deletion tools/rosgraph/src/rosgraph/roslogging.py
Original file line number Diff line number Diff line change
Expand Up @@ -178,7 +178,7 @@ def configure_logging(logname, level=logging.INFO, filename=None, env=None):
os.environ['ROS_LOG_FILENAME'] = log_filename
if config_file.endswith(('.yaml', '.yml')):
with open(config_file) as f:
dict_conf = yaml.load(f)
dict_conf = yaml.safe_load(f)
dict_conf.setdefault('version', 1)
logging.config.dictConfig(dict_conf)
else:
Expand Down
11 changes: 3 additions & 8 deletions tools/roslaunch/src/roslaunch/loader.py
Original file line number Diff line number Diff line change
Expand Up @@ -47,9 +47,6 @@

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
rosparam = None

class LoadException(RLException):
"""Error loading data as specified (e.g. cannot find included files, etc...)"""
pass
Expand Down Expand Up @@ -99,7 +96,7 @@ def convert_value(value, type_):
raise ValueError("%s is not a '%s' type"%(value, type_))
elif type_ == 'yaml':
try:
return yaml.load(value)
return yaml.safe_load(value)
except yaml.parser.ParserError as e:
raise ValueError(e)
else:
Expand Down Expand Up @@ -406,11 +403,9 @@ def load_rosparam(self, context, ros_config, cmd, param, file_, text, verbose=Tr
text = subst_function(text)
# parse YAML text
# - lazy import: we have to import rosparam in oder to to configure the YAML constructors
global rosparam
if rosparam is None:
import rosparam
import rosparam
dirk-thomas marked this conversation as resolved.
Show resolved Hide resolved
try:
data = yaml.load(text)
data = rosparam.yaml_load(text)
# #3162: if there is no YAML, load() will return an
# empty string. We want an empty dictionary instead
# for our representation of empty.
Expand Down
4 changes: 2 additions & 2 deletions tools/roslaunch/test/unit/test_roslaunch_dump_params.py
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ def test_roslaunch(self):
o, e = p.communicate()
self.assert_(p.returncode == 0, "Return code nonzero for param dump! Code: %d" % (p.returncode))

self.assertEquals({'/noop': 'noop'}, yaml.load(o))
self.assertEquals({'/noop': 'noop'}, yaml.safe_load(o))

p = Popen([cmd, '--dump-params', 'roslaunch', 'test-dump-rosparam.launch'], stdout = PIPE)
o, e = p.communicate()
Expand Down Expand Up @@ -95,7 +95,7 @@ def test_roslaunch(self):
'/noparam1': 'value1',
'/noparam2': 'value2',
}
output_val = yaml.load(o)
output_val = yaml.safe_load(o)
if not val == output_val:
for k, v in val.items():
if k not in output_val:
Expand Down
21 changes: 14 additions & 7 deletions tools/rosparam/src/rosparam/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,8 @@ def construct_yaml_binary(loader, node):

# register the (de)serializers with pyyaml
yaml.add_representer(Binary,represent_xml_binary)
yaml.add_constructor(u'tag:yaml.org,2002:binary', construct_yaml_binary)
ROSSafeLoader = yaml.loader.SafeLoader
ROSSafeLoader.add_constructor(u'tag:yaml.org,2002:binary', construct_yaml_binary)

def construct_angle_radians(loader, node):
"""
Expand Down Expand Up @@ -150,6 +151,12 @@ def print_params(params, ns):

# yaml processing

dirk-thomas marked this conversation as resolved.
Show resolved Hide resolved
def yaml_load(str):
return yaml.load(str, Loader=ROSSafeLoader)

def yaml_load_all(str):
return yaml.load_all(str, Loader=ROSSafeLoader)
mbuijs marked this conversation as resolved.
Show resolved Hide resolved

def load_file(filename, default_namespace=None, verbose=False):
"""
Load the YAML document from the specified file
Expand Down Expand Up @@ -185,7 +192,7 @@ def load_str(str, filename, default_namespace=None, verbose=False):
"""
paramlist = []
default_namespace = default_namespace or get_ros_namespace()
for doc in yaml.load_all(str):
for doc in yaml_load_all(str):
if NS in doc:
ns = ns_join(default_namespace, doc.get(NS, None))
if verbose:
Expand Down Expand Up @@ -367,7 +374,7 @@ def set_param(param, value, verbose=False):
:param param: parameter name, ``str``
:param value: yaml-encoded value, ``str``
"""
set_param_raw(param, yaml.load(value), verbose=verbose)
set_param_raw(param, yaml_load(value), verbose=verbose)

def upload_params(ns, values, verbose=False):
"""
Expand Down Expand Up @@ -631,12 +638,12 @@ def yamlmain(argv=None):

# YAML configuration. Doxygen does not like these being higher up in the code

yaml.add_constructor(u'!radians', construct_angle_radians)
yaml.add_constructor(u'!degrees', construct_angle_degrees)
ROSSafeLoader.add_constructor(u'!radians', construct_angle_radians)
ROSSafeLoader.add_constructor(u'!degrees', construct_angle_degrees)

# allow both !degrees 180, !radians 2*pi
pattern = re.compile(r'^deg\([^\)]*\)$')
yaml.add_implicit_resolver(u'!degrees', pattern, first="deg(")
ROSSafeLoader.add_implicit_resolver(u'!degrees', pattern, first="deg(")
pattern = re.compile(r'^rad\([^\)]*\)$')
yaml.add_implicit_resolver(u'!radians', pattern, first="rad(")
ROSSafeLoader.add_implicit_resolver(u'!radians', pattern, first="rad(")
dirk-thomas marked this conversation as resolved.
Show resolved Hide resolved

4 changes: 2 additions & 2 deletions tools/rosservice/src/rosservice/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -607,7 +607,7 @@ def _rosservice_cmd_call(argv):
# convert empty args to YAML-empty strings
if arg == '':
arg = "''"
service_args.append(yaml.load(arg))
service_args.append(yaml.safe_load(arg))
if not service_args and has_service_args(service_name, service_class=service_class):
if sys.stdin.isatty():
parser.error("Please specify service arguments")
Expand Down Expand Up @@ -650,7 +650,7 @@ def _stdin_yaml_arg():
elif arg.strip() != '---':
buff = buff + arg
try:
loaded = yaml.load(buff.rstrip())
loaded = yaml.safe_load(buff.rstrip())
except Exception as e:
print("Invalid YAML: %s"%str(e), file=sys.stderr)
if loaded is not None:
Expand Down
6 changes: 3 additions & 3 deletions tools/rostopic/src/rostopic/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -1779,7 +1779,7 @@ def _rostopic_cmd_pub(argv):
try:
pub_args = []
for arg in args[2:]:
pub_args.append(yaml.load(arg))
pub_args.append(yaml.safe_load(arg))
except Exception as e:
parser.error("Argument error: "+str(e))

Expand Down Expand Up @@ -1822,7 +1822,7 @@ def bagy_iter():
try:
with open(filename, 'r') as f:
# load all documents
data = yaml.load_all(f)
data = yaml.safe_load_all(f)
for d in data:
yield [d]
except yaml.YAMLError as e:
Expand Down Expand Up @@ -2014,7 +2014,7 @@ def stdin_yaml_arg():

if arg.strip() == '---': # End of document
try:
loaded = yaml.load(buff.rstrip())
loaded = yaml.safe_load(buff.rstrip())
except Exception as e:
sys.stderr.write("Invalid YAML: %s\n"%str(e))
if loaded is not None:
Expand Down
2 changes: 1 addition & 1 deletion tools/topic_tools/scripts/relay_field
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ class RelayField(object):
if self.input_fn is not None:
m = self.input_fn(m)

msg_generation = yaml.load(self.expression)
msg_generation = yaml.safe_load(self.expression)
pub_args = _eval_in_dict_impl(msg_generation, None, {'m': m})

now = rospy.get_rostime()
Expand Down