You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Copy file name to clipboardExpand all lines: joint_trajectory_controller/doc/parameters_context.yaml
+18-6Lines changed: 18 additions & 6 deletions
Original file line number
Diff line number
Diff line change
@@ -2,17 +2,29 @@ constraints:
2
2
Default values for tolerances if no explicit values are set in the ``JointTrajectory`` message.
3
3
4
4
gains: |
5
-
If ``velocity`` is the only command interface for all joints or an ``effort`` command interface is configured, PID controllers are used for every joint.
6
-
This structure contains the controller gains for every joint with the control law
5
+
The parameters are used to configure PID loops for the ``velocity`` or ``effort``-only command interfaces. This structure contains the controller gains for every joint with following the control laws
7
6
8
-
.. math:: u = k_{ff} v_d + k_p e + k_i \sum e dt + k_d (v_d - v)
7
+
* If ``velocity`` is the only command interface:
9
8
10
-
with the desired velocity :math:`v_d`, the measured velocity :math:`v`, the position error :math:`e` (definition see below),
11
-
the controller period :math:`dt`, and the ``velocity`` or ``effort`` manipulated variable (control variable) :math:`u`, respectively.
9
+
.. math::
10
+
11
+
u = k_{ff} v_d + k_p e + k_i \sum e dt + k_d (v_d - v)
12
+
13
+
with the desired velocity :math:`v_d`, the measured velocity :math:`v`, the position error :math:`e` (definition see below),
14
+
the controller period :math:`dt`, and the ``velocity`` manipulated variable (control variable) :math:`u`, respectively.
15
+
16
+
* If ``effort`` is the only command interface:
17
+
18
+
.. math::
19
+
20
+
u = k_{ff} v_d + \delta_d + k_p e + k_i \sum e dt + k_d (v_d - v)
21
+
22
+
with the desired velocity :math:`v_d`, the desired effort :math:`\delta_d` if provided in the trajectory (or 0 otherwise), the measured velocity :math:`v`, the position error :math:`e` (definition see below),
23
+
the controller period :math:`dt`, and the ``effort`` manipulated variable (control variable) :math:`u`, respectively.
12
24
13
25
If the joint is of continuous type, the position error :math:`e = normalize(s_d - s)` is normalized between :math:`-\pi, \pi`,
14
26
i.e., the shortest rotation to the target position is the desired motion.
15
27
Otherwise :math:`e = s_d - s` is used, with the desired position :math:`s_d` and the measured
16
28
position :math:`s` from the state interface.
17
29
18
-
If you want to turn off the PIDs (open loop control), set the feedback gains to zero.
30
+
If you want to turn off the PIDs (open loop control), set the feedback gains to zero and an appropriate value for feed-forward gain :math:`k_{ff}`.
Copy file name to clipboardExpand all lines: joint_trajectory_controller/doc/userdoc.rst
+3-3Lines changed: 3 additions & 3 deletions
Display the source diff
Display the rich diff
Original file line number
Diff line number
Diff line change
@@ -30,9 +30,9 @@ This means that the joints can have one or more command interfaces, where the fo
30
30
31
31
* For command interfaces ``position``, the desired positions are simply forwarded to the joints,
32
32
* For command interfaces ``acceleration``, desired accelerations are simply forwarded to the joints.
33
-
* For ``velocity`` (``effort``) command interfaces, the position+velocity trajectory following error is mapped to ``velocity`` (``effort``) commands through a PID loop if it is configured (:ref:`parameters`).
34
-
* For ``effort`` command interface (without ``position`` command interface), if the trajectory contains effort, this will be added to the PID commands as a feed forward effort.
35
-
* For ``position, effort`` command interface, if the trajectory contains effort, this will be passed directly to the ``effort`` interface (PID won't be used) while the positions will be passed to the ``position`` interface.
33
+
* For ``velocity`` command interfaces, the position+velocity trajectory following error is mapped to ``velocity`` commands through a PID loop if it is configured (:ref:`parameters`).
34
+
* For ``effort`` command interface (without ``position`` command interface), the position+velocity trajectory following error is mapped to ``effort`` commands through a PID loop if it is configured (:ref:`parameters`). In addition, it adds trajectory's effort as feedforward effort to the PID output.
35
+
* For ``position, effort`` command interface, PID loop is not used. If the trajectory contains effort, its value will be passed directly to the ``effort`` interface while the desired positions will be forwarded to the ``position`` interface. This could be useful for manipulation tasks where you need to add that extra force to maintain contact.
36
36
37
37
This leads to the following allowed combinations of command and state interfaces:
0 commit comments