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

Joint State Publisher produces empty messages

asked 2019-09-13 02:59:47 -0500

Weasfas gravatar image

updated 2019-09-17 03:31:22 -0500

Hello,

This questions can be split into two:

The first one. I am currently using in my URDF in Gazebo a ROS_control controller to control the platform wheels (velocity and position interface) and I am wondering if there is a way to plot the PID values in order to see the performance. Since I do not have any /command/data and /state/process_value topics I cannot plot the behavior of the PIDs.

The second one is related to the first question. Since I do not have those topics I want now to plot the changes on the jointStates. Robot_state_publisher and joint_state_publisher are launched properly but when you read the joint state topic there are certain messages which appear to be empty, this follows a pattern because this empty message happens every 4 messages, the 5th one is the empty one:

header: 
  seq: 74
  stamp: 
    secs: 7
    nsecs: 400000000
  frame_id: ''
name: [front_right_wheel_steer_joint, front_right_wheel_joint, front_right_shock,
  front_left_wheel_steer_joint, front_left_wheel_joint, front_left_shock,
  back_right_wheel_steer_joint, back_right_wheel_joint, back_right_shock,
  back_left_wheel_steer_joint, back_left_wheel_joint, back_left_shock]
position: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
velocity: []
effort: []

Joint state publisher node is publishing at a rate of 50 and I thought that was the problem, but changes on that value will output the same behavior.

If someone can help me with this I will appreciate.

Thanks in advance.

Update:

Here is the launch file:

<?xml version="1.0"?>

<launch>

  <!-- these are the arguments you can pass this launch file, for example paused:=true -->
  <arg name="gui" default="true"/>
  <arg name="use_joint_state_publisher" default="false"/>
  <arg name="setup" default="setup_4"/> <!-- Different setups for the sensors -->
  <arg name="ultrasonic_on" default="1"/> <!-- Different setups for the sensors -->
  <arg name="zed_on" default="1"/> <!-- Different setups for the sensors -->

  <group ns="ares">

    <!-- Load the URDF into the ROS Parameter Server -->
    <param name="robot_description"
    command="$(find xacro)/xacro --inorder '$(find ares_description)/urdf/bus/ares.xacro' setup:=$(arg setup) 
    ultrasonic_on:=$(arg ultrasonic_on) zed_on:=$(arg zed_on)" />

    <!-- send fake joint values -->
    <node if="$(arg use_joint_state_publisher)" name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" output="screen"/>

    <!-- Combine joint values -->
    <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen"/>

    <!-- Display with rviz -->
    <node name="rviz" pkg="rviz" type="rviz" respawn="false" output="screen"/>

  </group>

</launch>

If you change the parameter use_joint_state_publisher to true the model is well defined in tf and visualize in rviz.

edit retag flag offensive close merge delete

Comments

Are you quite sure only a single node is publishing the joint states topic? Typically when I get occasional messages with completely different values it's because there are two nodes publishing on the same topic.

jdlangs gravatar image jdlangs  ( 2019-09-13 10:05:40 -0500 )edit

Hello @jdlangs

In fact there are two Publishers: Gazebo and Joint_state_publisher, but I think that is the correct behavior.

Weasfas gravatar image Weasfas  ( 2019-09-16 02:24:20 -0500 )edit

I think what @jdlangs pointed out is most likely the problem. Usually, you would have either gazebo or the joint state publisher sending messages, but not both. The typical use case is: you build your URDF and use the joint state publisher to debug it. Then, as soon as your gazebo simulation is ready, gazebo publishes the actual message and you do not need the other anymore. There are cases in which you might still want the joint state publisher to run, but not in general. The reason is that the joint state publisher generally has an "internal fake state" that is updated via the gui, and thus it would differ from the actual state provided by a simulator. Also, it generally does not include velocity/effort info, making me think this is the problem. Are both gazebo and the joint state publisher sending messages on /joint_states? If so, give ...(more)

ffusco gravatar image ffusco  ( 2019-09-16 03:56:14 -0500 )edit

As @ffusco said I removed from my launch file the launch of the joint_state_publisher and now all the messages in the /joint_states topic are properly filled. However, now I have the problem of a broken tf tree because I am not able to see the model in rviz.

Weasfas gravatar image Weasfas  ( 2019-09-16 05:12:17 -0500 )edit

Is the robot state publisher printing and message on the console? (make sure to add the attribute output=screen in the launch file) In addition, is the RViz robot model display reporting any issue?

ffusco gravatar image ffusco  ( 2019-09-16 05:57:46 -0500 )edit

The robot_state_publisher has the attribute output=screen and does not produce any warnings or errors. In Rviz the problem resides in the tf tree, since there are no transforms between the vehicle base and the wheels. Thus, Rviz shows the vehicle chassis but not the wheels.

Weasfas gravatar image Weasfas  ( 2019-09-17 02:28:56 -0500 )edit

