From 5b468e145a84e6bc4aaa27b8cb828a18223724df Mon Sep 17 00:00:00 2001 From: Decwest Date: Thu, 30 Oct 2025 20:23:16 +0900 Subject: [PATCH 01/13] :memo: add dwpp description Signed-off-by: Decwest --- .../packages/configuring-regulated-pp.rst | 145 ++++++++++++++++-- plugins/index.rst | 2 +- 2 files changed, 129 insertions(+), 18 deletions(-) diff --git a/configuration/packages/configuring-regulated-pp.rst b/configuration/packages/configuring-regulated-pp.rst index a5e46556c..027b8a286 100644 --- a/configuration/packages/configuring-regulated-pp.rst +++ b/configuration/packages/configuring-regulated-pp.rst @@ -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 `_ algorithm. See the package's ``README`` for more complete information. @@ -22,7 +23,7 @@ If you use the Regulated Pure Pursuit Controller algorithm or software from this Regulated Pure Pursuit Parameters ********************************* -:desired_linear_vel: +:max_linear_vel: ============== =========================== Type Default @@ -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. + +:min_linear_vel: + + ============== =========================== + Type Default + -------------- --------------------------- + double 0.0 + ============== =========================== + + Description + The minimum linear velocity (m/s) to use. + +:max_angular_vel: + + ============== =========================== + Type Default + -------------- --------------------------- + double 1.0 + ============== =========================== + + Description + The maximum angular velocity (rad/s) to use. + +:min_angular_vel: + + ============== =========================== + Type Default + -------------- --------------------------- + double -1.0 + ============== =========================== + + Description + The minimum angular velocity (rad/s) to use. + +:max_linear_accel: + + ============== =========================== + Type Default + -------------- --------------------------- + double 0.5 + ============== =========================== + + Description + The maximum linear acceleration (m/s^2) to use. + +:max_linear_decel: + + ============== =========================== + Type Default + -------------- --------------------------- + double 0.5 + ============== =========================== + + Description + The maximum linear deceleration (m/s^2) to use. + +:max_angular_accel: + + ============== =========================== + Type Default + -------------- --------------------------- + double 1.0 + ============== =========================== + + Description + The maximum angular acceleration (rad/s^2) to use. + +:max_angular_decel: + + ============== =========================== + Type Default + -------------- --------------------------- + double 1.0 + ============== =========================== + + Description + The maximum angular deceleration (rad/s^2) to use. :lookahead_dist: @@ -198,6 +276,17 @@ Regulated Pure Pursuit Parameters Description A multiplier gain, which should be <= 1.0, used to further scale the speed when an obstacle is within ``cost_scaling_dist``. Lower value reduces speed more quickly. +:inflation_cost_scaling_factor: + + ============== ============================= + Type Default + -------------- ----------------------------- + double 3.0 + ============== ============================= + + Description + The value of `cost_scaling_factor` set for the inflation layer in the local costmap. The value should be exactly the same for accurately computing distance from obstacles using the inflated cell values + :regulated_linear_scaling_min_radius: ============== ============================= @@ -277,17 +366,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: ============== ============================= @@ -367,6 +445,30 @@ 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 true + ============== ============================= + + Description + Whether to use the Dynamic Window Pure Pursuit (DWPP) Algorithm. This algorithm computes optimal path tracking velocity commands under velocity and acceleration constraints. + +:velocity_feedback: + + ============== ============================= + Type Default + -------------- ----------------------------- + std::string "OPEN_LOOP" + ============== ============================= + + Description + How the current velocity is obtained during dynamic window computation. "OPEN_LOOP" uses the last commanded velocity (recommended). "CLOSED_LOOP" uses odometry velocity (may hinder proper acceleration/deceleration). + + + Example ******* .. code-block:: yaml @@ -392,7 +494,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.0 + max_angular_vel: 1.0 + min_angular_vel: -1.0 + max_linear_accel: 0.5 + max_linear_decel: 0.5 + max_angular_accel: 1.0 + max_angular_decel: 1.0 lookahead_dist: 0.6 min_lookahead_dist: 0.3 max_lookahead_dist: 0.9 @@ -406,16 +515,18 @@ Example max_allowed_time_to_collision_up_to_carrot: 1.0 use_regulated_linear_velocity_scaling: true use_fixed_curvature_lookahead: false - curvature_lookahead_dist: 0.25 + curvature_lookahead_dist: 0.6 use_cost_regulated_linear_velocity_scaling: false + interpolate_curvature_after_goal: false cost_scaling_dist: 0.3 cost_scaling_gain: 1.0 + inflation_cost_scaling_factor: 3.0 regulated_linear_scaling_min_radius: 0.9 regulated_linear_scaling_min_speed: 0.25 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: true + velocity_feedback: "OPEN_LOOP" diff --git a/plugins/index.rst b/plugins/index.rst index 5366840ac..45d8a8ec1 100644 --- a/plugins/index.rst +++ b/plugins/index.rst @@ -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, | From d7a2abdebf566157705accbb57fefc262e860ac2 Mon Sep 17 00:00:00 2001 From: Decwest Date: Thu, 27 Nov 2025 21:04:18 +0900 Subject: [PATCH 02/13] :memo: delete velocity feedback parameter Signed-off-by: Decwest --- .../packages/configuring-regulated-pp.rst | 30 ++----------------- 1 file changed, 3 insertions(+), 27 deletions(-) diff --git a/configuration/packages/configuring-regulated-pp.rst b/configuration/packages/configuring-regulated-pp.rst index 027b8a286..cf9d956fe 100644 --- a/configuration/packages/configuring-regulated-pp.rst +++ b/configuration/packages/configuring-regulated-pp.rst @@ -276,17 +276,6 @@ Regulated Pure Pursuit Parameters Description A multiplier gain, which should be <= 1.0, used to further scale the speed when an obstacle is within ``cost_scaling_dist``. Lower value reduces speed more quickly. -:inflation_cost_scaling_factor: - - ============== ============================= - Type Default - -------------- ----------------------------- - double 3.0 - ============== ============================= - - Description - The value of `cost_scaling_factor` set for the inflation layer in the local costmap. The value should be exactly the same for accurately computing distance from obstacles using the inflated cell values - :regulated_linear_scaling_min_radius: ============== ============================= @@ -456,18 +445,6 @@ Regulated Pure Pursuit Parameters Description Whether to use the Dynamic Window Pure Pursuit (DWPP) Algorithm. This algorithm computes optimal path tracking velocity commands under velocity and acceleration constraints. -:velocity_feedback: - - ============== ============================= - Type Default - -------------- ----------------------------- - std::string "OPEN_LOOP" - ============== ============================= - - Description - How the current velocity is obtained during dynamic window computation. "OPEN_LOOP" uses the last commanded velocity (recommended). "CLOSED_LOOP" uses odometry velocity (may hinder proper acceleration/deceleration). - - Example ******* @@ -515,12 +492,10 @@ Example max_allowed_time_to_collision_up_to_carrot: 1.0 use_regulated_linear_velocity_scaling: true use_fixed_curvature_lookahead: false - curvature_lookahead_dist: 0.6 + curvature_lookahead_dist: 0.25 use_cost_regulated_linear_velocity_scaling: false - interpolate_curvature_after_goal: false cost_scaling_dist: 0.3 cost_scaling_gain: 1.0 - inflation_cost_scaling_factor: 3.0 regulated_linear_scaling_min_radius: 0.9 regulated_linear_scaling_min_speed: 0.25 use_rotate_to_heading: true @@ -528,5 +503,6 @@ Example rotate_to_heading_min_angle: 0.785 max_robot_pose_search_dist: 10.0 min_distance_to_obstacle: 0.0 + stateful: true use_dynamic_window: true - velocity_feedback: "OPEN_LOOP" + From aa1ad36c8d17fde931d5a1c4035da2a0fa526908 Mon Sep 17 00:00:00 2001 From: Decwest Date: Thu, 27 Nov 2025 21:13:06 +0900 Subject: [PATCH 03/13] :memo: fix default value Signed-off-by: Decwest --- .../packages/configuring-regulated-pp.rst | 44 +++++++++---------- 1 file changed, 22 insertions(+), 22 deletions(-) diff --git a/configuration/packages/configuring-regulated-pp.rst b/configuration/packages/configuring-regulated-pp.rst index cf9d956fe..5dcc07562 100644 --- a/configuration/packages/configuring-regulated-pp.rst +++ b/configuration/packages/configuring-regulated-pp.rst @@ -39,62 +39,62 @@ Regulated Pure Pursuit Parameters ============== =========================== Type Default -------------- --------------------------- - double 0.0 + double -0.5 ============== =========================== Description - The minimum linear velocity (m/s) to use. + The minimum linear velocity (m/s) used when `use_dynamic_window` is `true`. :max_angular_vel: ============== =========================== Type Default -------------- --------------------------- - double 1.0 + double 2.5 ============== =========================== Description - The maximum angular velocity (rad/s) to use. + The maximum angular velocity (rad/s) used when `use_dynamic_window` is `true`. :min_angular_vel: ============== =========================== Type Default -------------- --------------------------- - double -1.0 + double -2.5 ============== =========================== Description - The minimum angular velocity (rad/s) to use. + The minimum angular velocity (rad/s) used when `use_dynamic_window` is `true`. :max_linear_accel: ============== =========================== Type Default -------------- --------------------------- - double 0.5 + double 2.5 ============== =========================== Description - The maximum linear acceleration (m/s^2) to use. + The maximum linear acceleration (m/s^2) used when `use_dynamic_window` is `true`. :max_linear_decel: ============== =========================== Type Default -------------- --------------------------- - double 0.5 + double 2.5 ============== =========================== Description - The maximum linear deceleration (m/s^2) to use. + The maximum linear deceleration (m/s^2) used when `use_dynamic_window` is `true`. :max_angular_accel: ============== =========================== Type Default -------------- --------------------------- - double 1.0 + double 3.2 ============== =========================== Description @@ -105,11 +105,11 @@ Regulated Pure Pursuit Parameters ============== =========================== Type Default -------------- --------------------------- - double 1.0 + double 3.2 ============== =========================== Description - The maximum angular deceleration (rad/s^2) to use. + The maximum angular deceleration (rad/s^2) used when `use_dynamic_window` is `true`. :lookahead_dist: @@ -439,7 +439,7 @@ Regulated Pure Pursuit Parameters ============== ============================= Type Default -------------- ----------------------------- - bool true + bool false ============== ============================= Description @@ -472,13 +472,13 @@ Example FollowPath: plugin: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController" max_linear_vel: 0.5 - min_linear_vel: 0.0 - max_angular_vel: 1.0 - min_angular_vel: -1.0 - max_linear_accel: 0.5 - max_linear_decel: 0.5 - max_angular_accel: 1.0 - max_angular_decel: 1.0 + 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 @@ -504,5 +504,5 @@ Example max_robot_pose_search_dist: 10.0 min_distance_to_obstacle: 0.0 stateful: true - use_dynamic_window: true + use_dynamic_window: false From fc06687062136375cacd0821961f1ab630d81876 Mon Sep 17 00:00:00 2001 From: Decwest Date: Fri, 12 Dec 2025 01:10:02 +0900 Subject: [PATCH 04/13] :memo: add migration guide about desired_linear_vel Signed-off-by: Decwest --- configuration/packages/configuring-regulated-pp.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/configuration/packages/configuring-regulated-pp.rst b/configuration/packages/configuring-regulated-pp.rst index 5dcc07562..9425d6eba 100644 --- a/configuration/packages/configuring-regulated-pp.rst +++ b/configuration/packages/configuring-regulated-pp.rst @@ -32,7 +32,7 @@ Regulated Pure Pursuit Parameters ============== =========================== Description - The maximum linear velocity (m/s) to use. + The maximum linear velocity (m/s) to use. Previously `desired_linear_vel` :min_linear_vel: From ae30eed80e6b8741a3a772242c549f1f897ea0d6 Mon Sep 17 00:00:00 2001 From: Decwest Date: Fri, 12 Dec 2025 01:20:09 +0900 Subject: [PATCH 05/13] :zap: add paper title Signed-off-by: Decwest --- configuration/packages/configuring-regulated-pp.rst | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/configuration/packages/configuring-regulated-pp.rst b/configuration/packages/configuring-regulated-pp.rst index 9425d6eba..68200c781 100644 --- a/configuration/packages/configuring-regulated-pp.rst +++ b/configuration/packages/configuring-regulated-pp.rst @@ -443,7 +443,8 @@ Regulated Pure Pursuit Parameters ============== ============================= Description - Whether to use the Dynamic Window Pure Pursuit (DWPP) Algorithm. This algorithm computes optimal path tracking velocity commands under velocity and acceleration constraints. + 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 From 75660837488aa8a6939602dba53a7e66e1d08db0 Mon Sep 17 00:00:00 2001 From: Decwest Date: Sun, 14 Dec 2025 18:37:02 +0900 Subject: [PATCH 06/13] :bug: fix pre-commit issue Signed-off-by: Decwest --- configuration/packages/configuring-regulated-pp.rst | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/configuration/packages/configuring-regulated-pp.rst b/configuration/packages/configuring-regulated-pp.rst index 68200c781..2db15a425 100644 --- a/configuration/packages/configuring-regulated-pp.rst +++ b/configuration/packages/configuring-regulated-pp.rst @@ -443,8 +443,8 @@ Regulated Pure Pursuit Parameters ============== ============================= 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. + 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 @@ -505,5 +505,4 @@ Example max_robot_pose_search_dist: 10.0 min_distance_to_obstacle: 0.0 stateful: true - use_dynamic_window: false - + use_dynamic_window: false \ No newline at end of file From a7ca956a21617a11154a30dacfef0b8bca3e9245 Mon Sep 17 00:00:00 2001 From: Decwest Date: Sun, 14 Dec 2025 18:40:46 +0900 Subject: [PATCH 07/13] :adhesive_bandage: add new line Signed-off-by: Decwest --- configuration/packages/configuring-regulated-pp.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/configuration/packages/configuring-regulated-pp.rst b/configuration/packages/configuring-regulated-pp.rst index 2db15a425..6d085aa88 100644 --- a/configuration/packages/configuring-regulated-pp.rst +++ b/configuration/packages/configuring-regulated-pp.rst @@ -505,4 +505,4 @@ Example max_robot_pose_search_dist: 10.0 min_distance_to_obstacle: 0.0 stateful: true - use_dynamic_window: false \ No newline at end of file + use_dynamic_window: false From 494fce8937b2637a70f84141ea823afa7fb31003 Mon Sep 17 00:00:00 2001 From: Decwest Date: Sat, 20 Dec 2025 21:31:26 +0900 Subject: [PATCH 08/13] :zap: add DWPP description to migration guide Signed-off-by: Decwest --- migration/Kilted.rst | 111 +++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 111 insertions(+) diff --git a/migration/Kilted.rst b/migration/Kilted.rst index d3d16245f..0112b2247 100644 --- a/migration/Kilted.rst +++ b/migration/Kilted.rst @@ -562,3 +562,114 @@ The UI workflow is now organized into two primary navigation modes: :align: center GIF above shows how multiple-goal navigation is configured mixing visual goal setting and file loading for NavigateThroughPoses and Waypoint Following actions. + +Add Dynamic Window Pure Pursuit Option to Regulated Pure Pursuit Controller +--------------------------------------------------------------------------- + +In `PR #5783 `_, an option was added to enable the Dynamic Window Pure Pursuit (DWPP) algorithm in the Regulated Pure Pursuit controller. When this option is enabled, velocity and acceleration constraints are explicitly considered when computing command velocities. + +- Fumiya Ohnishi and Masaki Takahashi, “Dynamic Window Pure Pursuit for Robot Path Tracking Considering Velocity and Acceleration Constraints”, Proceedings of the 19th International Conference on Intelligent Autonomous Systems, Genoa, Italy, 2025. + +The following parameters are introduced or updated for this feature. + +:use_dynamic_window (new): + + ============== ============================= + Type Default + -------------- ----------------------------- + bool false + ============== ============================= + + Description + Whether to enable the Dynamic Window Pure Pursuit (DWPP) algorithm. + +:max_linear_vel (renamed): + + ============== =========================== + Type Default + -------------- --------------------------- + double 0.5 + ============== =========================== + + Description + The maximum linear velocity (m/s) to use. **Previously named `desired_linear_vel`** + +:min_linear_vel (new): + + ============== =========================== + Type Default + -------------- --------------------------- + double -0.5 + ============== =========================== + + Description + The minimum linear velocity (m/s) used when `use_dynamic_window` is `true`. + +:max_angular_vel (new): + + ============== =========================== + Type Default + -------------- --------------------------- + double 2.5 + ============== =========================== + + Description + The maximum angular velocity (rad/s) used when `use_dynamic_window` is `true`. + +:min_angular_vel (new): + + ============== =========================== + Type Default + -------------- --------------------------- + double -2.5 + ============== =========================== + + Description + The minimum angular velocity (rad/s) used when `use_dynamic_window` is `true`. + +:max_linear_accel (new): + + ============== =========================== + Type Default + -------------- --------------------------- + double 2.5 + ============== =========================== + + Description + The maximum linear acceleration (m/s^2) used when `use_dynamic_window` is `true`. + +:max_linear_decel (new): + + ============== =========================== + 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 (new): + + ============== =========================== + Type Default + -------------- --------------------------- + double 3.2 + ============== =========================== + + Description + The maximum angular deceleration (rad/s^2) used when `use_dynamic_window` is `true`. + +**Note:** The velocity smoother clips velocity commands produced by this controller according to its own velocity and acceleration limits before publishing `cmd_vel`. +Therefore, the velocity smoother parameters `max_velocity`, `min_velocity`, `max_accel`, and `max_decel` must be set to values consistent with, or greater than, the corresponding velocity, acceleration, and deceleration parameters of this controller. From 2cb2c3166867ccb2f66c1a93dbef8014300eb3ca Mon Sep 17 00:00:00 2001 From: Decwest Date: Wed, 24 Dec 2025 00:42:54 +0900 Subject: [PATCH 09/13] :recycle: modify max_decel to negative values Signed-off-by: Decwest --- configuration/packages/configuring-regulated-pp.rst | 8 ++++---- migration/Kilted.rst | 4 ++-- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/configuration/packages/configuring-regulated-pp.rst b/configuration/packages/configuring-regulated-pp.rst index 6d085aa88..ca633906f 100644 --- a/configuration/packages/configuring-regulated-pp.rst +++ b/configuration/packages/configuring-regulated-pp.rst @@ -83,7 +83,7 @@ Regulated Pure Pursuit Parameters ============== =========================== Type Default -------------- --------------------------- - double 2.5 + double -2.5 ============== =========================== Description @@ -105,7 +105,7 @@ Regulated Pure Pursuit Parameters ============== =========================== Type Default -------------- --------------------------- - double 3.2 + double -3.2 ============== =========================== Description @@ -477,9 +477,9 @@ Example max_angular_vel: 2.5 min_angular_vel: -2.5 max_linear_accel: 2.5 - max_linear_decel: 2.5 + max_linear_decel: -2.5 max_angular_accel: 3.2 - max_angular_decel: 3.2 + max_angular_decel: -3.2 lookahead_dist: 0.6 min_lookahead_dist: 0.3 max_lookahead_dist: 0.9 diff --git a/migration/Kilted.rst b/migration/Kilted.rst index 0112b2247..f48fb6174 100644 --- a/migration/Kilted.rst +++ b/migration/Kilted.rst @@ -643,7 +643,7 @@ The following parameters are introduced or updated for this feature. ============== =========================== Type Default -------------- --------------------------- - double 2.5 + double -2.5 ============== =========================== Description @@ -665,7 +665,7 @@ The following parameters are introduced or updated for this feature. ============== =========================== Type Default -------------- --------------------------- - double 3.2 + double -3.2 ============== =========================== Description From 629976372238229ad4e16fa601391fedf63f1d05 Mon Sep 17 00:00:00 2001 From: Fumiya Ohnishi Date: Sat, 3 Jan 2026 20:15:08 +0900 Subject: [PATCH 10/13] Update migration/Kilted.rst Co-authored-by: Steve Macenski Signed-off-by: Fumiya Ohnishi --- migration/Kilted.rst | 13 ------------- 1 file changed, 13 deletions(-) diff --git a/migration/Kilted.rst b/migration/Kilted.rst index 651ccc7b7..fa10f6483 100644 --- a/migration/Kilted.rst +++ b/migration/Kilted.rst @@ -570,19 +570,6 @@ In `PR #5783 `_, an opt - Fumiya Ohnishi and Masaki Takahashi, “Dynamic Window Pure Pursuit for Robot Path Tracking Considering Velocity and Acceleration Constraints”, Proceedings of the 19th International Conference on Intelligent Autonomous Systems, Genoa, Italy, 2025. -The following parameters are introduced or updated for this feature. - -:use_dynamic_window (new): - - ============== ============================= - Type Default - -------------- ----------------------------- - bool false - ============== ============================= - - Description - Whether to enable the Dynamic Window Pure Pursuit (DWPP) algorithm. - :max_linear_vel (renamed): ============== =========================== From 84f55aaaa7ce4b6ce441b786c9cd9144450c1128 Mon Sep 17 00:00:00 2001 From: Fumiya Ohnishi Date: Sat, 3 Jan 2026 20:15:29 +0900 Subject: [PATCH 11/13] Update migration/Kilted.rst Co-authored-by: Steve Macenski Signed-off-by: Fumiya Ohnishi --- migration/Kilted.rst | 76 -------------------------------------------- 1 file changed, 76 deletions(-) diff --git a/migration/Kilted.rst b/migration/Kilted.rst index fa10f6483..8d20e1f20 100644 --- a/migration/Kilted.rst +++ b/migration/Kilted.rst @@ -581,82 +581,6 @@ In `PR #5783 `_, an opt Description The maximum linear velocity (m/s) to use. **Previously named `desired_linear_vel`** -:min_linear_vel (new): - - ============== =========================== - Type Default - -------------- --------------------------- - double -0.5 - ============== =========================== - - Description - The minimum linear velocity (m/s) used when `use_dynamic_window` is `true`. - -:max_angular_vel (new): - - ============== =========================== - Type Default - -------------- --------------------------- - double 2.5 - ============== =========================== - - Description - The maximum angular velocity (rad/s) used when `use_dynamic_window` is `true`. - -:min_angular_vel (new): - - ============== =========================== - Type Default - -------------- --------------------------- - double -2.5 - ============== =========================== - - Description - The minimum angular velocity (rad/s) used when `use_dynamic_window` is `true`. - -:max_linear_accel (new): - - ============== =========================== - Type Default - -------------- --------------------------- - double 2.5 - ============== =========================== - - Description - The maximum linear acceleration (m/s^2) used when `use_dynamic_window` is `true`. - -:max_linear_decel (new): - - ============== =========================== - 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 (new): - - ============== =========================== - Type Default - -------------- --------------------------- - double -3.2 - ============== =========================== - - Description - The maximum angular deceleration (rad/s^2) used when `use_dynamic_window` is `true`. **Note:** The velocity smoother clips velocity commands produced by this controller according to its own velocity and acceleration limits before publishing `cmd_vel`. Therefore, the velocity smoother parameters `max_velocity`, `min_velocity`, `max_accel`, and `max_decel` must be set to values consistent with, or greater than, the corresponding velocity, acceleration, and deceleration parameters of this controller. From f7104a387ef13a547e2b1d06727ca89af6d565f9 Mon Sep 17 00:00:00 2001 From: Fumiya Ohnishi Date: Sat, 3 Jan 2026 20:16:40 +0900 Subject: [PATCH 12/13] Update migration/Kilted.rst Co-authored-by: Steve Macenski Signed-off-by: Fumiya Ohnishi --- migration/Kilted.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/migration/Kilted.rst b/migration/Kilted.rst index 8d20e1f20..4faa1d3a4 100644 --- a/migration/Kilted.rst +++ b/migration/Kilted.rst @@ -566,7 +566,7 @@ GIF above shows how multiple-goal navigation is configured mixing visual goal se Add Dynamic Window Pure Pursuit Option to Regulated Pure Pursuit Controller --------------------------------------------------------------------------- -In `PR #5783 `_, an option was added to enable the Dynamic Window Pure Pursuit (DWPP) algorithm in the Regulated Pure Pursuit controller. When this option is enabled, velocity and acceleration constraints are explicitly considered when computing command velocities. +In `PR #5783 `_, an option was added to enable the Dynamic Window Pure Pursuit (DWPP) algorithm in the Regulated Pure Pursuit controller. When this option is enabled, velocity and acceleration constraints are explicitly considered when computing command velocities. See the Configuration Guide for the new parameters associated with this feature. - Fumiya Ohnishi and Masaki Takahashi, “Dynamic Window Pure Pursuit for Robot Path Tracking Considering Velocity and Acceleration Constraints”, Proceedings of the 19th International Conference on Intelligent Autonomous Systems, Genoa, Italy, 2025. From 153440d5ca41f46eb0b41e01a894af0dd1dd48ce Mon Sep 17 00:00:00 2001 From: Decwest Date: Sat, 3 Jan 2026 20:27:56 +0900 Subject: [PATCH 13/13] :zap: modify documents related to dwpp Signed-off-by: Decwest --- configuration/packages/configuring-regulated-pp.rst | 1 - migration/Kilted.rst | 3 +++ plugins/index.rst | 2 +- 3 files changed, 4 insertions(+), 2 deletions(-) diff --git a/configuration/packages/configuring-regulated-pp.rst b/configuration/packages/configuring-regulated-pp.rst index e5052c70b..b1d835e42 100644 --- a/configuration/packages/configuring-regulated-pp.rst +++ b/configuration/packages/configuring-regulated-pp.rst @@ -479,7 +479,6 @@ Example use_rotate_to_heading: true allow_reversing: false rotate_to_heading_min_angle: 0.785 - max_robot_pose_search_dist: 10.0 min_distance_to_obstacle: 0.0 stateful: true use_dynamic_window: false diff --git a/migration/Kilted.rst b/migration/Kilted.rst index 4faa1d3a4..59f10d01e 100644 --- a/migration/Kilted.rst +++ b/migration/Kilted.rst @@ -570,6 +570,8 @@ In `PR #5783 `_, an opt - Fumiya Ohnishi and Masaki Takahashi, “Dynamic Window Pure Pursuit for Robot Path Tracking Considering Velocity and Acceleration Constraints”, Proceedings of the 19th International Conference on Intelligent Autonomous Systems, Genoa, Italy, 2025. +The following parameters are updated for this feature. + :max_linear_vel (renamed): ============== =========================== @@ -584,6 +586,7 @@ In `PR #5783 `_, an opt **Note:** The velocity smoother clips velocity commands produced by this controller according to its own velocity and acceleration limits before publishing `cmd_vel`. Therefore, the velocity smoother parameters `max_velocity`, `min_velocity`, `max_accel`, and `max_decel` must be set to values consistent with, or greater than, the corresponding velocity, acceleration, and deceleration parameters of this controller. + Bond Heartbeat Period Default Value Change ------------------------------------------ diff --git a/plugins/index.rst b/plugins/index.rst index 7a01c7641..7bf80960b 100644 --- a/plugins/index.rst +++ b/plugins/index.rst @@ -122,7 +122,7 @@ Controllers | | | holonomic robots. | Differential | +--------------------------------+-----------------------+------------------------------------+-----------------------+ | `Regulated Pure Pursuit`_ | Steve Macenski | A service / industrial robot | **Ackermann**, Legged,| -| | Fumiya Ohnishi | variation on the pure pursuit | Differential | +| | | variation on the pure pursuit | Differential | | | | algorithm with adaptive features. | | +--------------------------------+-----------------------+------------------------------------+-----------------------+ | `MPPI Controller`_ | Steve Macenski | A predictive MPC controller with | Differential, Omni, |