Skip to content

Commit

Permalink
Update docs on URDF and robot_description
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Jan 3, 2024
1 parent a2a50d9 commit c702eba
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 5 deletions.
14 changes: 9 additions & 5 deletions controller_manager/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,15 @@ Alternatives to the standard kernel include
Though installing a realtime-kernel will definitely get the best results when it comes to low
jitter, using a lowlatency kernel can improve things a lot with being really easy to install.

Subscribers
-----------

~/robot_description [std_msgs::msg::String]
String with the URDF xml, e.g., from ``robot_state_publisher``.
Reloading of the URDF is not supported yet.
All joints defined in the ``<ros2_control>``-tag have to be present in the URDF.


Parameters
-----------

Expand All @@ -70,15 +79,10 @@ hardware_components_initial_state.unconfigured (optional; list<string>; default:
hardware_components_initial_state.inactive (optional; list<string>; default: empty)
Defines which hardware components will be configured immediately when controller manager is started.

robot_description (mandatory; string)
String with the URDF string as robot description.
This is usually result of the parsed description files by ``xacro`` command.

update_rate (mandatory; integer)
The frequency of controller manager's real-time update loop.
This loop reads states from hardware, updates controller and writes commands to hardware.


<controller_name>.type
Name of a plugin exported using ``pluginlib`` for a controller.
This is a class from which controller's instance with name "``controller_name``" is created.
Expand Down
2 changes: 2 additions & 0 deletions hardware_interface/doc/hardware_interface_types_userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@ Joints
``<joint>``-tag groups the interfaces associated with the joints of physical robots and actuators.
They have command and state interfaces to set the goal values for hardware and read its current state.

All joints defined in the ``<ros2_control>``-tag have to be present in the URDF received :ref:`by the controller manager <doc/ros2_control/controller_manager/doc/userdoc:subscribers>`.

State interfaces of joints can be published as a ROS topic by means of the :ref:`joint_state_broadcaster <joint_state_broadcaster_userdoc>`

Sensors
Expand Down

0 comments on commit c702eba

Please sign in to comment.