10 PKG =
'rosbridge_library' 11 NAME =
'test_ros_loader' 20 bad = [
"",
"/",
"//",
"///",
"////",
"/////",
"bad",
"stillbad",
21 "not/better/still",
"not//better//still",
"not///better///still",
22 "better/",
"better//",
"better///",
"/better",
"//better",
"///better",
25 self.assertRaises(ros_loader.InvalidTypeStringException,
26 ros_loader.get_message_class, x)
27 self.assertRaises(ros_loader.InvalidTypeStringException,
28 ros_loader.get_message_instance, x)
31 irregular = [
"std_msgs//String",
"//std_msgs/String",
32 "/std_msgs//String",
"/std_msgs/String",
"//std_msgs//String",
33 "/std_msgs/String/",
"//std_msgs//String//",
"std_msgs/String/",
36 self.assertNotEqual(ros_loader.get_message_class(x),
None)
37 self.assertNotEqual(ros_loader.get_message_instance(x),
None)
40 stdmsgs = [
"std_msgs/Bool",
"std_msgs/Byte",
"std_msgs/ByteMultiArray",
41 "std_msgs/ColorRGBA",
"std_msgs/Duration",
"std_msgs/Empty",
42 "std_msgs/Float32",
"std_msgs/Float32MultiArray",
"std_msgs/Float64",
43 "std_msgs/Header",
"std_msgs/Int16",
"std_msgs/Int16MultiArray",
44 "std_msgs/Int32",
"std_msgs/Int32MultiArray",
"std_msgs/Int64",
45 "std_msgs/Int64MultiArray",
"std_msgs/Int8",
"std_msgs/Int8MultiArray",
46 "std_msgs/MultiArrayDimension",
"std_msgs/MultiArrayLayout",
47 "std_msgs/String",
"std_msgs/Time",
"std_msgs/UInt16",
48 "std_msgs/UInt16MultiArray",
"std_msgs/UInt32MultiArray",
49 "std_msgs/UInt64MultiArray",
"std_msgs/UInt32",
"std_msgs/UInt64",
50 "std_msgs/UInt8",
"std_msgs/UInt8MultiArray"]
52 self.assertNotEqual(ros_loader.get_message_class(x),
None)
53 inst = ros_loader.get_message_instance(x)
54 self.assertNotEqual(inst,
None)
55 self.assertEqual(x, inst._type)
58 stdmsgs = [
"std_msgs/Bool",
"std_msgs/Byte",
"std_msgs/ByteMultiArray",
59 "std_msgs/ColorRGBA",
"std_msgs/Duration",
"std_msgs/Empty",
60 "std_msgs/Float32",
"std_msgs/Float32MultiArray",
"std_msgs/Float64",
61 "std_msgs/Header",
"std_msgs/Int16",
"std_msgs/Int16MultiArray",
62 "std_msgs/Int32",
"std_msgs/Int32MultiArray",
"std_msgs/Int64",
63 "std_msgs/Int64MultiArray",
"std_msgs/Int8",
"std_msgs/Int8MultiArray",
64 "std_msgs/MultiArrayDimension",
"std_msgs/MultiArrayLayout",
65 "std_msgs/String",
"std_msgs/Time",
"std_msgs/UInt16",
66 "std_msgs/UInt16MultiArray",
"std_msgs/UInt32MultiArray",
67 "std_msgs/UInt64MultiArray",
"std_msgs/UInt32",
"std_msgs/UInt64",
68 "std_msgs/UInt8",
"std_msgs/UInt8MultiArray"]
70 self.assertNotEqual(ros_loader.get_message_class(x),
None)
71 inst = ros_loader.get_message_instance(x)
72 self.assertNotEqual(inst,
None)
73 self.assertEqual(x, inst._type)
74 self.assertTrue(x
in ros_loader._loaded_msgs)
77 assortedmsgs = [
"geometry_msgs/Pose",
"actionlib_msgs/GoalStatus",
78 "geometry_msgs/WrenchStamped",
"stereo_msgs/DisparityImage",
79 "nav_msgs/OccupancyGrid",
"geometry_msgs/Point32",
"std_msgs/String",
80 "trajectory_msgs/JointTrajectoryPoint",
"diagnostic_msgs/KeyValue",
81 "visualization_msgs/InteractiveMarkerUpdate",
"nav_msgs/GridCells",
82 "sensor_msgs/PointCloud2"]
83 for x
in assortedmsgs:
84 self.assertNotEqual(ros_loader.get_message_class(x),
None)
85 inst = ros_loader.get_message_instance(x)
86 self.assertNotEqual(inst,
None)
87 self.assertEqual(x, inst._type)
90 invalid = [
"bool",
"int8",
"uint8",
"int16",
"uint16",
"int32",
91 "uint32",
"int64",
"uint64",
"float32",
"float64",
"string",
"time",
94 self.assertRaises(ros_loader.InvalidTypeStringException,
95 ros_loader.get_message_class, x)
96 self.assertRaises(ros_loader.InvalidTypeStringException,
97 ros_loader.get_message_instance, x)
100 nonexistent = [
"wangle_msgs/Jam",
"whistleblower_msgs/Document",
101 "sexual_harrassment_msgs/UnwantedAdvance",
"coercion_msgs/Bribe",
102 "airconditioning_msgs/Cold",
"pr2thoughts_msgs/Escape"]
103 for x
in nonexistent:
104 self.assertRaises(ros_loader.InvalidPackageException,
105 ros_loader.get_message_class, x)
106 self.assertRaises(ros_loader.InvalidPackageException,
107 ros_loader.get_message_instance, x)
110 no_msgs = [
"roslib/Time",
"roslib/Duration",
"roslib/Header",
111 "std_srvs/ConflictedMsg",
"topic_tools/MessageMessage"]
113 self.assertRaises(ros_loader.InvalidModuleException,
114 ros_loader.get_message_class, x)
115 self.assertRaises(ros_loader.InvalidModuleException,
116 ros_loader.get_message_instance, x)
119 nonexistent = [
"roscpp/Time",
"roscpp/Duration",
"roscpp/Header",
120 "rospy/Time",
"rospy/Duration",
"rospy/Header",
"std_msgs/Spool",
121 "geometry_msgs/Tetrahedron",
"sensor_msgs/TelepathyUnit"]
122 for x
in nonexistent:
123 self.assertRaises(ros_loader.InvalidClassException,
124 ros_loader.get_message_class, x)
125 self.assertRaises(ros_loader.InvalidClassException,
126 ros_loader.get_message_instance, x)
129 bad = [
"",
"/",
"//",
"///",
"////",
"/////",
"bad",
"stillbad",
130 "not/better/still",
"not//better//still",
"not///better///still",
131 "better/",
"better//",
"better///",
"/better",
"//better",
"///better",
134 self.assertRaises(ros_loader.InvalidTypeStringException,
135 ros_loader.get_service_class, x)
136 self.assertRaises(ros_loader.InvalidTypeStringException,
137 ros_loader.get_service_instance, x)
138 self.assertRaises(ros_loader.InvalidTypeStringException,
139 ros_loader.get_service_request_instance, x)
140 self.assertRaises(ros_loader.InvalidTypeStringException,
141 ros_loader.get_service_response_instance, x)
144 irregular = [
"roscpp//GetLoggers",
"/roscpp/GetLoggers/",
145 "/roscpp/GetLoggers",
"//roscpp/GetLoggers",
"/roscpp//GetLoggers",
146 "roscpp/GetLoggers//",
"/roscpp/GetLoggers//",
"roscpp/GetLoggers/",
147 "roscpp//GetLoggers//"]
149 self.assertNotEqual(ros_loader.get_service_class(x),
None)
150 self.assertNotEqual(ros_loader.get_service_instance(x),
None)
151 self.assertNotEqual(ros_loader.get_service_request_instance(x),
None)
152 self.assertNotEqual(ros_loader.get_service_response_instance(x),
None)
155 common = [
"roscpp/GetLoggers",
"roscpp/SetLoggerLevel",
156 "std_srvs/Empty",
"nav_msgs/GetMap",
"nav_msgs/GetPlan",
157 "sensor_msgs/SetCameraInfo",
"topic_tools/MuxAdd",
158 "topic_tools/MuxSelect",
"tf2_msgs/FrameGraph",
159 "rospy_tutorials/BadTwoInts",
"rospy_tutorials/AddTwoInts"]
161 self.assertNotEqual(ros_loader.get_service_class(x),
None)
162 self.assertNotEqual(ros_loader.get_service_instance(x),
None)
163 self.assertNotEqual(ros_loader.get_service_request_instance(x),
None)
164 self.assertNotEqual(ros_loader.get_service_response_instance(x),
None)
165 self.assertEqual(x, ros_loader.get_service_instance(x)._type)
168 common = [
"roscpp/GetLoggers",
"roscpp/SetLoggerLevel",
169 "std_srvs/Empty",
"nav_msgs/GetMap",
"nav_msgs/GetPlan",
170 "sensor_msgs/SetCameraInfo",
"topic_tools/MuxAdd",
171 "topic_tools/MuxSelect",
"tf2_msgs/FrameGraph",
172 "rospy_tutorials/BadTwoInts",
"rospy_tutorials/AddTwoInts"]
174 self.assertNotEqual(ros_loader.get_service_class(x),
None)
175 self.assertNotEqual(ros_loader.get_service_instance(x),
None)
176 self.assertNotEqual(ros_loader.get_service_request_instance(x),
None)
177 self.assertNotEqual(ros_loader.get_service_response_instance(x),
None)
178 self.assertTrue(x
in ros_loader._loaded_srvs)
181 no_msgs = [
"roslib/A",
"roslib/B",
"roslib/C",
182 "std_msgs/CuriousSrv"]
184 self.assertRaises(ros_loader.InvalidModuleException,
185 ros_loader.get_service_class, x)
186 self.assertRaises(ros_loader.InvalidModuleException,
187 ros_loader.get_service_instance, x)
188 self.assertRaises(ros_loader.InvalidModuleException,
189 ros_loader.get_service_request_instance, x)
190 self.assertRaises(ros_loader.InvalidModuleException,
191 ros_loader.get_service_response_instance, x)
194 nonexistent = [
"butler_srvs/FetchDrink",
"money_srvs/MoreMoney",
195 "snoopdogg_srvs/SipOnGinAndJuice",
"revenge_srvs/BackStab"]
196 for x
in nonexistent:
197 self.assertRaises(ros_loader.InvalidPackageException,
198 ros_loader.get_service_class, x)
199 self.assertRaises(ros_loader.InvalidPackageException,
200 ros_loader.get_service_instance, x)
201 self.assertRaises(ros_loader.InvalidPackageException,
202 ros_loader.get_service_request_instance, x)
203 self.assertRaises(ros_loader.InvalidPackageException,
204 ros_loader.get_service_response_instance, x)
207 nonexistent = [
"std_srvs/KillAllHumans",
"std_srvs/Full",
208 "rospy_tutorials/SubtractTwoInts",
"nav_msgs/LoseMap",
209 "topic_tools/TellMeWhatThisTopicIsActuallyAbout"]
210 for x
in nonexistent:
211 self.assertRaises(ros_loader.InvalidClassException,
212 ros_loader.get_service_class, x)
213 self.assertRaises(ros_loader.InvalidClassException,
214 ros_loader.get_service_instance, x)
215 self.assertRaises(ros_loader.InvalidClassException,
216 ros_loader.get_service_request_instance, x)
217 self.assertRaises(ros_loader.InvalidClassException,
218 ros_loader.get_service_response_instance, x)
221 if __name__ ==
'__main__':
222 rosunit.unitrun(PKG, NAME, TestROSLoader)
def test_nonexistent_packagenames(self)
def test_std_msgnames(self)
def test_packages_without_msgs(self)
def test_invalid_msgnames_primitives(self)
def test_packages_without_srvs(self)
def test_nonexistent_service_classnames(self)
def test_bad_servicenames(self)
def test_nonexistent_service_packagenames(self)
def test_nonexistent_msg_classnames(self)
def test_bad_msgnames(self)
def test_common_servicenames(self)
def test_irregular_servicenames(self)
def test_irregular_msgnames(self)
def test_assorted_msgnames(self)