diff --git a/ur_driver/src/ur_driver/driver.py b/ur_driver/src/ur_driver/driver.py index 469e523d2220eb89424f1787ca9e377ff5cab29d..f7b92c1dbb35f5f12a51f3c877fe01c0058857bb 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 84c74142a553e2e52ba20584addd4881c593e1ed..11daffa671c905c3243f894e9259a9c5000abe8b 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 29381354ccbf99050666cb8c68a982ce1625c847..1670db8521f0b862287d44ad6b0e75c09a34dbc3 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'