test_ros_loader.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import sys
3 import rospy
4 import rostest
5 import unittest
6 
7 from rosbridge_library.internal import ros_loader
8 
9 
10 class TestROSLoader(unittest.TestCase):
11 
12  def setUp(self):
13  rospy.init_node("test_ros_loader")
14 
15  def test_bad_msgnames(self):
16  bad = ["", "/", "//", "///", "////", "/////", "bad", "stillbad",
17  "not/better/still", "not//better//still", "not///better///still",
18  "better/", "better//", "better///", "/better", "//better", "///better",
19  "this\isbad", "\\"]
20  for x in bad:
21  self.assertRaises(ros_loader.InvalidTypeStringException,
22  ros_loader.get_message_class, x)
23  self.assertRaises(ros_loader.InvalidTypeStringException,
24  ros_loader.get_message_instance, x)
25 
27  irregular = ["std_msgs//String", "//std_msgs/String",
28  "/std_msgs//String", "/std_msgs/String", "//std_msgs//String",
29  "/std_msgs/String/", "//std_msgs//String//", "std_msgs/String/",
30  "std_msgs//String//"]
31  for x in irregular:
32  self.assertNotEqual(ros_loader.get_message_class(x), None)
33  self.assertNotEqual(ros_loader.get_message_instance(x), None)
34 
35  def test_std_msgnames(self):
36  stdmsgs = ["std_msgs/Bool", "std_msgs/Byte", "std_msgs/ByteMultiArray",
37  "std_msgs/ColorRGBA", "std_msgs/Duration", "std_msgs/Empty",
38  "std_msgs/Float32", "std_msgs/Float32MultiArray", "std_msgs/Float64",
39  "std_msgs/Header", "std_msgs/Int16", "std_msgs/Int16MultiArray",
40  "std_msgs/Int32", "std_msgs/Int32MultiArray", "std_msgs/Int64",
41  "std_msgs/Int64MultiArray", "std_msgs/Int8", "std_msgs/Int8MultiArray",
42  "std_msgs/MultiArrayDimension", "std_msgs/MultiArrayLayout",
43  "std_msgs/String", "std_msgs/Time", "std_msgs/UInt16",
44  "std_msgs/UInt16MultiArray", "std_msgs/UInt32MultiArray",
45  "std_msgs/UInt64MultiArray", "std_msgs/UInt32", "std_msgs/UInt64",
46  "std_msgs/UInt8", "std_msgs/UInt8MultiArray"]
47  for x in stdmsgs:
48  self.assertNotEqual(ros_loader.get_message_class(x), None)
49  inst = ros_loader.get_message_instance(x)
50  self.assertNotEqual(inst, None)
51  self.assertEqual(x, inst._type)
52 
53  def test_msg_cache(self):
54  stdmsgs = ["std_msgs/Bool", "std_msgs/Byte", "std_msgs/ByteMultiArray",
55  "std_msgs/ColorRGBA", "std_msgs/Duration", "std_msgs/Empty",
56  "std_msgs/Float32", "std_msgs/Float32MultiArray", "std_msgs/Float64",
57  "std_msgs/Header", "std_msgs/Int16", "std_msgs/Int16MultiArray",
58  "std_msgs/Int32", "std_msgs/Int32MultiArray", "std_msgs/Int64",
59  "std_msgs/Int64MultiArray", "std_msgs/Int8", "std_msgs/Int8MultiArray",
60  "std_msgs/MultiArrayDimension", "std_msgs/MultiArrayLayout",
61  "std_msgs/String", "std_msgs/Time", "std_msgs/UInt16",
62  "std_msgs/UInt16MultiArray", "std_msgs/UInt32MultiArray",
63  "std_msgs/UInt64MultiArray", "std_msgs/UInt32", "std_msgs/UInt64",
64  "std_msgs/UInt8", "std_msgs/UInt8MultiArray"]
65  for x in stdmsgs:
66  self.assertNotEqual(ros_loader.get_message_class(x), None)
67  inst = ros_loader.get_message_instance(x)
68  self.assertNotEqual(inst, None)
69  self.assertEqual(x, inst._type)
70  self.assertTrue(x in ros_loader._loaded_msgs)
71 
73  assortedmsgs = ["geometry_msgs/Pose", "actionlib_msgs/GoalStatus",
74  "geometry_msgs/WrenchStamped", "stereo_msgs/DisparityImage",
75  "nav_msgs/OccupancyGrid", "geometry_msgs/Point32", "std_msgs/String",
76  "trajectory_msgs/JointTrajectoryPoint", "diagnostic_msgs/KeyValue",
77  "visualization_msgs/InteractiveMarkerUpdate", "nav_msgs/GridCells",
78  "sensor_msgs/PointCloud2"]
79  for x in assortedmsgs:
80  self.assertNotEqual(ros_loader.get_message_class(x), None)
81  inst = ros_loader.get_message_instance(x)
82  self.assertNotEqual(inst, None)
83  self.assertEqual(x, inst._type)
84 
86  invalid = ["bool", "int8", "uint8", "int16", "uint16", "int32",
87  "uint32", "int64", "uint64", "float32", "float64", "string", "time",
88  "duration"]
89  for x in invalid:
90  self.assertRaises(ros_loader.InvalidTypeStringException,
91  ros_loader.get_message_class, x)
92  self.assertRaises(ros_loader.InvalidTypeStringException,
93  ros_loader.get_message_instance, x)
94 
96  nonexistent = ["wangle_msgs/Jam", "whistleblower_msgs/Document",
97  "sexual_harrassment_msgs/UnwantedAdvance", "coercion_msgs/Bribe",
98  "airconditioning_msgs/Cold", "pr2thoughts_msgs/Escape"]
99  for x in nonexistent:
100  self.assertRaises(ros_loader.InvalidPackageException,
101  ros_loader.get_message_class, x)
102  self.assertRaises(ros_loader.InvalidPackageException,
103  ros_loader.get_message_instance, x)
104 
106  no_msgs = ["roslib/Time", "roslib/Duration", "roslib/Header",
107  "std_srvs/ConflictedMsg", "topic_tools/MessageMessage"]
108  for x in no_msgs:
109  self.assertRaises(ros_loader.InvalidModuleException,
110  ros_loader.get_message_class, x)
111  self.assertRaises(ros_loader.InvalidModuleException,
112  ros_loader.get_message_instance, x)
113 
115  nonexistent = ["roscpp/Time", "roscpp/Duration", "roscpp/Header",
116  "rospy/Time", "rospy/Duration", "rospy/Header", "std_msgs/Spool",
117  "geometry_msgs/Tetrahedron", "sensor_msgs/TelepathyUnit"]
118  for x in nonexistent:
119  self.assertRaises(ros_loader.InvalidClassException,
120  ros_loader.get_message_class, x)
121  self.assertRaises(ros_loader.InvalidClassException,
122  ros_loader.get_message_instance, x)
123 
125  bad = ["", "/", "//", "///", "////", "/////", "bad", "stillbad",
126  "not/better/still", "not//better//still", "not///better///still",
127  "better/", "better//", "better///", "/better", "//better", "///better",
128  "this\isbad", "\\"]
129  for x in bad:
130  self.assertRaises(ros_loader.InvalidTypeStringException,
131  ros_loader.get_service_class, x)
132  self.assertRaises(ros_loader.InvalidTypeStringException,
133  ros_loader.get_service_instance, x)
134  self.assertRaises(ros_loader.InvalidTypeStringException,
135  ros_loader.get_service_request_instance, x)
136  self.assertRaises(ros_loader.InvalidTypeStringException,
137  ros_loader.get_service_response_instance, x)
138 
140  irregular = ["roscpp//GetLoggers", "/roscpp/GetLoggers/",
141  "/roscpp/GetLoggers", "//roscpp/GetLoggers", "/roscpp//GetLoggers",
142  "roscpp/GetLoggers//", "/roscpp/GetLoggers//", "roscpp/GetLoggers/",
143  "roscpp//GetLoggers//"]
144  for x in irregular:
145  self.assertNotEqual(ros_loader.get_service_class(x), None)
146  self.assertNotEqual(ros_loader.get_service_instance(x), None)
147  self.assertNotEqual(ros_loader.get_service_request_instance(x), None)
148  self.assertNotEqual(ros_loader.get_service_response_instance(x), None)
149 
151  common = ["roscpp/GetLoggers", "roscpp/SetLoggerLevel",
152  "std_srvs/Empty", "nav_msgs/GetMap", "nav_msgs/GetPlan",
153  "sensor_msgs/SetCameraInfo", "topic_tools/MuxAdd",
154  "topic_tools/MuxSelect", "tf2_msgs/FrameGraph",
155  "rospy_tutorials/BadTwoInts", "rospy_tutorials/AddTwoInts"]
156  for x in common:
157  self.assertNotEqual(ros_loader.get_service_class(x), None)
158  self.assertNotEqual(ros_loader.get_service_instance(x), None)
159  self.assertNotEqual(ros_loader.get_service_request_instance(x), None)
160  self.assertNotEqual(ros_loader.get_service_response_instance(x), None)
161  self.assertEqual(x, ros_loader.get_service_instance(x)._type)
162 
163  def test_srv_cache(self):
164  common = ["roscpp/GetLoggers", "roscpp/SetLoggerLevel",
165  "std_srvs/Empty", "nav_msgs/GetMap", "nav_msgs/GetPlan",
166  "sensor_msgs/SetCameraInfo", "topic_tools/MuxAdd",
167  "topic_tools/MuxSelect", "tf2_msgs/FrameGraph",
168  "rospy_tutorials/BadTwoInts", "rospy_tutorials/AddTwoInts"]
169  for x in common:
170  self.assertNotEqual(ros_loader.get_service_class(x), None)
171  self.assertNotEqual(ros_loader.get_service_instance(x), None)
172  self.assertNotEqual(ros_loader.get_service_request_instance(x), None)
173  self.assertNotEqual(ros_loader.get_service_response_instance(x), None)
174  self.assertTrue(x in ros_loader._loaded_srvs)
175 
177  no_msgs = ["roslib/A", "roslib/B", "roslib/C",
178  "std_msgs/CuriousSrv"]
179  for x in no_msgs:
180  self.assertRaises(ros_loader.InvalidModuleException,
181  ros_loader.get_service_class, x)
182  self.assertRaises(ros_loader.InvalidModuleException,
183  ros_loader.get_service_instance, x)
184  self.assertRaises(ros_loader.InvalidModuleException,
185  ros_loader.get_service_request_instance, x)
186  self.assertRaises(ros_loader.InvalidModuleException,
187  ros_loader.get_service_response_instance, x)
188 
190  nonexistent = ["butler_srvs/FetchDrink", "money_srvs/MoreMoney",
191  "snoopdogg_srvs/SipOnGinAndJuice", "revenge_srvs/BackStab"]
192  for x in nonexistent:
193  self.assertRaises(ros_loader.InvalidPackageException,
194  ros_loader.get_service_class, x)
195  self.assertRaises(ros_loader.InvalidPackageException,
196  ros_loader.get_service_instance, x)
197  self.assertRaises(ros_loader.InvalidPackageException,
198  ros_loader.get_service_request_instance, x)
199  self.assertRaises(ros_loader.InvalidPackageException,
200  ros_loader.get_service_response_instance, x)
201 
203  nonexistent = ["std_srvs/KillAllHumans", "std_srvs/Full",
204  "rospy_tutorials/SubtractTwoInts", "nav_msgs/LoseMap",
205  "topic_tools/TellMeWhatThisTopicIsActuallyAbout"]
206  for x in nonexistent:
207  self.assertRaises(ros_loader.InvalidClassException,
208  ros_loader.get_service_class, x)
209  self.assertRaises(ros_loader.InvalidClassException,
210  ros_loader.get_service_instance, x)
211  self.assertRaises(ros_loader.InvalidClassException,
212  ros_loader.get_service_request_instance, x)
213  self.assertRaises(ros_loader.InvalidClassException,
214  ros_loader.get_service_response_instance, x)
215 
216 PKG = 'rosbridge_library'
217 NAME = 'test_ros_loader'
218 if __name__ == '__main__':
219  rostest.unitrun(PKG, NAME, TestROSLoader)
220 


rosbridge_library
Author(s): Jonathan Mace
autogenerated on Fri May 10 2019 02:17:02