mirror of
https://github.com/bjoernellens1/cps_rmp220_support.git
synced 2024-11-23 15:45:08 +00:00
update
This commit is contained in:
parent
76e77dcc4a
commit
aa2aed6e02
@ -576,58 +576,58 @@ 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 hybrid planner
|
||||
planner_server:
|
||||
ros__parameters:
|
||||
expected_planner_frequency: 20.0
|
||||
use_sim_time: False
|
||||
planner_plugins: ["GridBased"]
|
||||
use_sim_time: True
|
||||
|
||||
GridBased:
|
||||
plugin: "nav2_smac_planner/SmacPlannerHybrid"
|
||||
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)
|
||||
tolerance: 0.25 # dist-to-goal heuristic cost (distance) for valid tolerance endpoints if exact goal cannot be found.
|
||||
allow_unknown: true # allow traveling in unknown space
|
||||
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
|
||||
motion_model_for_search: "DUBIN" #was DUBIN # Hybrid-A* Dubin, Redds-Shepp
|
||||
angle_quantization_bins: 72 # Number of angle bins for search
|
||||
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
|
||||
minimum_turning_radius: 0.10 # was 0.40 # minimum turning radius in m of path / vehicle
|
||||
reverse_penalty: 1.3 # was 2.0 # Penalty to apply if motion is reversing, must be => 1
|
||||
change_penalty: 0.5 # was 0.0 # Penalty to apply if motion is changing directions (L to R), must be >= 0
|
||||
non_straight_penalty: 1.2 # Penalty to apply if motion is non-straight, must be => 1
|
||||
cost_penalty: 3.0 # was 2 before # 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.015
|
||||
lookup_table_size: 20.0 # Size of the dubin/reeds-sheep distance window to cache, in meters.
|
||||
cache_obstacle_heuristic: true #was fasle # 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.
|
||||
debug_visualizations: false # For Hybrid nodes: Whether to publish expansions on the /expansions topic as an array of poses (the orientation has no meaning) and the path's footprints on the /planned_footprints topic. WARNING: heavy to compute and to display, for debug only as it degrades the performance.
|
||||
use_quadratic_cost_penalty: False
|
||||
downsample_obstacle_heuristic: True
|
||||
allow_primitive_interpolation: False
|
||||
smooth_path: True # If true, does a simple and quick smoothing post-processing to the path
|
||||
plugin: "nav2_navfn_planner/NavfnPlanner"
|
||||
#plugin: "nav2_smac_planner/SmacPlanner2D"
|
||||
tolerance: 0.5
|
||||
#use_astar: false
|
||||
allow_unknown: true
|
||||
|
||||
smoother:
|
||||
max_iterations: 1000
|
||||
w_smooth: 0.3
|
||||
w_data: 0.2
|
||||
tolerance: 1.0e-10
|
||||
do_refinement: true
|
||||
refinement_num: 2
|
||||
# trying smac hybrid planner
|
||||
# planner_server:
|
||||
# ros__parameters:
|
||||
# planner_plugins: ["GridBased"]
|
||||
# use_sim_time: True
|
||||
|
||||
# GridBased:
|
||||
# plugin: "nav2_smac_planner/SmacPlannerHybrid"
|
||||
# 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)
|
||||
# tolerance: 0.25 # dist-to-goal heuristic cost (distance) for valid tolerance endpoints if exact goal cannot be found.
|
||||
# allow_unknown: true # allow traveling in unknown space
|
||||
# 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
|
||||
# motion_model_for_search: "DUBIN" #was DUBIN # Hybrid-A* Dubin, Redds-Shepp
|
||||
# angle_quantization_bins: 72 # Number of angle bins for search
|
||||
# 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
|
||||
# minimum_turning_radius: 0.10 # was 0.40 # minimum turning radius in m of path / vehicle
|
||||
# reverse_penalty: 1.3 # was 2.0 # Penalty to apply if motion is reversing, must be => 1
|
||||
# change_penalty: 0.5 # was 0.0 # Penalty to apply if motion is changing directions (L to R), must be >= 0
|
||||
# non_straight_penalty: 1.2 # Penalty to apply if motion is non-straight, must be => 1
|
||||
# cost_penalty: 3.0 # was 2 before # 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.015
|
||||
# lookup_table_size: 20.0 # Size of the dubin/reeds-sheep distance window to cache, in meters.
|
||||
# cache_obstacle_heuristic: true #was fasle # 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.
|
||||
# debug_visualizations: false # For Hybrid nodes: Whether to publish expansions on the /expansions topic as an array of poses (the orientation has no meaning) and the path's footprints on the /planned_footprints topic. WARNING: heavy to compute and to display, for debug only as it degrades the performance.
|
||||
# use_quadratic_cost_penalty: False
|
||||
# downsample_obstacle_heuristic: True
|
||||
# allow_primitive_interpolation: False
|
||||
# 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:
|
||||
|
Loading…
Reference in New Issue
Block a user