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
The lookahead distance (m) to use to find the motion_target point.
37
+
The maximum lookahead distance (m) to use when selecting a target pose for the underlying control law. Using poses that are further away will generally result in smoother operations, but simulating poses that are very far away can result in reduced performance, especially in tight or cluttered environments. If the controller cannot forward simulate to a pose this far away without colliding, it will iteratively select a target pose that is closer to the robot.
38
+
39
+
:min_lookahead:
40
+
41
+
============== =============================
42
+
Type Default
43
+
-------------- -----------------------------
44
+
double 0.25
45
+
============== =============================
46
+
47
+
Description
48
+
The minimum lookahead distance (m) to use when selecting a target pose for the underlying control law. This parameter avoids instability when an unexpected obstacle appears in the path of the robot by returning failure, which typically triggers replanning.
Ratio of the rate of change in phi to the rate of change in r. Controls the convergence of the slow subsystem. If this value is equal to zero, the controller will behave as a pure waypoint follower. A high value offers extreme scenario of pose-following where theta is reduced much faster than r.
70
+
Ratio of the rate of change in phi to the rate of change in r. Controls the convergence of the slow subsystem. If this value is equal to zero, the controller will behave as a pure waypoint follower. A high value offers extreme scenario of pose-following where theta is reduced much faster than r. The referenced paper calls this `k1`.
60
71
61
72
:k_delta:
62
73
63
74
============== =============================
64
75
Type Default
65
76
-------------- -----------------------------
66
-
double 2.0
77
+
double 1.0
67
78
============== =============================
68
79
69
80
Description
70
-
Constant factor applied to the heading error feedback. Controls the convergence of the fast subsystem. The bigger the value, the robot converge faster to the reference heading.
81
+
Constant factor applied to the heading error feedback. Controls the convergence of the fast subsystem. The bigger the value, the robot converge faster to the reference heading. The referenced paper calls this `k2`.
Maximum angular velocity (rad/s) produced by the control law.
126
137
138
+
:v_angular_min_in_place:
139
+
140
+
============== =============================
141
+
Type Default
142
+
-------------- -----------------------------
143
+
double 0.25
144
+
============== =============================
145
+
146
+
Description
147
+
Minimum angular velocity (rad/s) produced by the control law when rotating in place. This value should be based on the minimum rotation speed controllable by the robot.
Enable a rotation in place to the goal before starting the path. The control law may generate large sweeping arcs to the goal pose, depending on the initial robot orientation and ``k_phi``, ``k_delta``.
148
170
149
-
:initial_rotation_min_angle:
171
+
:initial_rotation_tolerance:
150
172
151
173
============== =============================
152
174
Type Default
153
175
-------------- -----------------------------
154
-
double 0.75
176
+
double 0.75
155
177
============== =============================
156
178
157
179
Description
158
-
The difference in the path orientation and the starting robot orientation to trigger a rotate in place, if ``initial_rotation`` is enabled.
180
+
The difference in the path orientation and the starting robot orientation to trigger a rotate in place, if ``initial_rotation`` is enabled. This value is generally acceptable if continuous replanning is enabled. If not using continuous replanning, a lower value may perform better.
Similar to ``initial_rotation``, the control law can generate large arcs when the goal orientation is not aligned with the path. If this is enabled, the final pose will be ignored and the robot will follow the orientation of he path and will make a final rotation in place to the goal orientation.
191
+
The control law can generate large arcs when the goal orientation is not aligned with the path. If this is enabled, the orientation of the final pose will be ignored and the robot will follow the orientation of the path and will make a final rotation in place to the goal orientation.
Copy file name to clipboardExpand all lines: migration/Jazzy.rst
+10Lines changed: 10 additions & 0 deletions
Display the source diff
Display the rich diff
Original file line number
Diff line number
Diff line change
@@ -204,3 +204,13 @@ New Plugin Container Layer
204
204
**************************
205
205
206
206
In `PR #4781 <https://github.com/ros-navigation/navigation2/pull/4781>`_ a costmap layer plugin type was added to support the grouping of different costmap layers under a single costmap layer. This would allow for different isolated combinations of costmap layers to be combined under one parent costmap instead of the current implementation which would indiscriminately combine all costmap layers together.
207
+
208
+
Iterative Target Selection for the Graceful Controller
In `PR #4795 <https://github.com/ros-navigation/navigation2/pull/4795>`_ the ``nav2_graceful_controller`` was updated to iteratively select motion targets. This is a large refactor which significantly improves the performance of the controller. The ``motion_target_dist`` parameter has been replaced by ``min_lookahead`` and ``max_lookahead`` parameters. Additional changes include:
212
+
213
+
* Improved defaults for ``k_phi``, ``k_delta``, ``beta`` parameters of the underlying control law.
214
+
* Automatic creation of orientations for the plan if they are missing.
215
+
* Addition of ``v_angular_min_in_place`` parameter to avoid the robot getting stuck while rotating due to mechanical limitations.
216
+
* ``final_rotation`` has been renamed ``prefer_final_rotation`` and the behavior has changed slightly.
0 commit comments