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

Revision history [back]

In simulation the gazebo_ros_controller_manager plugin is responsible for providing the infrastructure for running controllers and for publishing the joint state. You should be able to use it in a custom urdf. I think you will have to add transmission specifications though which seem to be undocumented. To use the controller plugin, add the following to your urdf file:

  <gazebo>
    <controller:gazebo_ros_controller_manager name="gazebo_ros_controller_manager" plugin="libgazebo_ros_controller_manager.so">
      <alwaysOn>true</alwaysOn>
      <updateRate>1000.0</updateRate>
      <interface:audio name="gazebo_ros_controller_manager_dummy_iface" />
    </controller:gazebo_ros_controller_manager>
  </gazebo>

To get joint states, a node that communicates with your robot's hardware is run on the robot. It reads the position of the encoders in all joints and constructs a sensor_msgs/JointState message that is then published on the /joint_states topic.

If you are running on a real robot, you need to implement such a node. On the PR2 that's the pr2_etherCAT node and you need to implement something similar if you are using a custom robot and want to have joint states.

In simulation the simulation, things can be a little easier because you can use the pr2 controller manager that's used on the simulated pr2 for other robots, too The gazebo_ros_controller_manager plugin is responsible for providing the infrastructure for running controllers and for publishing the joint state. You should be able to use it in a custom urdf. I think you will have to add transmission specifications though which seem to be undocumented. To use the controller plugin, add the following to your urdf file:

  <gazebo>
    <controller:gazebo_ros_controller_manager name="gazebo_ros_controller_manager" plugin="libgazebo_ros_controller_manager.so">
      <alwaysOn>true</alwaysOn>
      <updateRate>1000.0</updateRate>
      <interface:audio name="gazebo_ros_controller_manager_dummy_iface" />
    </controller:gazebo_ros_controller_manager>
  </gazebo>

If you do not want to use that plugin, you need to write your own gazebo plugin that reads the positions of the joints specified in your URDF file, advertises the /joint_states topic and publishes the joint positions as a message of type sensor_msgs/JointState.

The joint_state_publisher node you mentioned in your question essentially publishes a constant value for all non-fixed joint positions, i.e. it does not respect the actual position of joints in simulation. It also provides a gui that lets you to change the joint state values. This node is most useful when you are creating a urdf file to check if all joints are aligned correctly.