00001
00002 PKG = 'rosbridge_library'
00003 import roslib; roslib.load_manifest(PKG)
00004 import rospy
00005
00006 from rosbridge_library.internal import ros_loader
00007
00008 import unittest
00009
00010
00011 class TestROSLoader(unittest.TestCase):
00012
00013 def setUp(self):
00014 rospy.init_node("test_ros_loader")
00015
00016 def test_bad_msgnames(self):
00017 bad = ["", "/", "//", "///", "////", "/////", "bad", "stillbad",
00018 "not/better/still", "not//better//still", "not///better///still",
00019 "better/", "better//", "better///", "/better", "//better", "///better",
00020 "this\isbad", "\\"]
00021 for x in bad:
00022 self.assertRaises(ros_loader.InvalidTypeStringException,
00023 ros_loader.get_message_class, x)
00024 self.assertRaises(ros_loader.InvalidTypeStringException,
00025 ros_loader.get_message_instance, x)
00026
00027 def test_irregular_msgnames(self):
00028 irregular = ["std_msgs//String", "//std_msgs/String",
00029 "/std_msgs//String", "/std_msgs/String", "//std_msgs//String",
00030 "/std_msgs/String/", "//std_msgs//String//", "std_msgs/String/",
00031 "std_msgs//String//"]
00032 for x in irregular:
00033 self.assertNotEqual(ros_loader.get_message_class(x), None)
00034 self.assertNotEqual(ros_loader.get_message_instance(x), None)
00035
00036 def test_std_msgnames(self):
00037 stdmsgs = ["std_msgs/Bool", "std_msgs/Byte", "std_msgs/ByteMultiArray",
00038 "std_msgs/ColorRGBA", "std_msgs/Duration", "std_msgs/Empty",
00039 "std_msgs/Float32", "std_msgs/Float32MultiArray", "std_msgs/Float64",
00040 "std_msgs/Header", "std_msgs/Int16", "std_msgs/Int16MultiArray",
00041 "std_msgs/Int32", "std_msgs/Int32MultiArray", "std_msgs/Int64",
00042 "std_msgs/Int64MultiArray", "std_msgs/Int8", "std_msgs/Int8MultiArray",
00043 "std_msgs/MultiArrayDimension", "std_msgs/MultiArrayLayout",
00044 "std_msgs/String", "std_msgs/Time", "std_msgs/UInt16",
00045 "std_msgs/UInt16MultiArray", "std_msgs/UInt32MultiArray",
00046 "std_msgs/UInt64MultiArray", "std_msgs/UInt32", "std_msgs/UInt64",
00047 "std_msgs/UInt8", "std_msgs/UInt8MultiArray"]
00048 for x in stdmsgs:
00049 self.assertNotEqual(ros_loader.get_message_class(x), None)
00050 inst = ros_loader.get_message_instance(x)
00051 self.assertNotEqual(inst, None)
00052 self.assertEqual(x, inst._type)
00053
00054 def test_msg_cache(self):
00055 stdmsgs = ["std_msgs/Bool", "std_msgs/Byte", "std_msgs/ByteMultiArray",
00056 "std_msgs/ColorRGBA", "std_msgs/Duration", "std_msgs/Empty",
00057 "std_msgs/Float32", "std_msgs/Float32MultiArray", "std_msgs/Float64",
00058 "std_msgs/Header", "std_msgs/Int16", "std_msgs/Int16MultiArray",
00059 "std_msgs/Int32", "std_msgs/Int32MultiArray", "std_msgs/Int64",
00060 "std_msgs/Int64MultiArray", "std_msgs/Int8", "std_msgs/Int8MultiArray",
00061 "std_msgs/MultiArrayDimension", "std_msgs/MultiArrayLayout",
00062 "std_msgs/String", "std_msgs/Time", "std_msgs/UInt16",
00063 "std_msgs/UInt16MultiArray", "std_msgs/UInt32MultiArray",
00064 "std_msgs/UInt64MultiArray", "std_msgs/UInt32", "std_msgs/UInt64",
00065 "std_msgs/UInt8", "std_msgs/UInt8MultiArray"]
00066 for x in stdmsgs:
00067 self.assertNotEqual(ros_loader.get_message_class(x), None)
00068 inst = ros_loader.get_message_instance(x)
00069 self.assertNotEqual(inst, None)
00070 self.assertEqual(x, inst._type)
00071 self.assertTrue(x in ros_loader._loaded_msgs)
00072
00073 def test_assorted_msgnames(self):
00074 assortedmsgs = ["geometry_msgs/Pose", "actionlib_msgs/GoalStatus",
00075 "geometry_msgs/WrenchStamped", "stereo_msgs/DisparityImage",
00076 "nav_msgs/OccupancyGrid", "geometry_msgs/Point32", "std_msgs/String",
00077 "trajectory_msgs/JointTrajectoryPoint", "diagnostic_msgs/KeyValue",
00078 "visualization_msgs/InteractiveMarkerUpdate", "nav_msgs/GridCells",
00079 "sensor_msgs/PointCloud2"]
00080 for x in assortedmsgs:
00081 self.assertNotEqual(ros_loader.get_message_class(x), None)
00082 inst = ros_loader.get_message_instance(x)
00083 self.assertNotEqual(inst, None)
00084 self.assertEqual(x, inst._type)
00085
00086 def test_invalid_msgnames_primitives(self):
00087 invalid = ["bool", "int8", "uint8", "int16", "uint16", "int32",
00088 "uint32", "int64", "uint64", "float32", "float64", "string", "time",
00089 "duration"]
00090 for x in invalid:
00091 self.assertRaises(ros_loader.InvalidTypeStringException,
00092 ros_loader.get_message_class, x)
00093 self.assertRaises(ros_loader.InvalidTypeStringException,
00094 ros_loader.get_message_instance, x)
00095
00096 def test_nonexistent_packagenames(self):
00097 nonexistent = ["wangle_msgs/Jam", "whistleblower_msgs/Document",
00098 "sexual_harrassment_msgs/UnwantedAdvance", "coercion_msgs/Bribe",
00099 "airconditioning_msgs/Cold", "pr2thoughts_msgs/Escape"]
00100 for x in nonexistent:
00101 self.assertRaises(ros_loader.InvalidPackageException,
00102 ros_loader.get_message_class, x)
00103 self.assertRaises(ros_loader.InvalidPackageException,
00104 ros_loader.get_message_instance, x)
00105
00106 def test_packages_without_msgs(self):
00107 no_msgs = ["roslib/Time", "roslib/Duration", "roslib/Header",
00108 "std_srvs/ConflictedMsg", "topic_tools/MessageMessage"]
00109 for x in no_msgs:
00110 self.assertRaises(ros_loader.InvalidModuleException,
00111 ros_loader.get_message_class, x)
00112 self.assertRaises(ros_loader.InvalidModuleException,
00113 ros_loader.get_message_instance, x)
00114
00115 def test_nonexistent_msg_classnames(self):
00116 nonexistent = ["roscpp/Time", "roscpp/Duration", "roscpp/Header",
00117 "rospy/Time", "rospy/Duration", "rospy/Header", "std_msgs/Spool",
00118 "geometry_msgs/Tetrahedron", "sensor_msgs/TelepathyUnit"]
00119 for x in nonexistent:
00120 self.assertRaises(ros_loader.InvalidClassException,
00121 ros_loader.get_message_class, x)
00122 self.assertRaises(ros_loader.InvalidClassException,
00123 ros_loader.get_message_instance, x)
00124
00125 def test_bad_servicenames(self):
00126 bad = ["", "/", "//", "///", "////", "/////", "bad", "stillbad",
00127 "not/better/still", "not//better//still", "not///better///still",
00128 "better/", "better//", "better///", "/better", "//better", "///better",
00129 "this\isbad", "\\"]
00130 for x in bad:
00131 self.assertRaises(ros_loader.InvalidTypeStringException,
00132 ros_loader.get_service_class, x)
00133 self.assertRaises(ros_loader.InvalidTypeStringException,
00134 ros_loader.get_service_instance, x)
00135 self.assertRaises(ros_loader.InvalidTypeStringException,
00136 ros_loader.get_service_request_instance, x)
00137 self.assertRaises(ros_loader.InvalidTypeStringException,
00138 ros_loader.get_service_response_instance, x)
00139
00140 def test_irregular_servicenames(self):
00141 irregular = ["roscpp//GetLoggers", "/roscpp/GetLoggers/",
00142 "/roscpp/GetLoggers", "//roscpp/GetLoggers", "/roscpp//GetLoggers",
00143 "roscpp/GetLoggers//", "/roscpp/GetLoggers//", "roscpp/GetLoggers/",
00144 "roscpp//GetLoggers//"]
00145 for x in irregular:
00146 self.assertNotEqual(ros_loader.get_service_class(x), None)
00147 self.assertNotEqual(ros_loader.get_service_instance(x), None)
00148 self.assertNotEqual(ros_loader.get_service_request_instance(x), None)
00149 self.assertNotEqual(ros_loader.get_service_response_instance(x), None)
00150
00151 def test_common_servicenames(self):
00152 common = ["roscpp/GetLoggers", "roscpp/SetLoggerLevel",
00153 "std_srvs/Empty", "nav_msgs/GetMap", "nav_msgs/GetPlan",
00154 "sensor_msgs/SetCameraInfo", "topic_tools/MuxAdd",
00155 "topic_tools/MuxSelect", "tf2_msgs/FrameGraph",
00156 "rospy_tutorials/BadTwoInts", "rospy_tutorials/AddTwoInts"]
00157 for x in common:
00158 self.assertNotEqual(ros_loader.get_service_class(x), None)
00159 self.assertNotEqual(ros_loader.get_service_instance(x), None)
00160 self.assertNotEqual(ros_loader.get_service_request_instance(x), None)
00161 self.assertNotEqual(ros_loader.get_service_response_instance(x), None)
00162 self.assertEqual(x, ros_loader.get_service_instance(x)._type)
00163
00164 def test_srv_cache(self):
00165 common = ["roscpp/GetLoggers", "roscpp/SetLoggerLevel",
00166 "std_srvs/Empty", "nav_msgs/GetMap", "nav_msgs/GetPlan",
00167 "sensor_msgs/SetCameraInfo", "topic_tools/MuxAdd",
00168 "topic_tools/MuxSelect", "tf2_msgs/FrameGraph",
00169 "rospy_tutorials/BadTwoInts", "rospy_tutorials/AddTwoInts"]
00170 for x in common:
00171 self.assertNotEqual(ros_loader.get_service_class(x), None)
00172 self.assertNotEqual(ros_loader.get_service_instance(x), None)
00173 self.assertNotEqual(ros_loader.get_service_request_instance(x), None)
00174 self.assertNotEqual(ros_loader.get_service_response_instance(x), None)
00175 self.assertTrue(x in ros_loader._loaded_srvs)
00176
00177 def test_packages_without_srvs(self):
00178 no_msgs = ["roslib/A", "roslib/B", "roslib/C",
00179 "std_msgs/CuriousSrv"]
00180 for x in no_msgs:
00181 self.assertRaises(ros_loader.InvalidModuleException,
00182 ros_loader.get_service_class, x)
00183 self.assertRaises(ros_loader.InvalidModuleException,
00184 ros_loader.get_service_instance, x)
00185 self.assertRaises(ros_loader.InvalidModuleException,
00186 ros_loader.get_service_request_instance, x)
00187 self.assertRaises(ros_loader.InvalidModuleException,
00188 ros_loader.get_service_response_instance, x)
00189
00190 def test_nonexistent_service_packagenames(self):
00191 nonexistent = ["butler_srvs/FetchDrink", "money_srvs/MoreMoney",
00192 "snoopdogg_srvs/SipOnGinAndJuice", "revenge_srvs/BackStab"]
00193 for x in nonexistent:
00194 self.assertRaises(ros_loader.InvalidPackageException,
00195 ros_loader.get_service_class, x)
00196 self.assertRaises(ros_loader.InvalidPackageException,
00197 ros_loader.get_service_instance, x)
00198 self.assertRaises(ros_loader.InvalidPackageException,
00199 ros_loader.get_service_request_instance, x)
00200 self.assertRaises(ros_loader.InvalidPackageException,
00201 ros_loader.get_service_response_instance, x)
00202
00203 def test_nonexistent_service_classnames(self):
00204 nonexistent = ["std_srvs/KillAllHumans", "std_srvs/Full",
00205 "rospy_tutorials/SubtractTwoInts", "nav_msgs/LoseMap",
00206 "topic_tools/TellMeWhatThisTopicIsActuallyAbout"]
00207 for x in nonexistent:
00208 self.assertRaises(ros_loader.InvalidClassException,
00209 ros_loader.get_service_class, x)
00210 self.assertRaises(ros_loader.InvalidClassException,
00211 ros_loader.get_service_instance, x)
00212 self.assertRaises(ros_loader.InvalidClassException,
00213 ros_loader.get_service_request_instance, x)
00214 self.assertRaises(ros_loader.InvalidClassException,
00215 ros_loader.get_service_response_instance, x)
00216
00217
00218 if __name__ == '__main__':
00219 import rostest
00220 rostest.rosrun(PKG, 'test_ros_loader', TestROSLoader)