You're reading the documentation for a development version. For the latest released version, please have a look at Iron.

joint_state_broadcaster

The broadcaster reads all state interfaces and reports them on /joint_states and /dynamic_joint_states.

Commands

Broadcasters are not real controllers, and therefore take no commands.

Hardware interface type

By default, all available joint state interfaces are used, unless configured otherwise. In the latter case, resulting interfaces is defined by a “matrix” of interfaces defined by the cross-product of the joints and interfaces parameters. If some requested interfaces are missing, the controller will print a warning about that, but work for other interfaces. If none of the requested interface are not defined, the controller returns error on activation.

Parameters

This controller uses the generate_parameter_library to handle its parameters. The parameter definition file located in the src folder contains descriptions for all the parameters used by the controller.

List of parameters

use_local_topics (bool)

Defining if joint_states and dynamic_joint_states messages should be published into local namespace, e.g., /my_state_broadcaster/joint_states.

Default: false

joints (string_array)

Parameter to support broadcasting of only specific joints and interfaces. It has to be used in combination with the interfaces parameter. If either joints or interfaces is left empty, all available state interfaces will be published. Joint state broadcaster asks for access to all defined interfaces on all defined joints.

Default: {}

extra_joints (string_array)

Names of extra joints to be added to joint_states and dynamic_joint_states with state set to 0.

Default: {}

interfaces (string_array)

Parameter to support broadcasting of only specific joints and interfaces. It has to be used in combination with the joints parameter. If either joints or interfaces is left empty, all available state interfaces will be published.

Default: {}

map_interface_to_joint_state

Optional parameter (map) providing mapping between custom interface names to standard fields in joint_states message. Usecases:

  1. Hydraulics robots where feedback and commanded values often have an offset and reliance on open-loop control is common. Typically one would map both values in separate interfaces in the framework. To visualize those data multiple joint_state_broadcaster instances and robot_state_publishers would be used to visualize both values in RViz.

  2. A robot provides multiple measuring techniques for its joint values which results in slightly different values. Typically one would use separate interface for providing those values in the framework. Using multiple joint_state_broadcaster instances we could publish and show both in RViz.

Format (each line is optional):

map_interface_to_joint_state:
    position: <custom_interface>
    velocity: <custom_interface>
    effort: <custom_interface>

Examples:

map_interface_to_joint_state:
    position: kf_estimated_position
map_interface_to_joint_state:
    velocity: derived_velocity
    effort: derived_effort
map_interface_to_joint_state:
    effort: torque_sensor
map_interface_to_joint_state:
    effort: current_sensor
map_interface_to_joint_state.position (string)

Default: “position”

map_interface_to_joint_state.velocity (string)

Default: “velocity”

map_interface_to_joint_state.effort (string)

Default: “effort”

An example parameter file

joint_state_broadcaster:
  ros__parameters:
    extra_joints: '{}'
    interfaces: '{}'
    joints: '{}'
    map_interface_to_joint_state:
      effort: effort
      position: position
      velocity: velocity
    use_local_topics: false