/
teb_params.yaml
109 lines (92 loc) · 3.21 KB
/
teb_params.yaml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
controller_server:
ros__parameters:
odom_topic: /odom
use_sim_time: True
controller_frequency: 5.0
controller_plugin_types: ["teb_local_planner::TebLocalPlannerROS"]
controller_plugins: ["FollowPath"]
FollowPath:
plugin: teb_local_planner::TebLocalPlannerROS
teb_autosize: 1.0
dt_ref: 0.3
dt_hysteresis: 0.1
max_samples: 500
global_plan_overwrite_orientation: False
allow_init_with_backwards_motion: False
max_global_plan_lookahead_dist: 3.0
global_plan_viapoint_sep: 0.3
global_plan_prune_distance: 1.0
exact_arc_length: False
feasibility_check_no_poses: 2
publish_feedback: False
# Robot
max_vel_x: 0.26
max_vel_theta: 1.0
acc_lim_x: 2.5
acc_lim_theta: 3.2
footprint_model: # types: "point", "circular", "two_circles", "line", "polygon"
type: "circular"
radius: 0.17 # for type "circular"
# GoalTolerance
free_goal_vel: False
# Obstacles
min_obstacle_dist: 0.27
inflation_dist: 0.6
include_costmap_obstacles: True
costmap_obstacles_behind_robot_dist: 1.0
obstacle_poses_affected: 15
dynamic_obstacle_inflation_dist: 0.6
include_dynamic_obstacles: True
costmap_converter_plugin: "costmap_converter::CostmapToPolygonsDBSMCCH"
costmap_converter_spin_thread: True
costmap_converter_rate: 5
# Optimization
no_inner_iterations: 5
no_outer_iterations: 4
optimization_activate: True
optimization_verbose: False
penalty_epsilon: 0.1
obstacle_cost_exponent: 4.0
weight_max_vel_x: 0.5
weight_max_vel_theta: 0.5
weight_acc_lim_x: 0.5
weight_acc_lim_theta: 10.5
weight_kinematics_nh: 1000.0
weight_kinematics_forward_drive: 3.0
weight_kinematics_turning_radius: 1.0
weight_optimaltime: 1.0 # must be > 0
weight_shortest_path: 0.0
weight_obstacle: 100.0
weight_inflation: 0.2
weight_dynamic_obstacle: 10.0 # not in use yet
weight_dynamic_obstacle_inflation: 0.2
weight_viapoint: 50.0
weight_adapt_factor: 2.0
# Homotopy Class Planner
enable_homotopy_class_planning: True
enable_multithreading: True
max_number_classes: 4
selection_cost_hysteresis: 5.0
selection_prefer_initial_plan: 1.0
selection_obst_cost_scale: 1.0
selection_alternative_time_cost: True
roadmap_graph_no_samples: 15
roadmap_graph_area_width: 5.0
roadmap_graph_area_length_scale: 1.0
h_signature_prescaler: 0.5
h_signature_threshold: 0.1
obstacle_heading_threshold: 0.45
switching_blocking_period: 0.0
viapoints_all_candidates: True
delete_detours_backwards: True
max_ratio_detours_duration_best_duration: 3.0
visualize_hc_graph: False
visualize_with_time_as_z_axis_scale: 0.0
# Recovery
shrink_horizon_backup: True
shrink_horizon_min_duration: 10.0
oscillation_recovery: True
oscillation_v_eps: 0.1
oscillation_omega_eps: 0.1
oscillation_recovery_min_duration: 10.0
oscillation_filter_duration: 10.0