7 from time
import sleep, time
19 rospy.init_node(
"test_multi_unregistering")
22 """ Make sure that publishing works """ 23 topic =
"/test_publish_once" 24 msg_type =
"std_msgs/String" 25 msg = {
"data":
"why halo thar"}
27 received = {
"msg":
None}
31 rospy.Subscriber(topic, ros_loader.get_message_class(msg_type), cb)
37 self.assertEqual(received[
"msg"].data, msg[
"data"])
40 """ Make sure that publishing works """ 41 topic =
"/test_publish_twice" 42 msg_type =
"std_msgs/String" 43 msg = {
"data":
"why halo thar"}
45 received = {
"msg":
None}
49 rospy.Subscriber(topic, ros_loader.get_message_class(msg_type), cb)
55 self.assertEqual(received[
"msg"].data, msg[
"data"])
69 received[
"msg"] =
None 70 self.assertIsNone(received[
"msg"])
74 self.assertIsNone(received[
"msg"])
81 self.assertIsNone(received[
"msg"])
83 self.assertEqual(received[
"msg"].data, msg[
"data"])
86 PKG =
'rosbridge_library' 87 NAME =
'test_multi_unregistering' 88 if __name__ ==
'__main__':
89 rostest.unitrun(PKG, NAME, TestMultiUnregistering)
def test_publish_twice(self)
def test_publish_once(self)