forked from autowarefoundation/autoware_universe
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathstart_planner.param.yaml
158 lines (153 loc) · 5.24 KB
/
start_planner.param.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
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
/**:
ros__parameters:
start_planner:
th_arrived_distance: 1.0
th_stopped_velocity: 0.01
th_stopped_time: 1.0
collision_check_margins: [2.0, 1.5, 1.0]
collision_check_distance_from_end: 1.0
collision_check_margin_from_front_object: 5.0
th_moving_object_velocity: 1.0
th_distance_to_middle_of_the_road: 0.5
center_line_path_interval: 1.0
# shift pull out
enable_shift_pull_out: true
check_shift_path_lane_departure: true
minimum_shift_pull_out_distance: 0.0
deceleration_interval: 15.0
lateral_jerk: 0.5
lateral_acceleration_sampling_num: 3
minimum_lateral_acc: 0.15
maximum_lateral_acc: 0.5
maximum_curvature: 0.07
# geometric pull out
enable_geometric_pull_out: true
divide_pull_out_path: true
geometric_pull_out_velocity: 1.0
arc_path_interval: 1.0
lane_departure_margin: 0.2
backward_velocity: -1.0
pull_out_max_steer_angle: 0.26 # 15deg
# search start pose backward
enable_back: true
search_priority: "efficient_path" # "efficient_path" or "short_back_distance"
max_back_distance: 30.0
backward_search_resolution: 2.0
backward_path_update_duration: 3.0
ignore_distance_from_lane_end: 15.0
# turns signal
th_turn_signal_on_lateral_offset: 1.0
intersection_search_length: 30.0
length_ratio_for_turn_signal_deactivation_near_intersection: 0.5
# freespace planner
freespace_planner:
enable_freespace_planner: true
end_pose_search_start_distance: 20.0
end_pose_search_end_distance: 30.0
end_pose_search_interval: 2.0
freespace_planner_algorithm: "astar" # options: astar, rrtstar
velocity: 1.0
vehicle_shape_margin: 1.0
time_limit: 3000.0
minimum_turning_radius: 5.0
maximum_turning_radius: 5.0
turning_radius_size: 1
# search configs
search_configs:
theta_size: 144
angle_goal_range: 6.0
curve_weight: 1.2
reverse_weight: 1.0
lateral_goal_range: 0.5
longitudinal_goal_range: 2.0
# costmap configs
costmap_configs:
obstacle_threshold: 30
# -- A* search Configurations --
astar:
only_behind_solutions: false
use_back: false
distance_heuristic_weight: 1.0
# -- RRT* search Configurations --
rrtstar:
enable_update: true
use_informed_sampling: true
max_planning_time: 150.0
neighbor_radius: 8.0
margin: 1.0
stop_condition:
maximum_deceleration_for_stop: 1.0
maximum_jerk_for_stop: 1.0
path_safety_check:
# EgoPredictedPath
ego_predicted_path:
min_velocity: 0.0
min_acceleration: 1.0
time_horizon_for_front_object: 10.0
time_horizon_for_rear_object: 10.0
time_resolution: 0.5
delay_until_departure: 1.0
# For target object filtering
target_filtering:
safety_check_time_horizon: 5.0
safety_check_time_resolution: 1.0
# detection range
object_check_forward_distance: 10.0
object_check_backward_distance: 100.0
ignore_object_velocity_threshold: 1.0
# ObjectTypesToCheck
object_types_to_check:
check_car: true
check_truck: true
check_bus: true
check_trailer: true
check_bicycle: true
check_motorcycle: true
check_pedestrian: true
check_unknown: false
# ObjectLaneConfiguration
object_lane_configuration:
check_current_lane: true
check_right_side_lane: true
check_left_side_lane: true
check_shoulder_lane: true
check_other_lane: false
include_opposite_lane: false
invert_opposite_lane: false
check_all_predicted_path: true
use_all_predicted_path: true
use_predicted_path_outside_lanelet: false
# For safety check
safety_check_params:
# safety check configuration
enable_safety_check: true
# collision check parameters
check_all_predicted_path: true
publish_debug_marker: false
rss_params:
rear_vehicle_reaction_time: 2.0
rear_vehicle_safety_time_margin: 1.0
lateral_distance_max_threshold: 2.0
longitudinal_distance_min_threshold: 3.0
longitudinal_velocity_delta_time: 0.8
# hysteresis factor to expand/shrink polygon
hysteresis_factor_expand_rate: 1.0
# temporary
backward_path_length: 30.0
forward_path_length: 100.0
surround_moving_obstacle_check:
search_radius: 10.0
th_moving_obstacle_velocity: 1.0
# ObjectTypesToCheck
object_types_to_check:
check_car: true
check_truck: true
check_bus: true
check_trailer: true
check_bicycle: true
check_motorcycle: true
check_pedestrian: true
check_unknown: false
# debug
debug:
print_debug_info: false