You're reading the documentation for an older, but still supported, version of ROS 2. For information on the latest version, please have a look at Kilted.
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.
Published topics
/joint_states(sensor_msgs/msg/JointState):Publishes movement-related interfaces only —
position,velocity, andeffort— for joints that provide them. If a joint does not expose a given movement interface, that field is omitted/left empty for that joint in the message./dynamic_joint_states(control_msgs/msg/DynamicJointState):Publishes all available state interfaces for each joint. This includes the movement interfaces (position/velocity/effort) and any additional or custom interfaces provided by the hardware (e.g., temperature, voltage, torque sensor readings, calibration flags).
The message maps
joint_namesto per-joint interface name lists and values. Example payload:joint_names: [joint1, joint2] interface_values: - interface_names: [position, velocity, effort] values: [1.5708, 0.0, 0.20] - interface_names: [position, temperature] values: [0.7854, 42.1]
Use this topic if you need every reported interface, not just movement.
Note
If use_local_topics is set to true, both topics are published in the
controller’s namespace (e.g., /my_state_broadcaster/joint_states and
/my_state_broadcaster/dynamic_joint_states). If false (default),
they are published at the root (e.g., /joint_states).
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_statesanddynamic_joint_statesmessages 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
interfacesparameter. If eitherjointsorinterfacesis 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_statesanddynamic_joint_stateswith 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
jointsparameter. If eitherjointsorinterfacesis 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_statesmessage. Usecases: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.
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”
- frame_id (string)
The frame_id to be used in the published joint states. This parameter allows rviz2 to visualize the effort of the joints.
Default: “base_link”
An example parameter file
joint_state_broadcaster:
ros__parameters:
extra_joints: '{}'
frame_id: base_link
interfaces: '{}'
joints: '{}'
map_interface_to_joint_state:
effort: effort
position: position
velocity: velocity
use_local_topics: false