From 4ff97692a1aae0f0d640c1d8724e3f654dae867c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bj=C3=B6rn=20Ellensohn?= Date: Thu, 7 Sep 2023 11:17:29 +0200 Subject: [PATCH] update --- config/nav2_params.yaml | 48 +++++++++++++++++++++++++++++++++++------ 1 file changed, 41 insertions(+), 7 deletions(-) diff --git a/config/nav2_params.yaml b/config/nav2_params.yaml index c799e73..5c3dc19 100644 --- a/config/nav2_params.yaml +++ b/config/nav2_params.yaml @@ -513,17 +513,51 @@ map_saver: occupied_thresh_default: 0.65 map_subscribe_transient_local: True +# planner_server: +# ros__parameters: +# expected_planner_frequency: 20.0 +# use_sim_time: False +# planner_plugins: ["GridBased"] +# GridBased: +# plugin: "nav2_navfn_planner/NavfnPlanner" +# #plugin: "nav2_smac_planner/SmacPlanner2D" +# tolerance: 0.5 +# #use_astar: false +# allow_unknown: true + +# trying smac lattice planner planner_server: ros__parameters: - expected_planner_frequency: 20.0 - use_sim_time: False planner_plugins: ["GridBased"] + use_sim_time: True + GridBased: - plugin: "nav2_navfn_planner/NavfnPlanner" - #plugin: "nav2_smac_planner/SmacPlanner2D" - tolerance: 0.5 - #use_astar: false - allow_unknown: true + 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 + lattice_filepath: "" # The filepath to the state lattice graph + 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). + 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 smoother_server: ros__parameters: