From 506a5cbca329f472183d2bb9532c4d1cf32cc684 Mon Sep 17 00:00:00 2001 From: Austin Greisman <92941098+austin-InDro@users.noreply.github.com> Date: Wed, 24 Aug 2022 11:55:32 -0400 Subject: [PATCH] Update README.md (#3147) Current example doesn't work with the updates. --- nav2_smac_planner/README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/nav2_smac_planner/README.md b/nav2_smac_planner/README.md index 0f58190b69..be522d7ca4 100644 --- a/nav2_smac_planner/README.md +++ b/nav2_smac_planner/README.md @@ -103,7 +103,7 @@ planner_server: use_sim_time: True GridBased: - plugin: "nav2_smac_planner/SmacPlanner" + plugin: "nav2_smac_planner/SmacPlannerHybrid" tolerance: 0.5 # tolerance for planning if unable to reach exact pose, in meters, for 2D node downsample_costmap: false # whether or not to downsample the map downsampling_factor: 1 # multiplier for the resolution of the costmap layer (e.g. 2 on a 5cm costmap would be 10cm) @@ -123,7 +123,7 @@ planner_server: cost_penalty: 2.0 # For Hybrid nodes: 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. retrospective_penalty: 0.025 # For Hybrid/Lattice nodes: penalty to prefer later maneuvers before earlier along the path. Saves search time since earlier nodes are not expanded until it is necessary. Must be >= 0.0 and <= 1.0 rotation_penalty: 5.0 # For Lattice node: Penalty to apply only to pure rotate in place commands when using minimum control sets containing rotate in place primitives. This should always be set sufficiently high to weight against this action unless strictly necessary for obstacle avoidance or there may be frequent discontinuities in the plan where it requests the robot to rotate in place to short-cut an otherwise smooth path for marginal path distance savings. - lookup_table_size: 20 # For Hybrid nodes: Size of the dubin/reeds-sheep distance window to cache, in meters. + lookup_table_size: 20.0 # For Hybrid nodes: Size of the dubin/reeds-sheep distance window to cache, in meters. cache_obstacle_heuristic: True # For Hybrid nodes: 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 # For Lattice nodes: Whether to expand state lattice graph in forward primitives or reverse as well, will double the branching factor at each step. smooth_path: True # For Lattice/Hybrid nodes: Whether or not to smooth the path, always true for 2D nodes.