There is a good chance the node responsible for publishing JointStates is not publishing them for alljoints defined in your urdf.

That would cause the RSP to not do FK, leading to missing transforms, causing the error you get in RViz.

gvdhoorn gravatar image gvdhoorn  ( 2019-09-17 02:37:43 -0500 )edit

As far as I understood joint_state_publisher node is needed by robot_state_publisher to build the tf tree. The problem rises when Gazebo AND joint_state_publisher node publish on the same topic /joint_states with different messages. I have 12 joints for the wheels: 4 linear movement, 4 steering and 4 shock absorbers. To my knowledge, Gazebo is publishing on /joint_states empty messages with all 12 joints names, while joint_state_publisher node is publishing filled messages with only 8 joints, without the shock ones.

In truth I only want this data to debug what is happening in the wheels... I decided to record a rosbag and filter the empty messages. But I do not really able to understand and find why this empty messages are produced.

I am going to update the question with my launch file.

Weasfas gravatar image Weasfas  ( 2019-09-17 03:29:51 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
3

answered 2019-09-17 07:11:28 -0500

ffusco gravatar image

updated 2019-09-17 07:29:03 -0500

I will gather what we said in a short answer.

First of all, you should not have multiple nodes publishing on the same /joint_states topic, since this will likely lead to weird behaviors, like the one you were getting. In general, you firstly want to have a joint_state_publisher (JSP) running so that you can debug your URDF. When you are ok with that, you can then switch to simulating the robot in Gazebo. Since you use ROS control, I assume that a JointStateController or similar will be publishing the wheel angles on the /joint_states topic. From that point on, you want in general not to run the JSP node as well. This is because it will provide values which do not match with the simulation: the JSP node keeps an internal fake state and since it is not updated elsewhere, Gazebo will say, e.g., that the joint front_right_wheel_steer_joint has an angle of 1.4 radians while JSP might publish for the same joint the value -5.8. This can lead to different issues later on. Long story short, again: do not use a JSP when someone else is publishing the correct joint values, in general.

Time to address specifically the issue with the "incomplete" TF. The issue comes from the fact that Gazebo publishes only 4 wheels angles, despite your robot having more moving joints. In the future, you should try to give more information about your robot, e.g., by sharing the URDF or simply more info about it. By doing this, you will make us "guess less" and give you better answers ;)

The point is this: the robot_state_publisher (RSP) node expects to receive full information about the current configuration. This means that sooner or later, you have to provide all joint coordinates into the /joint_states topic. In your setup, Gazebo will only publish 4 values, and therefore this is not enough to evaluate all transforms. If you add the JSP as you did, every so and then the published state will mismatch the one obtained in the simulation. The workaround that I can propose is rather simple, but it is, in my opinion, sub-optimal. What you can do is to actually use both Gazebo and the JSP but in a different way. In its documentation, it is written that JSP allows to "listen" to various sources, listed in the parameter source_list. In addition, unless the parameter publish_default_positions is set to False, JSP will always publish all joint values, either using "known values" or their defaults. You can thus make the Gazebo controller publish in a topic named, e.g., wheels_states. Then, start the JSP, listening to such topic, i.e., with source_list=[wheels_states]. In this way, JSP will start by publishing all joints set to zero, and as soon as Gazebo is able to provide the actual value of the wheels, fake values will be replaced with actual ones. This way, the RSP will finally be able to publish all transforms you need.

The reason why I ... (more)

edit flag offensive delete link more

Comments

Good answer.

Just to add: joint_state_controller can be configured to publish values for "extra joints" (ie: those it is not configured for). I haven't seen it documented anywhere but here (in the header file of the class).

it's static values only, but it would avoid having to run a JSP just for the joints the Gazebo sim is not publishing and would avoid having to use a source_list JSP.

gvdhoorn gravatar image gvdhoorn  ( 2019-09-17 07:16:16 -0500 )edit

Ok. In the future I will take into account the suggestions @ffusco provide.

Actually, I will mark your answers as correct because I was able to fix all the TF tree and problems regarding the controller with this lines:

  # Publish all joint states -----------------------------------
  joint_state_controller:
    type: joint_state_controller/JointStateController
    publish_rate: 50
    extra_joints:
     - name: front_left_shock
       position: 0.01
       velocity: 0.0
       effort: 0.0

     - name: front_right_shock
       position: 0.01
       velocity: 0.0
       effort: 0.0

     - name: back_left_shock
       position: 0.01
       velocity: 0.0
       effort: 0.0

     - name: back_right_shock
       position: 0.01
       velocity: 0.0
       effort: 0.0

It turned out to be that the controller interface was not fully completed with all URDF joints.

Weasfas gravatar image Weasfas  ( 2019-09-18 05:08:57 -0500 )edit

Glad we helped! :)

ffusco gravatar image ffusco  ( 2019-09-19 00:32:04 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2019-09-13 02:59:47 -0500

Seen: 3,169 times

Last updated: Sep 17 '19