Skip to content

Commit

Permalink
The name of the pid-control-joints command interfa (#343)
Browse files Browse the repository at this point in the history
ce was changed from position_PID/velocity_PID to position_pid/velocity_pid

(cherry picked from commit f6bf9ce)
  • Loading branch information
HPCLOL authored and mergify[bot] committed Jun 20, 2024
1 parent 2ff0432 commit ba8cb83
Showing 1 changed file with 6 additions and 6 deletions.
12 changes: 6 additions & 6 deletions doc/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -143,13 +143,13 @@ Using PID control joints
To use PID control joints in gazebo_ros2_control, you should define their parameters inside the ``<joint>`` tag
within the ``<ros2_control>`` tag. These PID joints can be controlled either in position or velocity.

- To control a joint with velocity PID, simply set its ``command_interface`` to ``velocity_PID``.
- To control a joint with position PID, set its ``command_interface`` to ``position_PID``.
- To control a joint with velocity PID, simply set its ``command_interface`` to ``velocity_pid``.
- To control a joint with position PID, set its ``command_interface`` to ``position_pid``.

.. note::
You cannot have both command interfaces set to position and position_PID for the same joint. The same restriction applies to velocity (and velocity_PID).
You cannot have both command interfaces set to position and position_pid for the same joint. The same restriction applies to velocity (and velocity_pid).

To create a system with one joint that can be controlled using both position_PID and velocity_PID, follow this example:
To create a system with one joint that can be controlled using both position_pid and velocity_pid, follow this example:

.. code-block:: xml
Expand All @@ -169,8 +169,8 @@ To create a system with one joint that can be controlled using both position_PID
<param name="vel_kd">2</param>
<param name="vel_max_integral_error">10000</param>
<command_interface name="position_PID"/>
<command_interface name="velocity_PID"/>
<command_interface name="position_pid"/>
<command_interface name="velocity_pid"/>
<state_interface name="position">
<param name="initial_value">1.0</param>
Expand Down

0 comments on commit ba8cb83

Please sign in to comment.