Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
117 changes: 102 additions & 15 deletions configuration/packages/configuring-regulated-pp.rst
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ It regulates the linear velocities by curvature of the path to help reduce overs
It also better follows paths than any other variation currently available of Pure Pursuit.
It also has heuristics to slow in proximity to other obstacles so that you can slow the robot automatically when nearby potential collisions.
It also implements the Adaptive lookahead point features to be scaled by velocities to enable more stable behavior in a larger range of translational speeds.
It also considers the robot’s velocity and acceleration constraints during velocity command computation using `Dynamic Window Pure Pursuit <https://github.com/Decwest/nav2_dynamic_window_pure_pursuit_controller/blob/main/algorithm.md>`_ algorithm.

See the package's ``README`` for more complete information.

Expand All @@ -22,7 +23,7 @@ If you use the Regulated Pure Pursuit Controller algorithm or software from this
Regulated Pure Pursuit Parameters
*********************************

:desired_linear_vel:
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In the migration guide, we need to mention this change. I'd also put in the description a note that it is desired_linear_vel in Kilted and older.

:max_linear_vel:

============== ===========================
Type Default
Expand All @@ -31,7 +32,84 @@ Regulated Pure Pursuit Parameters
============== ===========================

Description
The desired maximum linear velocity (m/s) to use.
The maximum linear velocity (m/s) to use. Previously `desired_linear_vel`

:min_linear_vel:

============== ===========================
Type Default
-------------- ---------------------------
double -0.5
============== ===========================

Description
The minimum linear velocity (m/s) used when `use_dynamic_window` is `true`.

:max_angular_vel:

============== ===========================
Type Default
-------------- ---------------------------
double 2.5
============== ===========================

Description
The maximum angular velocity (rad/s) used when `use_dynamic_window` is `true`.

:min_angular_vel:

============== ===========================
Type Default
-------------- ---------------------------
double -2.5
============== ===========================

Description
The minimum angular velocity (rad/s) used when `use_dynamic_window` is `true`.

:max_linear_accel:

============== ===========================
Type Default
-------------- ---------------------------
double 2.5
============== ===========================

Description
The maximum linear acceleration (m/s^2) used when `use_dynamic_window` is `true`.

:max_linear_decel:

============== ===========================
Type Default
-------------- ---------------------------
double 2.5
============== ===========================

Description
The maximum linear deceleration (m/s^2) used when `use_dynamic_window` is `true`.

:max_angular_accel:

============== ===========================
Type Default
-------------- ---------------------------
double 3.2
============== ===========================

Description
The maximum angular acceleration (rad/s^2) to use.

:max_angular_decel:

============== ===========================
Type Default
-------------- ---------------------------
double 3.2
============== ===========================

Description
The maximum angular deceleration (rad/s^2) used when `use_dynamic_window` is `true`.

:lookahead_dist:

Expand Down Expand Up @@ -277,17 +355,6 @@ Regulated Pure Pursuit Parameters
Description
The difference in the path orientation and the starting robot orientation (radians) to trigger a rotate in place, if ``use_rotate_to_heading`` is ``true``.

:max_angular_accel:

============== =============================
Type Default
-------------- -----------------------------
double 3.2
============== =============================

Description
Maximum allowable angular acceleration (rad/s/s) while rotating to heading, if ``use_rotate_to_heading`` is ``true``.

:use_cancel_deceleration:

============== =============================
Expand Down Expand Up @@ -367,6 +434,19 @@ Regulated Pure Pursuit Parameters
Description
The shortest distance at which the robot is allowed to be from an obstacle along its trajectory. Set <= 0.0 to disable. It is limited to maximum distance of lookahead distance selected.

:use_dynamic_window:

============== =============================
Type Default
-------------- -----------------------------
bool false
============== =============================

Description
Whether to use the Dynamic Window Pure Pursuit (DWPP) Algorithm. This algorithm computes optimal path tracking velocity commands under velocity and acceleration constraints.
Fumiya Ohnishi and Masaki Takahashi, "Dynamic Window Pure Pursuit for Robot Path Tracking Considering Velocity and Acceleration Constraints", the 19th International Conference on Intelligent Autonomous Systems (IAS-19), 2025.


Example
*******
.. code-block:: yaml
Expand All @@ -392,7 +472,14 @@ Example
stateful: True
FollowPath:
plugin: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController"
desired_linear_vel: 0.5
max_linear_vel: 0.5
min_linear_vel: -0.5
max_angular_vel: 2.5
min_angular_vel: -2.5
max_linear_accel: 2.5
max_linear_decel: 2.5
max_angular_accel: 3.2
max_angular_decel: 3.2
lookahead_dist: 0.6
min_lookahead_dist: 0.3
max_lookahead_dist: 0.9
Expand All @@ -415,7 +502,7 @@ Example
use_rotate_to_heading: true
allow_reversing: false
rotate_to_heading_min_angle: 0.785
max_angular_accel: 3.2
max_robot_pose_search_dist: 10.0
min_distance_to_obstacle: 0.0
stateful: true
use_dynamic_window: false
2 changes: 1 addition & 1 deletion plugins/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ Controllers
| | | holonomic robots. | Differential |
+--------------------------------+-----------------------+------------------------------------+-----------------------+
| `Regulated Pure Pursuit`_ | Steve Macenski | A service / industrial robot | **Ackermann**, Legged,|
| | | variation on the pure pursuit | Differential |
| | Fumiya Ohnishi | variation on the pure pursuit | Differential |
| | | algorithm with adaptive features. | |
+--------------------------------+-----------------------+------------------------------------+-----------------------+
| `MPPI Controller`_ | Steve Macenski | A predictive MPC controller with | Differential, Omni, |
Expand Down
Loading