Skip to content
This repository was archived by the owner on May 18, 2025. It is now read-only.

Commit 63973a2

Browse files
chameau5050ahcordechristophfroehlich
authored andcommitted
Add PID controller to control joint using effort (#294)
Co-authored-by: Alejandro Hernández Cordero <[email protected]> Co-authored-by: Christoph Fröhlich <[email protected]> (cherry picked from commit f769c6c)
1 parent 3276cbd commit 63973a2

13 files changed

+659
-25
lines changed

doc/index.rst

Lines changed: 70 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -131,6 +131,58 @@ We should include:
131131
</joint>
132132
133133
134+
Using PID control joints
135+
-----------------------------------------------------------
136+
137+
To use PID control joints in gazebo_ros2_control, you should define their parameters inside the ``<joint>`` tag
138+
within the ``<ros2_control>`` tag. These PID joints can be controlled either in position or velocity.
139+
140+
- To control a joint with velocity PID, simply set its ``command_interface`` to ``velocity_PID``.
141+
- To control a joint with position PID, set its ``command_interface`` to ``position_PID``.
142+
143+
.. note::
144+
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).
145+
146+
To create a system with one joint that can be controlled using both position_PID and velocity_PID, follow this example:
147+
148+
.. code-block:: xml
149+
150+
<ros2_control name="GazeboSystem" type="system">
151+
<hardware>
152+
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
153+
</hardware>
154+
<joint name="slider_to_cart">
155+
156+
<param name="pos_kp">10</param>
157+
<param name="pos_ki">1</param>
158+
<param name="pos_kd">2</param>
159+
<param name="pos_max_integral_error">10000</param>
160+
161+
<param name="vel_kp">10</param>
162+
<param name="vel_ki">5</param>
163+
<param name="vel_kd">2</param>
164+
<param name="vel_max_integral_error">10000</param>
165+
166+
<command_interface name="position_PID"/>
167+
<command_interface name="velocity_PID"/>
168+
169+
<state_interface name="position">
170+
<param name="initial_value">1.0</param>
171+
</state_interface>
172+
<state_interface name="velocity"/>
173+
<state_interface name="effort"/>
174+
</joint>
175+
</ros2_control>
176+
177+
Where the parameters are as follows:
178+
179+
- ``pos_kp``: Proportional gain
180+
- ``pos_ki``: Integral gain
181+
- ``pos_kd``: Derivative gain
182+
- ``pos_max_integral_error``: Maximum summation of the error
183+
184+
The same definitions apply to the ``vel_*`` parameters.
185+
134186
Add the gazebo_ros2_control plugin
135187
==========================================
136188

@@ -243,6 +295,7 @@ When the Gazebo world is launched you can run some of the following commands to
243295
.. code-block:: shell
244296
245297
ros2 run gazebo_ros2_control_demos example_position
298+
ros2 run gazebo_ros2_control_demos example_position_pid
246299
ros2 run gazebo_ros2_control_demos example_velocity
247300
ros2 run gazebo_ros2_control_demos example_effort
248301
@@ -310,3 +363,20 @@ degree of freedom on the rail, and the physics of the passive joint of the pendu
310363
311364
ros2 launch gazebo_ros2_control_demos pendulum_example_position.launch.py
312365
ros2 run gazebo_ros2_control_demos example_position
366+
367+
368+
369+
PID control joints
370+
-----------------------------------------------------------
371+
372+
The following examples shows a vertical cart control by a PID joint using position and velocity cmd.
373+
374+
.. code-block:: shell
375+
376+
ros2 launch gazebo_ros2_control_demos vertical_cart_example_position_pid.launch.py
377+
ros2 launch gazebo_ros2_control_demos vertical_cart_example_velocity_pid.launch.py
378+
379+
.. code-block:: shell
380+
381+
ros2 run gazebo_ros2_control_demos example_position_pid
382+
ros2 run gazebo_ros2_control_demos example_velocity

gazebo_ros2_control/CMakeLists.txt

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@ project(gazebo_ros2_control)
44
find_package(ament_cmake REQUIRED)
55
find_package(angles REQUIRED)
66
find_package(controller_manager REQUIRED)
7+
find_package(control_toolbox REQUIRED)
78
find_package(gazebo_dev REQUIRED)
89
find_package(gazebo_ros REQUIRED)
910
find_package(hardware_interface REQUIRED)
@@ -33,6 +34,7 @@ add_library(${PROJECT_NAME} SHARED
3334
ament_target_dependencies(${PROJECT_NAME}
3435
angles
3536
controller_manager
37+
control_toolbox
3638
gazebo_dev
3739
gazebo_ros
3840
hardware_interface
@@ -46,6 +48,7 @@ add_library(gazebo_hardware_plugins SHARED
4648
)
4749
ament_target_dependencies(gazebo_hardware_plugins
4850
angles
51+
control_toolbox
4952
gazebo_dev
5053
hardware_interface
5154
rclcpp

gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,12 +16,16 @@
1616
#ifndef GAZEBO_ROS2_CONTROL__GAZEBO_SYSTEM_HPP_
1717
#define GAZEBO_ROS2_CONTROL__GAZEBO_SYSTEM_HPP_
1818

19+
#define VELOCITY_PID_PARAMS_PREFIX "vel_"
20+
#define POSITION_PID_PARAMS_PREFIX "pos_"
21+
1922
#include <memory>
2023
#include <string>
2124
#include <vector>
2225

2326
#include "angles/angles.h"
2427

28+
#include "control_toolbox/pid.hpp"
2529
#include "gazebo_ros2_control/gazebo_system_interface.hpp"
2630

2731
#include "std_msgs/msg/bool.hpp"
@@ -86,6 +90,10 @@ class GazeboSystem : public GazeboSystemInterface
8690
const hardware_interface::HardwareInfo & hardware_info,
8791
gazebo::physics::ModelPtr parent_model);
8892

93+
control_toolbox::Pid extractPID(
94+
std::string prefix,
95+
hardware_interface::ComponentInfo joint_info);
96+
8997
/// \brief Private data class
9098
std::unique_ptr<GazeboSystemPrivate> dataPtr;
9199
};

gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -79,6 +79,8 @@ class GazeboSystemInterface
7979
POSITION = (1 << 0),
8080
VELOCITY = (1 << 1),
8181
EFFORT = (1 << 2),
82+
VELOCITY_PID = (1 << 3),
83+
POSITION_PID = (1 << 4),
8284
};
8385

8486
typedef SafeEnum<enum ControlMethod_> ControlMethod;

gazebo_ros2_control/package.xml

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,9 +19,10 @@
1919
<buildtool_depend>ament_cmake</buildtool_depend>
2020

2121
<depend>angles</depend>
22+
<depend>controller_manager</depend>
23+
<depend>control_toolbox</depend>
2224
<depend>gazebo_dev</depend>
2325
<depend>gazebo_ros</depend>
24-
<depend>controller_manager</depend>
2526
<depend>hardware_interface</depend>
2627
<depend>pluginlib</depend>
2728
<depend>rclcpp</depend>

0 commit comments

Comments
 (0)