Skip to content

Commit

Permalink
Add tcp_no_delay to joint_states subscriber (#80)
Browse files Browse the repository at this point in the history
* Add tcp_no_delay to joint_states subscriber

* Describe how subscriber NODELAY gets to publishers
  • Loading branch information
v-lopez authored and sloretz committed Feb 16, 2018
1 parent 722eae7 commit ef0bde4
Showing 1 changed file with 6 additions and 1 deletion.
7 changes: 6 additions & 1 deletion src/joint_state_listener.cpp
Expand Up @@ -66,8 +66,13 @@ JointStateListener::JointStateListener(const KDL::Tree& tree, const MimicMap& m,
n_tilde.param(tf_prefix_key, tf_prefix_, std::string(""));
publish_interval_ = ros::Duration(1.0/max(publish_freq, 1.0));

// Setting tcpNoNelay tells the subscriber to ask publishers that connect
// to set TCP_NODELAY on their side. This prevents some joint_state messages
// from being bundled together, increasing the latency of one of the messages.
ros::TransportHints transport_hints;
transport_hints.tcpNoDelay(true);
// subscribe to joint state
joint_state_sub_ = n.subscribe("joint_states", 1, &JointStateListener::callbackJointState, this);
joint_state_sub_ = n.subscribe("joint_states", 1, &JointStateListener::callbackJointState, this, transport_hints);

// trigger to publish fixed joints
// if using static transform broadcaster, this will be a oneshot trigger and only run once
Expand Down

0 comments on commit ef0bde4

Please sign in to comment.