blob: e9e9aa8202a951bcf04a7f4a0a3e8691330b7a2f (
plain)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
|
From 29053c4832229efa7160fb944c05e3bc82e11540 Mon Sep 17 00:00:00 2001
From: Martijn Buijs <Martijn.buijs@gmail.com>
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 d543c53ac..c72d6d6f0 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)))
|