diff --git a/rospy_tutorials/001_talker_listener/talker.py b/rospy_tutorials/001_talker_listener/talker.py index a2ca47b4..7da070d5 100755 --- a/rospy_tutorials/001_talker_listener/talker.py +++ b/rospy_tutorials/001_talker_listener/talker.py @@ -40,7 +40,7 @@ from std_msgs.msg import String def talker(): - pub = rospy.Publisher('chatter', String) + pub = rospy.Publisher('chatter', String, queue_size=10) rospy.init_node('talker', anonymous=True) r = rospy.Rate(10) # 10hz while not rospy.is_shutdown(): diff --git a/rospy_tutorials/002_headers/talker_header.py b/rospy_tutorials/002_headers/talker_header.py index d895d9a7..d7da6292 100755 --- a/rospy_tutorials/002_headers/talker_header.py +++ b/rospy_tutorials/002_headers/talker_header.py @@ -44,7 +44,7 @@ NAME = 'talker_header' def talker_header(): - pub = rospy.Publisher("chatter_header", HeaderString) + pub = rospy.Publisher("chatter_header", HeaderString, queue_size=10) rospy.init_node(NAME) #blocks until registered with master count = 0 diff --git a/rospy_tutorials/004_listener_subscribe_notify/listener_subscribe_notify.py b/rospy_tutorials/004_listener_subscribe_notify/listener_subscribe_notify.py index fea71011..7e484c54 100755 --- a/rospy_tutorials/004_listener_subscribe_notify/listener_subscribe_notify.py +++ b/rospy_tutorials/004_listener_subscribe_notify/listener_subscribe_notify.py @@ -59,7 +59,7 @@ def peer_unsubscribe(self, topic_name, numPeers): print("I have no friends") def talker_callback(): - pub = rospy.Publisher("chatter", String, ChatterListener()) + pub = rospy.Publisher("chatter", String, subscriber_listener=ChatterListener(), queue_size=10) rospy.init_node(NAME, anonymous=True) count = 0 while not rospy.is_shutdown(): diff --git a/rospy_tutorials/006_parameters/param_talker.py b/rospy_tutorials/006_parameters/param_talker.py index fc4821b8..96098a8d 100755 --- a/rospy_tutorials/006_parameters/param_talker.py +++ b/rospy_tutorials/006_parameters/param_talker.py @@ -90,7 +90,7 @@ def param_talker(): rospy.loginfo('found global_example parameter under key: %s'%param_name) # publish the value of utterance repeatedly - pub = rospy.Publisher(topic_name, String) + pub = rospy.Publisher(topic_name, String, queue_size=10) while not rospy.is_shutdown(): pub.publish(utterance) rospy.loginfo(utterance) diff --git a/rospy_tutorials/007_connection_header/talker_connection_header.py b/rospy_tutorials/007_connection_header/talker_connection_header.py index 52ad40ec..2bf2b508 100755 --- a/rospy_tutorials/007_connection_header/talker_connection_header.py +++ b/rospy_tutorials/007_connection_header/talker_connection_header.py @@ -40,7 +40,7 @@ from std_msgs.msg import String def talker(): - pub = rospy.Publisher('chatter', String, headers={'cookies': 'oreo'}) + pub = rospy.Publisher('chatter', String, headers={'cookies': 'oreo'}, queue_size=10) rospy.init_node('talker', anonymous=True) r = rospy.Rate(10) # 10hz while not rospy.is_shutdown(): diff --git a/rospy_tutorials/008_on_shutdown/publish_on_shutdown.py b/rospy_tutorials/008_on_shutdown/publish_on_shutdown.py index 07eda0bd..075c129c 100755 --- a/rospy_tutorials/008_on_shutdown/publish_on_shutdown.py +++ b/rospy_tutorials/008_on_shutdown/publish_on_shutdown.py @@ -47,7 +47,7 @@ def talker_shutdown(): def talker(): global pub - pub = rospy.Publisher('chatter', String) + pub = rospy.Publisher('chatter', String, queue_size=10) rospy.init_node('talker', anonymous=True) # register talker_shutdown() to be called when rospy exits diff --git a/rospy_tutorials/009_advanced_publish/advanced_publish.py b/rospy_tutorials/009_advanced_publish/advanced_publish.py index dff0d62f..9cf95918 100755 --- a/rospy_tutorials/009_advanced_publish/advanced_publish.py +++ b/rospy_tutorials/009_advanced_publish/advanced_publish.py @@ -43,7 +43,7 @@ def talker(): topic = 'color' - pub = rospy.Publisher(topic, ColorRGBA) + pub = rospy.Publisher(topic, ColorRGBA, queue_size=10) rospy.init_node('color_talker', anonymous=True) print "\n\nNode running. To see messages, please type\n\t'rostopic echo %s'\nIn another window\n\n"%(rospy.resolve_name(topic)) while not rospy.is_shutdown(): diff --git a/rospy_tutorials/test/publish_on_shutdown_test_node.py b/rospy_tutorials/test/publish_on_shutdown_test_node.py index d4f0c8d6..076f9f1c 100755 --- a/rospy_tutorials/test/publish_on_shutdown_test_node.py +++ b/rospy_tutorials/test/publish_on_shutdown_test_node.py @@ -47,7 +47,7 @@ def talker_shutdown(): def talker(): global pub - pub = rospy.Publisher('chatter', String) + pub = rospy.Publisher('chatter', String, queue_size=10) rospy.init_node('talker', anonymous=True) # register talker_shutdown() to be called when rospy exits