From 29053c4832229efa7160fb944c05e3bc82e11540 Mon Sep 17 00:00:00 2001 From: Martijn Buijs Date: Tue, 23 Apr 2019 18:20:12 +0200 Subject: [PATCH] Switch to yaml.safe_load(_all) to prevent YAMLLoadWarning (#1688) * Switch to yaml.safe_load(_all) to prevent YAMLLoadWarning * Change all usages of yaml.load to yaml.safe_load * Extend PyYAML's SafeLoader and use it with `yaml.load` Also added convenience functions for using this loader for reuse in `roslaunch` * fix typo in rosparam.yaml_load_all * Modify Loader and SafeLoader in yaml module directly * Revert whitespace change * Revert unrelated change to import through global variable construction --- clients/rospy/src/rospy/client.py | 2 +- .../test/test_roslib_message.py | 2 +- .../client_verification/test_slave_api.py | 2 +- test/test_rosparam/test/check_rosparam.py | 8 ++--- .../check_rosparam_command_line_online.py | 2 +- .../check_rosservice_command_line_online.py | 4 +-- test/test_rostopic/test/test_rostopic_unit.py | 30 +++++++++---------- tools/rosbag/src/rosbag/bag.py | 2 +- tools/rosgraph/src/rosgraph/roslogging.py | 2 +- tools/roslaunch/src/roslaunch/loader.py | 4 +-- .../test/unit/test_roslaunch_dump_params.py | 4 +-- tools/rosparam/src/rosparam/__init__.py | 7 ++++- tools/rosservice/src/rosservice/__init__.py | 4 +-- tools/rostopic/src/rostopic/__init__.py | 6 ++-- tools/topic_tools/scripts/relay_field | 2 +- 15 files changed, 43 insertions(+), 38 deletions(-) diff --git a/clients/rospy/src/rospy/client.py b/clients/rospy/src/rospy/client.py index d543c53ac4..c72d6d6f05 100644 --- a/clients/rospy/src/rospy/client.py +++ b/clients/rospy/src/rospy/client.py @@ -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))) diff --git a/test/test_roslib_comm/test/test_roslib_message.py b/test/test_roslib_comm/test/test_roslib_message.py index 3d4e7a6fa7..288cc375bf 100644 --- a/test/test_roslib_comm/test/test_roslib_message.py +++ b/test/test_roslib_comm/test/test_roslib_message.py @@ -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: diff --git a/test/test_rosmaster/test/client_verification/test_slave_api.py b/test/test_rosmaster/test/client_verification/test_slave_api.py index 63d919c728..8614c045d6 100755 --- a/test/test_rosmaster/test/client_verification/test_slave_api.py +++ b/test/test_rosmaster/test/client_verification/test_slave_api.py @@ -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', {}) diff --git a/test/test_rosparam/test/check_rosparam.py b/test/test_rosparam/test/check_rosparam.py index 52ed976b5e..fe8c03fb4f 100755 --- a/test/test_rosparam/test/check_rosparam.py +++ b/test/test_rosparam/test/check_rosparam.py @@ -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") @@ -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 diff --git a/test/test_rosparam/test/check_rosparam_command_line_online.py b/test/test_rosparam/test/check_rosparam_command_line_online.py index d3d1051235..98a2724460 100755 --- a/test/test_rosparam/test/check_rosparam_command_line_online.py +++ b/test/test_rosparam/test/check_rosparam_command_line_online.py @@ -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") diff --git a/test/test_rosservice/test/check_rosservice_command_line_online.py b/test/test_rosservice/test/check_rosservice_command_line_online.py index dc696adbaa..c75a52c15a 100755 --- a/test/test_rosservice/test/check_rosservice_command_line_online.py +++ b/test/test_rosservice/test/check_rosservice_command_line_online.py @@ -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']) @@ -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)) diff --git a/test/test_rostopic/test/test_rostopic_unit.py b/test/test_rostopic/test/test_rostopic_unit.py index 1fcb6bc274..fbc62e41d6 100644 --- a/test/test_rostopic/test/test_rostopic_unit.py +++ b/test/test_rostopic/test/test_rostopic_unit.py @@ -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) @@ -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) @@ -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) @@ -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): diff --git a/tools/rosbag/src/rosbag/bag.py b/tools/rosbag/src/rosbag/bag.py index 0578aed91f..9bdcb693df 100644 --- a/tools/rosbag/src/rosbag/bag.py +++ b/tools/rosbag/src/rosbag/bag.py @@ -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: diff --git a/tools/rosgraph/src/rosgraph/roslogging.py b/tools/rosgraph/src/rosgraph/roslogging.py index ffe975dabb..bbf1d9f49c 100644 --- a/tools/rosgraph/src/rosgraph/roslogging.py +++ b/tools/rosgraph/src/rosgraph/roslogging.py @@ -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: diff --git a/tools/roslaunch/src/roslaunch/loader.py b/tools/roslaunch/src/roslaunch/loader.py index a7671c64d9..421bd060cd 100644 --- a/tools/roslaunch/src/roslaunch/loader.py +++ b/tools/roslaunch/src/roslaunch/loader.py @@ -99,7 +99,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: @@ -410,7 +410,7 @@ def load_rosparam(self, context, ros_config, cmd, param, file_, text, verbose=Tr if rosparam is None: import rosparam try: - data = yaml.load(text) + data = yaml.safe_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. diff --git a/tools/roslaunch/test/unit/test_roslaunch_dump_params.py b/tools/roslaunch/test/unit/test_roslaunch_dump_params.py index 20024a6013..2e5d90c082 100644 --- a/tools/roslaunch/test/unit/test_roslaunch_dump_params.py +++ b/tools/roslaunch/test/unit/test_roslaunch_dump_params.py @@ -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() @@ -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: diff --git a/tools/rosparam/src/rosparam/__init__.py b/tools/rosparam/src/rosparam/__init__.py index 41b806711a..3279ab97d5 100644 --- a/tools/rosparam/src/rosparam/__init__.py +++ b/tools/rosparam/src/rosparam/__init__.py @@ -99,6 +99,7 @@ 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) +yaml.SafeLoader.add_constructor(u'tag:yaml.org,2002:binary', construct_yaml_binary) def construct_angle_radians(loader, node): """ @@ -185,7 +186,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.safe_load_all(str): if NS in doc: ns = ns_join(default_namespace, doc.get(NS, None)) if verbose: @@ -633,10 +634,14 @@ def yamlmain(argv=None): yaml.add_constructor(u'!radians', construct_angle_radians) yaml.add_constructor(u'!degrees', construct_angle_degrees) +yaml.SafeLoader.add_constructor(u'!radians', construct_angle_radians) +yaml.SafeLoader.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(") +yaml.SafeLoader.add_implicit_resolver(u'!degrees', pattern, first="deg(") pattern = re.compile(r'^rad\([^\)]*\)$') yaml.add_implicit_resolver(u'!radians', pattern, first="rad(") +yaml.SafeLoader.add_implicit_resolver(u'!radians', pattern, first="rad(") diff --git a/tools/rosservice/src/rosservice/__init__.py b/tools/rosservice/src/rosservice/__init__.py index 6d58807a46..e6c41a73d7 100644 --- a/tools/rosservice/src/rosservice/__init__.py +++ b/tools/rosservice/src/rosservice/__init__.py @@ -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") @@ -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: diff --git a/tools/rostopic/src/rostopic/__init__.py b/tools/rostopic/src/rostopic/__init__.py index ad244b0f0f..41138562e1 100644 --- a/tools/rostopic/src/rostopic/__init__.py +++ b/tools/rostopic/src/rostopic/__init__.py @@ -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)) @@ -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: @@ -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: diff --git a/tools/topic_tools/scripts/relay_field b/tools/topic_tools/scripts/relay_field index 6630b685df..cc73ac4432 100755 --- a/tools/topic_tools/scripts/relay_field +++ b/tools/topic_tools/scripts/relay_field @@ -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()