From fb2acf20576059b4bee3106e9d4d77575bd59034 Mon Sep 17 00:00:00 2001 From: ipa-fxm <felix.messmer@ipa.fhg.de> Date: Wed, 22 Oct 2014 13:32:02 +0200 Subject: [PATCH] add queue_size argument to Publisher --- ur_driver/src/ur_driver/driver.py | 6 +++--- ur_driver/src/ur_driver/testRT_comm.py | 4 ++-- ur_driver/src/ur_driver/test_comm.py | 4 ++-- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/ur_driver/src/ur_driver/driver.py b/ur_driver/src/ur_driver/driver.py index 469e523..f7b92c1 100755 --- a/ur_driver/src/ur_driver/driver.py +++ b/ur_driver/src/ur_driver/driver.py @@ -88,9 +88,9 @@ connected_robot_lock = threading.Lock() connected_robot_cond = threading.Condition(connected_robot_lock) last_joint_states = None last_joint_states_lock = threading.Lock() -pub_joint_states = rospy.Publisher('joint_states', JointState) -pub_wrench = rospy.Publisher('wrench', WrenchStamped) -pub_io_states = rospy.Publisher('io_states', IOStates) +pub_joint_states = rospy.Publisher('joint_states', JointState, queue_size=1) +pub_wrench = rospy.Publisher('wrench', WrenchStamped, queue_size=1) +pub_io_states = rospy.Publisher('io_states', IOStates, queue_size=1) #dump_state = open('dump_state', 'wb') class EOF(Exception): pass diff --git a/ur_driver/src/ur_driver/testRT_comm.py b/ur_driver/src/ur_driver/testRT_comm.py index 84c7414..11daffa 100755 --- a/ur_driver/src/ur_driver/testRT_comm.py +++ b/ur_driver/src/ur_driver/testRT_comm.py @@ -64,9 +64,9 @@ def main(): rospy.init_node('testRT_comm', disable_signals=True) global pub_joint_statesRT - pub_joint_statesRT = rospy.Publisher('joint_statesRT', JointState) + pub_joint_statesRT = rospy.Publisher('joint_statesRT', JointState, queue_size=1) global pub_robot_stateRT - pub_robot_stateRT = rospy.Publisher('robot_stateRT', RobotStateRTMsg) + pub_robot_stateRT = rospy.Publisher('robot_stateRT', RobotStateRTMsg, queue_size=1) diff --git a/ur_driver/src/ur_driver/test_comm.py b/ur_driver/src/ur_driver/test_comm.py index 2938135..1670db8 100755 --- a/ur_driver/src/ur_driver/test_comm.py +++ b/ur_driver/src/ur_driver/test_comm.py @@ -87,9 +87,9 @@ def main(): rospy.init_node('test_comm', disable_signals=True) global pub_masterboard_state - pub_masterboard_state = rospy.Publisher('masterboard_state', MasterboardDataMsg) + pub_masterboard_state = rospy.Publisher('masterboard_state', MasterboardDataMsg, queue_size=1) global pub_io_states - pub_io_states = rospy.Publisher('io_states', IOStates) + pub_io_states = rospy.Publisher('io_states', IOStates, queue_size=1) robot_hostname = '192.168.0.42' -- GitLab