Note: This tutorial assumes you completed the create your own urdf file tutorial..
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Using the robot state publisher on your own robot

Description: This tutorial explains how you can publish the state of your robot to tf, using the robot state publisher.

Tutorial Level: BEGINNER

Next Tutorial: For a detailed tutorial on how to use the robot_state_publisher in combination with a urdf, take a look at this tutorial

tf is deprecated in favor of tf2. tf2 provides a superset of the functionality of tf and is actually now the implementation under the hood. If you're just learning now it's strongly recommended to use the tf2/Tutorials instead.

When you are working with a robot that has many relevant frames, it becomes quite a task to publish them all to tf. The robot state publisher is a tool that will do this job for you.

frames2.png

The robot state publisher helps you to broadcast the state of your robot to the tf transform library. The robot state publisher internally has a kinematic model of the robot; so given the joint positions of the robot, the robot state publisher can compute and broadcast the 3D pose of each link in the robot.

You can use the robot state publisher as a standalone ROS node or as a library:

Running as a ROS node

robot_state_publisher

The easiest way to run the robot state publisher is as a node. For normal users, this is the recommended usage. You need two things to run the robot state publisher:

Please read the following sections on how to configure the parameters and topics for robot_state_publisher.

Subscribed topics

joint_states (sensor_msgs/JointState)

  • joint position information

Parameters

robot_description (urdf map)

tf_prefix (string)

  • Set the tf prefix for namespace-aware publishing of transforms. See tf_prefix for more details.

publish_frequency (double)

  • Publish frequency of state publisher, default: 50Hz.

ignore_timestamp (bool)

  • If true, ignore the publish_frequency and the timestamp of joint_states and publish a tf for each of the received joint_states. Default is "false".

use_tf_static (bool)

  • Set whether to use the /tf_static latched static transform broadcaster. Default: false.

use_tf_static (bool)

  • Set whether to use the /tf_static latched static transform broadcaster. Default: true.

Example launch file

Once you have setup the XML robot description and a source for joint position information, simply create a launch file like this one:

  <launch>
   <!-- Load the urdf into the parameter server. -->
   <param name="my_robot_description" textfile="$(find mypackage)/urdf/robotmodel.xml"/>
    
   <node pkg="robot_state_publisher" type="robot_state_publisher" name="rob_st_pub" >
      <remap from="robot_description" to="my_robot_description" />
      <remap from="joint_states" to="different_joint_states" />
    </node>
  </launch>

Running as a library

Advanced users can also run the robot state publisher as a library, from within their own C++ code. After you include the header:

  #include <robot_state_publisher/robot_state_publisher.h>

all you need is the constructor which takes in a KDL tree

  RobotStatePublisher(const KDL::Tree& tree);

and now, every time you want to publish the state of your robot, you call the publishTransforms functions:

  // publish moving joints
  void publishTransforms(const std::map<std::string, double>& joint_positions,
                         const ros::Time& time);

  // publish fixed joints
  void publishFixedTransforms();

The first argument is a map with joint names and joint positions, and the second argument is the time at which the joint positions were recorded. It is okay if the map does not contain all the joint names. It is also okay if the map contains some joints names that are not part of the kinematic model. But note if you don't tell the joint state publisher about some of the joints in your kinematic model, then your tf tree will not be complete.

Wiki: robot_state_publisher/Tutorials/Using the robot state publisher on your own robot (last edited 2021-04-01 04:36:55 by FelixvonDrigalski)