Skip to content

Commit 7200338

Browse files
Merge pull request autowarefoundation#824 from tier4/sync-awf-upstream
chore: sync awf/autoware_launch
2 parents c47af32 + b6cff40 commit 7200338

File tree

4 files changed

+128
-137
lines changed

4 files changed

+128
-137
lines changed

autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml

+3
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
enable_avoidance_over_same_direction: true
1616
enable_avoidance_over_opposite_direction: true
1717
enable_update_path_when_object_is_gone: false
18+
enable_force_avoidance_for_stopped_vehicle: false
1819
enable_safety_check: false
1920
enable_yield_maneuver: false
2021
disable_path_update: false
@@ -39,7 +40,9 @@
3940
# filtering moving objects
4041
threshold_speed_object_is_stopped: 1.0 # [m/s]
4142
threshold_time_object_is_moving: 1.0 # [s]
43+
threshold_time_force_avoidance_for_stopped_vehicle: 10.0 # [s]
4244
# detection range
45+
object_check_force_avoidance_clearance: 30.0 # [m]
4346
object_check_forward_distance: 150.0 # [m]
4447
object_check_backward_distance: 2.0 # [m]
4548
object_check_goal_distance: 20.0 # [m]

autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,7 @@
11
/**:
22
ros__parameters:
3+
verbose: false
4+
35
planning_hz: 10.0
46
backward_path_length: 5.0
57
forward_path_length: 300.0
Original file line numberDiff line numberDiff line change
@@ -1,166 +1,140 @@
11
/**:
22
ros__parameters:
33
option:
4-
# publish
5-
is_publishing_debug_visualization_marker: true
6-
is_publishing_clearance_map: false # publish clearance map as nav_msgs::OccupancyGrid
7-
is_publishing_object_clearance_map: false # publish clearance map as nav_msgs::OccupancyGrid
8-
is_publishing_area_with_objects: false # publish occupancy map as nav_msgs::OccupancyGrid
4+
enable_smoothing: true # enable path smoothing by elastic band
5+
enable_skip_optimization: false # skip elastic band and model predictive trajectory
6+
enable_reset_prev_optimization: false # If true, optimization has no fix constraint to the previous result.
7+
enable_outside_drivable_area_stop: true # stop if the ego's trajectory footprint is outside the drivable area
8+
use_footprint_polygon_for_outside_drivable_area_check: false # If false, only the footprint's corner points are considered.
99

10-
is_stopping_if_outside_drivable_area: true # stop if the ego's footprint will be outside the drivable area
10+
debug:
11+
# flag to publish
12+
enable_pub_debug_marker: true # publish debug marker
1113

12-
# show
13-
is_showing_debug_info: false
14-
is_showing_calculation_time: false
15-
16-
# other
17-
enable_avoidance: false # enable avoidance function
18-
enable_pre_smoothing: true # enable EB
19-
skip_optimization: false # skip MPT and EB
20-
reset_prev_optimization: false
21-
is_considering_footprint_edges: false # consider ego footprint edges to decide whether footprint is outside drivable area
14+
# flag to show
15+
enable_debug_info: false
16+
enable_calculation_time_info: false
2217

2318
common:
24-
# sampling
25-
num_sampling_points: 100 # number of optimizing points
26-
27-
# trajectory total/fixing length
28-
trajectory_length: 300.0 # total trajectory length[m]
29-
30-
forward_fixing_min_distance: 1.0 # number of fixing points around ego vehicle [m]
31-
forward_fixing_min_time: 0.5 # forward fixing time with current velocity [s]
19+
# output
20+
output_delta_arc_length: 0.5 # delta arc length for output trajectory [m]
21+
output_backward_traj_length: 5.0 # backward length for backward trajectory from base_link [m]
3222

33-
backward_fixing_distance: 5.0 # backward fixing length from base_link [m]
34-
delta_arc_length_for_trajectory: 0.1 # delta arc length for trajectory [m]
23+
# replanning & trimming trajectory param outside algorithm
24+
replan:
25+
max_path_shape_around_ego_lat_dist: 2.0 # threshold of path shape change around ego [m]
26+
max_ego_moving_dist: 5.0 # threshold of ego's moving distance for replan [m]
27+
# make max_goal_moving_dist long to keep start point fixed for pull over
28+
max_goal_moving_dist: 15.0 # threshold of goal's moving distance for replan [m]
29+
max_delta_time_sec: 1.0 # threshold of delta time for replan [second]
30+
31+
# eb param
32+
eb:
33+
option:
34+
enable_warm_start: true
35+
enable_optimization_validation: false
3536

36-
delta_dist_threshold_for_closest_point: 3.0 # delta dist thres for closest point [m]
37-
delta_yaw_threshold_for_closest_point: 1.046 #M_PI/3.0, delta yaw thres for closest point
38-
delta_yaw_threshold_for_straight: 0.02 # delta dist thres for straight point
37+
common:
38+
num_points: 100 # number of points for optimization [-]
39+
delta_arc_length: 1.0 # delta arc length for optimization [m]
3940

40-
num_fix_points_for_extending: 50 # number of fixing points when extending
41-
max_dist_for_extending_end_point: 0.0001 # minimum delta dist thres for extending last point [m]
41+
clearance:
42+
num_joint_points: 3 # number of joint points (joint means connecting fixing and smoothing)
4243

43-
enable_clipping_fixed_traj: false
44-
non_fixed_trajectory_length: 5.0 # length of the trajectory merging optimized mpt trajectory to original(not optimized) trajectory
44+
clearance_for_fix: 0.0 # maximum optimizing range when applying fixing
45+
clearance_for_joint: 0.1 # maximum optimizing range when applying jointing
46+
clearance_for_smooth: 0.1 # maximum optimizing range when applying smoothing
4547

46-
vehicle_stop_margin_outside_drivable_area: 1.5 # vehicle stop margin to let the vehicle stop before the calculated stop point if it is calculated outside the drivable area [m] .
47-
# This margin will be realized with delta_arc_length_for_mpt_points m precision.
48+
weight:
49+
smooth_weight: 1.0
50+
lat_error_weight: 0.001
4851

49-
object: # avoiding object
50-
max_avoiding_objects_velocity_ms: 0.5 # maximum velocity for avoiding objects [m/s]
51-
max_avoiding_ego_velocity_ms: 6.0 # maximum ego velocity when avoiding objects [m/s]
52+
qp:
53+
max_iteration: 10000 # max iteration when solving QP
54+
eps_abs: 1.0e-7 # eps abs when solving OSQP
55+
eps_rel: 1.0e-7 # eps rel when solving OSQP
5256

53-
avoiding_object_type:
54-
unknown: true
55-
car: true
56-
truck: true
57-
bus: true
58-
bicycle: true
59-
motorbike: true
60-
pedestrian: true
61-
animal: true
57+
validation: # if enable_optimization_validation is true
58+
max_error: 3.0 # [m]
6259

6360
# mpt param
6461
mpt:
6562
option:
66-
steer_limit_constraint: true
67-
fix_points_around_ego: true
68-
plan_from_ego: true
69-
max_plan_from_ego_length: 10.0
63+
# TODO(murooka) enable the following. Currently enabling the flag makes QP so heavy
64+
steer_limit_constraint: false
7065
visualize_sampling_num: 1
71-
enable_manual_warm_start: true
72-
enable_warm_start: true # false
73-
is_fixed_point_single: false
66+
enable_manual_warm_start: false
67+
enable_warm_start: true
68+
enable_optimization_validation: false
7469

7570
common:
76-
num_curvature_sampling_points: 5 # number of sampling points when calculating curvature
77-
delta_arc_length_for_mpt_points: 0.5 # delta arc length when generating mpt [m]
71+
num_points: 100 # number of points for optimization [-]
72+
delta_arc_length: 1.0 # delta arc length for optimization [m]
7873

7974
# kinematics:
8075
# If this parameter is commented out, the parameter is set as below by default.
81-
# The logic could be `optimization_center_offset = vehicle_info.wheel_base * 0.8`
76+
# The logic could be `optimization_center_offset = vehicle_info.wheelbase * 0.8`
8277
# The 0.8 scale is adopted as it performed the best.
8378
# optimization_center_offset: 2.3 # optimization center offset from base link
8479

85-
# replanning & trimming trajectory param outside algorithm
86-
replan:
87-
max_path_shape_change_dist: 0.3 # threshold of path shape change from behavior path [m]
88-
max_ego_moving_dist_for_replan: 3.0 # threshold of ego's moving distance for replan [m]
89-
max_delta_time_sec_for_replan: 1.0 # threshold of delta time for replan [second]
90-
91-
# advanced parameters to improve performance as much as possible
92-
advanced:
93-
eb:
94-
common:
95-
num_joint_buffer_points: 3 # number of joint buffer points
96-
num_offset_for_begin_idx: 2 # number of shifting points for beginning non-fix idx
97-
delta_arc_length_for_eb: 0.6 # 1.0 # delta arc length when optimizing[m] When the value is around 1.0, overshoot at the corner happens.
98-
num_sampling_points_for_eb: 95 # number of optimizing points # must be longer than mpt points
99-
100-
clearance:
101-
clearance_for_straight_line: 0.05 # minimum optimizing range around straight points
102-
clearance_for_joint: 0.1 # minimum optimizing range around joint points
103-
clearance_for_only_smoothing: 0.1 # minimum optimizing range when applying only smoothing
104-
105-
qp:
106-
max_iteration: 10000 # max iteration when solving QP
107-
eps_abs: 1.0e-8 # eps abs when solving OSQP
108-
eps_rel: 1.0e-10 # eps rel when solving OSQP
109-
110-
mpt:
111-
bounds_search_widths: [0.45, 0.15, 0.05, 0.01]
112-
113-
clearance: # clearance(distance) between vehicle and roads/objects when generating trajectory
114-
hard_clearance_from_road: 0.0 # clearance from road boundary[m]
115-
soft_clearance_from_road: 0.1 # clearance from road boundary[m]
116-
soft_second_clearance_from_road: 1.0 # clearance from road boundary[m]
117-
clearance_from_object: 1.0 # clearance from object[m]
118-
extra_desired_clearance_from_road: 0.0 # extra desired clearance from road
80+
clearance: # clearance(distance) between vehicle and roads/objects when generating trajectory
81+
# if collision_free_constraints.option.hard_constraint is true
82+
hard_clearance_from_road: 0.0 # clearance from road boundary[m]
83+
# if collision_free_constraints.option.soft_constraint is true
84+
soft_clearance_from_road: 0.1 # clearance from road boundary[m]
85+
86+
# weight parameter for optimization
87+
weight:
88+
# collision free
89+
soft_collision_free_weight: 1000.0 # soft weight for lateral error around the middle point
90+
91+
# tracking error
92+
lat_error_weight: 1.0 # weight for lateral error
93+
yaw_error_weight: 0.0 # weight for yaw error
94+
yaw_error_rate_weight: 0.0 # weight for yaw error rate
95+
steer_input_weight: 1.0 # weight for steering input
96+
steer_rate_weight: 1.0 # weight for steering rate
97+
98+
terminal_lat_error_weight: 100.0 # weight for lateral error at terminal point
99+
terminal_yaw_error_weight: 100.0 # weight for yaw error at terminal point
100+
goal_lat_error_weight: 1000.0 # weight for lateral error at path end point
101+
goal_yaw_error_weight: 1000.0 # weight for yaw error at path end point
102+
103+
# avoidance
104+
avoidance:
105+
max_avoidance_cost: 0.5 # [m]
106+
avoidance_cost_margin: 0.0 # [m]
107+
avoidance_cost_band_length: 5.0 # [m]
108+
avoidance_cost_decrease_rate: 0.05 # decreased cost per point interval
119109

120110
weight:
121-
soft_avoidance_weight: 1000.0 # slack weight for lateral error around the middle point
122-
soft_second_avoidance_weight: 100.0 # slack weight for lateral error around the middle point
123-
124-
lat_error_weight: 100.0 # weight for lateral error
125-
yaw_error_weight: 0.0 # weight for yaw error
126-
yaw_error_rate_weight: 0.0 # weight for yaw error rate
127-
steer_input_weight: 10.0 # weight for steering input
128-
steer_rate_weight: 10.0 # weight for steering rate
129-
130-
obstacle_avoid_lat_error_weight: 3.0 # weight for lateral error
131-
obstacle_avoid_yaw_error_weight: 0.0 # weight for yaw error
132-
obstacle_avoid_steer_input_weight: 1000.0 # weight for yaw error
133-
near_objects_length: 30.0 # weight for yaw error
134-
135-
terminal_lat_error_weight: 100.0 # weight for lateral error at terminal point
136-
terminal_yaw_error_weight: 100.0 # weight for yaw error at terminal point
137-
terminal_path_lat_error_weight: 1000.0 # weight for lateral error at path end point
138-
terminal_path_yaw_error_weight: 1000.0 # weight for yaw error at path end point
139-
140-
# check if planned trajectory is outside drivable area
141-
collision_free_constraints:
142-
option:
143-
l_inf_norm: true
144-
soft_constraint: true
145-
hard_constraint: false
146-
# two_step_soft_constraint: false
147-
148-
vehicle_circles:
149-
method: "rear_drive"
150-
151-
uniform_circle:
152-
num: 3
153-
radius_ratio: 0.8
154-
155-
fitting_uniform_circle:
156-
num: 3 # must be greater than 1
157-
158-
rear_drive:
159-
num_for_calculation: 3
160-
front_radius_ratio: 1.0
161-
rear_radius_ratio: 1.0
162-
163-
bicycle_model:
164-
num_for_calculation: 3
165-
front_radius_ratio: 1.0
166-
rear_radius_ratio: 1.0
111+
lat_error_weight: 0.0 # weight for lateral error
112+
yaw_error_weight: 10.0 # weight for yaw error
113+
steer_input_weight: 100.0 # weight for yaw error
114+
115+
# collision free constraint for optimization
116+
collision_free_constraints:
117+
option:
118+
l_inf_norm: true
119+
soft_constraint: true
120+
hard_constraint: false
121+
122+
# how to represent footprint as circles
123+
vehicle_circles:
124+
method: "fitting_uniform_circle"
125+
126+
bicycle_model:
127+
num_for_calculation: 3
128+
front_radius_ratio: 1.0
129+
rear_radius_ratio: 1.0
130+
131+
uniform_circle:
132+
num: 3
133+
radius_ratio: 1.0
134+
135+
fitting_uniform_circle:
136+
num: 3
137+
138+
validation: # if enable_optimization_validation is true
139+
max_lat_error: 5.0 # [m]
140+
max_yaw_error: 1.046 # [rad]

autoware_launch/rviz/autoware.rviz

+12
Original file line numberDiff line numberDiff line change
@@ -1189,6 +1189,18 @@ Visualization Manager:
11891189
Reliability Policy: Reliable
11901190
Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/crosswalk
11911191
Value: true
1192+
- Class: rviz_default_plugins/MarkerArray
1193+
Enabled: true
1194+
Name: VirtualWall (Walkway)
1195+
Namespaces:
1196+
{}
1197+
Topic:
1198+
Depth: 5
1199+
Durability Policy: Volatile
1200+
History Policy: Keep Last
1201+
Reliability Policy: Reliable
1202+
Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/walkway
1203+
Value: true
11921204
- Class: rviz_default_plugins/MarkerArray
11931205
Enabled: true
11941206
Name: VirtualWall (DetectionArea)

0 commit comments

Comments
 (0)