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