From fc7695d726f16fb94fccc260e4aa4b0bbdd674ca Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Thu, 1 Feb 2024 10:57:36 -0800 Subject: [PATCH] Revert accidental inclusion of Smac Lattice as default (#4089) Signed-off-by: Steve Macenski Signed-off-by: enricosutera --- nav2_bringup/params/nav2_params.yaml | 32 +++++----------------------- 1 file changed, 5 insertions(+), 27 deletions(-) diff --git a/nav2_bringup/params/nav2_params.yaml b/nav2_bringup/params/nav2_params.yaml index 0e3427a17b..5f0e6e775d 100644 --- a/nav2_bringup/params/nav2_params.yaml +++ b/nav2_bringup/params/nav2_params.yaml @@ -277,34 +277,12 @@ planner_server: ros__parameters: expected_planner_frequency: 20.0 planner_plugins: ["GridBased"] - GridBased: - plugin: "nav2_smac_planner/SmacPlannerLattice" - allow_unknown: true # Allow traveling in unknown space - tolerance: 0.25 # dist-to-goal heuristic cost (distance) for valid tolerance endpoints if exact goal cannot be found. - max_iterations: 1000000 # Maximum total iterations to search for before failing (in case unreachable), set to -1 to disable - max_on_approach_iterations: 1000 # Maximum number of iterations after within tolerances to continue to try to find exact solution - max_planning_time: 5.0 # Max time in s for planner to plan, smooth - analytic_expansion_ratio: 3.5 # The ratio to attempt analytic expansions during search for final approach. - analytic_expansion_max_length: 3.0 # For Hybrid/Lattice nodes: The maximum length of the analytic expansion to be considered valid to prevent unsafe shortcutting - reverse_penalty: 2.0 # Penalty to apply if motion is reversing, must be => 1 - change_penalty: 0.05 # Penalty to apply if motion is changing directions (L to R), must be >= 0 - non_straight_penalty: 1.05 # Penalty to apply if motion is non-straight, must be => 1 - cost_penalty: 2.0 # Penalty to apply to higher cost areas when adding into the obstacle map dynamic programming distance expansion heuristic. This drives the robot more towards the center of passages. A value between 1.3 - 3.5 is reasonable. - rotation_penalty: 5.0 # Penalty to apply to in-place rotations, if minimum control set contains them - retrospective_penalty: 0.015 - lookup_table_size: 20.0 # Size of the dubin/reeds-sheep distance window to cache, in meters. - cache_obstacle_heuristic: false # Cache the obstacle map dynamic programming distance expansion heuristic between subsiquent replannings of the same goal location. Dramatically speeds up replanning performance (40x) if costmap is largely static. - allow_reverse_expansion: false # If true, allows the robot to use the primitives to expand in the mirrored opposite direction of the current robot's orientation (to reverse). - debug_visualizations: true - smooth_path: True # If true, does a simple and quick smoothing post-processing to the path - smoother: - max_iterations: 1000 - w_smooth: 0.3 - w_data: 0.2 - tolerance: 1.0e-10 - do_refinement: true - refinement_num: 2 + plugin: "nav2_navfn_planner/NavfnPlanner" + tolerance: 0.5 + use_astar: false + allow_unknown: true + smoother_server: ros__parameters: smoother_plugins: ["simple_smoother"]