ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
2

/joint_states topic and publish rate

asked 2015-12-07 07:35:23 -0500

iasons gravatar image

updated 2015-12-07 08:43:29 -0500

I want to read the joint states of a robot from the /joint_states topic, preferably at 1kHz. The problem is that when I increase the publishing rate X of the joint controller above 100Hz, a subscriber to /joint_states receives messages at X Hz for 1-2 seconds and then the rate changes. The joint_states topic seems to give me packets of messages in a smaller frequency.

For instance, I have 1Khz publish rate. For the first half a second I have 1 msg every 1 ms. After that half a second I receive 20 msgs together every 20ms.

I have visualized this issue with rosbag and it seems to be repeatable in multiple machines. Also the timing and the behaviour is exactly the same every time.

I have tried to subscribe to /joint_states topic running the Shadow's robot hand and the KUKA LWR4+ ROS packages from here: https://github.com/CentroEPiaggio/kuk... either in real robots or simulated with gazebo, and the same issue is persistent, so I don't thing is something depended on the robot.

Has anyone else noticed this behaviour? It seems like a buffer is full or something locks a mutex during the real-time publishing of the joint state controller.

edit retag flag offensive close merge delete

Comments

I am having the same issue, packets of messages show up every 20 ms. The total number of messages corresponds with the publish rate that I have set, but no matter what I change the messages show up in packets. If I change the real time rate that Gazebo runs at it makes no difference, still every 20 ms of simulation time. I am also trying to publish at 1 kHz, though I had also tried 2 kHz with no effect. I will for now drop down to 100 Hz and see if that at least gets me messages every 10 ms.

JoshuaElliott gravatar image JoshuaElliott  ( 2020-12-16 22:17:13 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-12-16 23:08:00 -0500

JoshuaElliott gravatar image

updated 2020-12-17 10:34:50 -0500

I have searched high and low for a true answer to your question, but I think whatever is causing this is insufficiently documented to the point it is unsolvable.

I think the way around this is to avoid the /joint_states topic, and instead generate a custom topic within a Gazebo plugin that will publish the necessary data. My own Gazebo plugin is able to smoothly output current joint states exactly synched with the simulation time steps (by using the OnUpdate() function within the plugin).

public: void OnUpdate()
    {
              ROS_INFO_STREAM(this->model->GetJoint(joint_name[i][j][k])->GetVelocity(0));
    }

In the above example I have it printing to the terminal, but you can also create a ros topic within the plugin to publish to.

EDIT: while the above method will still work (and may be best for certain time sensitive topics), this issue is definitely caused by the implementation of Nagle's algorithm for connections. Nagle's algorithm groups messages together and sends them as a block in order to save bandwidth at the expense of latency. Therefore the rate that messages get sent at I believe depends on the size and frequency of those messages. You don't need to modify the publisher, which seems weird but that's how it is.

To disable Nagle's algorithm you need to modify the ROS subscriber, below are my original subscriber, then modified to dissable Nagle.

sub5 = nh_.subscribe("/dd_robot/joint_states", 5, &variables::joint_states_Callback, this);
sub5 = nh_.subscribe("/dd_robot/joint_states", 5, &variables::joint_states_Callback, this, ros::TransportHints().tcpNoDelay());
edit flag offensive delete link more

Comments

1

Have you tried disabling Nagle for your subscriber?

gvdhoorn gravatar image gvdhoorn  ( 2020-12-17 03:44:58 -0500 )edit

That sounds like it might be the exact cause of the problem. Can you explain how to disable it? It sounds like it is set within the subscriber, for clarity by subscriber is below:

sub5 = nh_.subscribe("/dd_robot/joint_states", 5, &variables::joint_states_Callback, this);

Where "variables" is the name of the class I'm using to hold things.

EDIT I figured it out after writing this original comment and amended by answer above to show how to disable it. Thanks a lot for saving me a lot of work converting ROS nodes into Gazebo plugins.

JoshuaElliott gravatar image JoshuaElliott  ( 2020-12-17 10:26:02 -0500 )edit
1

It's documented on the roscpp/Overview/Publishers and Subscribers page.

gvdhoorn gravatar image gvdhoorn  ( 2020-12-17 10:36:20 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-12-07 07:35:23 -0500

Seen: 2,703 times

Last updated: Dec 17 '20