You're reading the documentation for a development version. For the latest released version, please have a look at Jazzy.
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_names
to 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_states
anddynamic_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 eitherjoints
orinterfaces
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
anddynamic_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 eitherjoints
orinterfaces
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: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”
- use_urdf_to_filter (bool)
Uses the robot_description to filter the
joint_states
topic. If true, the broadcaster will publish the data of the joints present in the URDF alone. If false, the broadcaster will publish the data of any interface that has typeposition
,velocity
, oreffort
.Default: true
- 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
use_urdf_to_filter: true
Order of the joints in the message
The order of the joints in the message can determined by 3 different parameter settings:
- No defined
joints
parameter anduse_urdf_to_filter
set tofalse
: The order of the joints in the message is the same as the order of the joints’ state interfaces registered in the resource manager. This is typically the order in which the hardware components are loaded and configured.
- No defined
- No defined
joints
parameter anduse_urdf_to_filter
set totrue
: The order of the joints in the message is the same as the order of the joints in the URDF file, which is inherited from the loaded URDF model and independent of the order in the ros2_control tag.
- No defined
- Defined
joints
parameter along withinterfaces
parameter: The order of the joints in the message is the same as the order of the joints in the
joints
parameter.If the
joints
parameter is a subset of the total available joints in the URDF (or) the total available state interfaces, then only the joints in thejoints
parameter are published in the message.If any of the combinations of the defined
joints
parameter andinterfaces
parameter are not in the available state interfaces, the controller will fail to activate.
- Defined
Note
If the extra_joints
parameter is set, the joints in the extra_joints
parameter are appended to the end of the joint names in the message.