Skip to content

Commit 23c76f2

Browse files
authored
docs(joint_state_broadcaster): clarify /dynamic_joint_states contents (backport #1865) (#1870)
1 parent 8c12464 commit 23c76f2

File tree

1 file changed

+36
-0
lines changed

1 file changed

+36
-0
lines changed

joint_state_broadcaster/doc/userdoc.rst

Lines changed: 36 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,42 @@ In the latter case, resulting interfaces is defined by a "matrix" of interfaces
2020
If some requested interfaces are missing, the controller will print a warning about that, but work for other interfaces.
2121
If none of the requested interface are not defined, the controller returns error on activation.
2222

23+
Published topics
24+
----------------
25+
26+
* ``/joint_states`` (``sensor_msgs/msg/JointState``):
27+
28+
Publishes *movement-related* interfaces only — ``position``, ``velocity``,
29+
and ``effort`` — for joints that provide them. If a joint does not expose a given
30+
movement interface, that field is omitted/left empty for that joint in the message.
31+
32+
* ``/dynamic_joint_states`` (``control_msgs/msg/DynamicJointState``):
33+
34+
Publishes **all available state interfaces** for each joint. This includes the
35+
movement interfaces (position/velocity/effort) *and* any additional or custom
36+
interfaces provided by the hardware (e.g., temperature, voltage, torque sensor
37+
readings, calibration flags).
38+
39+
The message maps ``joint_names`` to per-joint interface name lists and values.
40+
Example payload::
41+
42+
joint_names: [joint1, joint2]
43+
interface_values:
44+
- interface_names: [position, velocity, effort]
45+
values: [1.5708, 0.0, 0.20]
46+
- interface_names: [position, temperature]
47+
values: [0.7854, 42.1]
48+
49+
Use this topic if you need *every* reported interface, not just movement.
50+
51+
.. note::
52+
53+
If ``use_local_topics`` is set to ``true``, both topics are published in the
54+
controller’s namespace (e.g., ``/my_state_broadcaster/joint_states`` and
55+
``/my_state_broadcaster/dynamic_joint_states``). If ``false`` (default),
56+
they are published at the root (e.g., ``/joint_states``).
57+
58+
2359
Parameters
2460
----------
2561
This controller uses the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters. The parameter `definition file located in the src folder <https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/joint_state_broadcaster/src/joint_state_broadcaster_parameters.yaml>`_ contains descriptions for all the parameters used by the controller.

0 commit comments

Comments
 (0)