This commit is contained in:
Björn Ellensohn 2023-09-08 09:47:04 +02:00
parent aab1cc7842
commit 4aa5e2134b

View File

@ -56,7 +56,7 @@ bt_navigator:
- nav2_compute_path_through_poses_action_bt_node - nav2_compute_path_through_poses_action_bt_node
- nav2_smooth_path_action_bt_node - nav2_smooth_path_action_bt_node
- nav2_follow_path_action_bt_node - nav2_follow_path_action_bt_node
- nav2_spin_action_bt_node #- nav2_spin_action_bt_node
- nav2_wait_action_bt_node - nav2_wait_action_bt_node
- nav2_assisted_teleop_action_bt_node - nav2_assisted_teleop_action_bt_node
- nav2_back_up_action_bt_node - nav2_back_up_action_bt_node
@ -540,18 +540,18 @@ planner_server:
max_iterations: 1000000 # maximum total iterations to search for before failing (in case unreachable), set to -1 to disable 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_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 max_planning_time: 5.0 # max time in s for planner to plan, smooth
motion_model_for_search: "DUBIN" # Hybrid-A* Dubin, Redds-Shepp motion_model_for_search: "Hybrid-A*" #was DUBIN # Hybrid-A* Dubin, Redds-Shepp
angle_quantization_bins: 72 # Number of angle bins for search 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_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 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 minimum_turning_radius: 0.15 # was 0.40 # minimum turning radius in m of path / vehicle
reverse_penalty: 2.0 # Penalty to apply if motion is reversing, must be => 1 reverse_penalty: 2.0 # Penalty to apply if motion is reversing, must be => 1
change_penalty: 0.0 # Penalty to apply if motion is changing directions (L to R), must be >= 0 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 non_straight_penalty: 1.2 # 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. 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.
retrospective_penalty: 0.015 retrospective_penalty: 0.015
lookup_table_size: 20.0 # Size of the dubin/reeds-sheep distance window to cache, in meters. 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. 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. 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 use_quadratic_cost_penalty: False
downsample_obstacle_heuristic: True downsample_obstacle_heuristic: True