Skip to content

Commit c86f45e

Browse files
authored
Merge pull request autowarefoundation#879 from tier4/feature/xx1-gen1_2-launcher
feat(autoware_launcher): update for xx1 gen2
2 parents 68ab822 + 7792f69 commit c86f45e

File tree

10 files changed

+356
-23
lines changed

10 files changed

+356
-23
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,76 @@
1+
/**:
2+
ros__parameters:
3+
# -- system --
4+
traj_resample_dist: 0.1 # path resampling interval [m]
5+
use_steer_prediction: false # flag for using steer prediction (do not use steer measurement)
6+
admissible_position_error: 5.0 # stop mpc calculation when error is larger than the following value
7+
admissible_yaw_error_rad: 1.57 # stop mpc calculation when error is larger than the following value
8+
9+
# -- path smoothing --
10+
enable_path_smoothing: true # flag for path smoothing
11+
path_filter_moving_ave_num: 25 # param of moving average filter for path smoothing
12+
curvature_smoothing_num_traj: 15 # point-to-point index distance used in curvature calculation (for trajectory): curvature is calculated from three points p(i-num), p(i), p(i+num)
13+
curvature_smoothing_num_ref_steer: 15 # point-to-point index distance used in curvature calculation (for steer command reference): curvature is calculated from three points p(i-num), p(i), p(i+num)
14+
15+
# -- trajectory extending --
16+
extend_trajectory_for_end_yaw_control: true # flag of trajectory extending for terminal yaw control
17+
18+
# -- mpc optimization --
19+
qp_solver_type: "osqp" # optimization solver option (unconstraint_fast or osqp)
20+
mpc_prediction_horizon: 50 # prediction horizon step
21+
mpc_prediction_dt: 0.1 # prediction horizon period [s]
22+
mpc_weight_lat_error: 0.2 # lateral error weight in matrix Q
23+
mpc_weight_heading_error: 0.0 # heading error weight in matrix Q
24+
mpc_weight_heading_error_squared_vel: 0.03 # heading error * velocity weight in matrix Q
25+
mpc_weight_steering_input: 1.0 # steering error weight in matrix R
26+
mpc_weight_steering_input_squared_vel: 1.00 # steering error * velocity weight in matrix R
27+
mpc_weight_lat_jerk: 0.0 # lateral jerk weight in matrix R
28+
mpc_weight_steer_rate: 0.0 # steering rate weight in matrix R
29+
mpc_weight_steer_acc: 0.000001 # steering angular acceleration weight in matrix R
30+
mpc_low_curvature_weight_lat_error: 0.05 # lateral error weight in matrix Q in low curvature point
31+
mpc_low_curvature_weight_heading_error: 0.0 # heading error weight in matrix Q in low curvature point
32+
mpc_low_curvature_weight_heading_error_squared_vel: 0.03 # heading error * velocity weight in matrix Q in low curvature point
33+
mpc_low_curvature_weight_steering_input: 1.0 # steering error weight in matrix R in low curvature point
34+
mpc_low_curvature_weight_steering_input_squared_vel: 2.00 # steering error * velocity weight in matrix R in low curvature point
35+
mpc_low_curvature_weight_lat_jerk: 0.0 # lateral jerk weight in matrix R in low curvature point
36+
mpc_low_curvature_weight_steer_rate: 0.0 # steering rate weight in matrix R in low curvature point
37+
mpc_low_curvature_weight_steer_acc: 0.000001 # steering angular acceleration weight in matrix R in low curvature point
38+
mpc_low_curvature_thresh_curvature: 0.03 # threshold of curvature to use "low_curvature" parameter (recommend: 0.01~0.03)
39+
mpc_weight_terminal_lat_error: 1.0 # terminal lateral error weight in matrix Q to improve mpc stability
40+
mpc_weight_terminal_heading_error: 0.1 # terminal heading error weight in matrix Q to improve mpc stability
41+
mpc_zero_ff_steer_deg: 0.5 # threshold that feed-forward angle becomes zero
42+
mpc_acceleration_limit: 2.0 # limit on the vehicle's acceleration
43+
mpc_velocity_time_constant: 0.3 # time constant used for velocity smoothing
44+
mpc_min_prediction_length: 5.0 # minimum prediction length
45+
46+
# -- vehicle model --
47+
vehicle_model_type: "kinematics" # vehicle model type for mpc prediction. option is kinematics, kinematics_no_delay, and dynamics
48+
input_delay: 0.1 # steering input delay time for delay compensation
49+
vehicle_model_steer_tau: 0.1 # steering dynamics time constant (1d approximation) [s]
50+
steer_rate_lim_dps_list_by_curvature: [20.0, 20.0, 20.0] # steering angle rate limit list depending on curvature [deg/s]
51+
curvature_list_for_steer_rate_lim: [0.001, 0.002, 0.01] # curvature list for steering angle rate limit interpolation in ascending order [/m]
52+
steer_rate_lim_dps_list_by_velocity: [18.0, 18.0, 15.0, 12.0, 5.0, 2.25, 1.5 , 1.5 , 1.5] # steering angle rate limit list depending on velocity [deg/s] [72, 72, 36, 18, 9, 3.6, 3.6]
53+
velocity_list_for_steer_rate_lim: [0.0, 1.388, 2.778, 4.167, 5.556, 6.944, 8.333, 9.722, 11.11] # velocity list for steering angle rate limit interpolation in ascending order [m/s]
54+
acceleration_limit: 1.0 # acceleration limit for trajectory velocity modification [m/ss]
55+
velocity_time_constant: 0.3 # velocity dynamics time constant for trajectory velocity modification [s]
56+
57+
# -- lowpass filter for noise reduction --
58+
steering_lpf_cutoff_hz: 10.0 # cutoff frequency of lowpass filter for steering command [Hz]
59+
error_deriv_lpf_cutoff_hz: 5.0
60+
61+
# stop state: steering command is kept in the previous value in the stop state.
62+
stop_state_entry_ego_speed: 0.2
63+
stop_state_entry_target_speed: 0.2
64+
converged_steer_rad: 0.1
65+
keep_steer_control_until_converged: true
66+
new_traj_duration_time: 1.0
67+
new_traj_end_dist: 0.3
68+
mpc_converged_threshold_rps: 0.01 # threshold of mpc convergence check [rad/s]
69+
70+
# steer offset
71+
steering_offset:
72+
enable_auto_steering_offset_removal: true
73+
update_vel_threshold: 5.56
74+
update_steer_threshold: 0.035
75+
average_num: 1000
76+
steering_offset_limit: 0.02
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,76 @@
1+
/**:
2+
ros__parameters:
3+
delay_compensation_time: 0.40
4+
5+
enable_smooth_stop: true
6+
enable_overshoot_emergency: false
7+
enable_large_tracking_error_emergency: false
8+
enable_slope_compensation: true
9+
enable_keep_stopped_until_steer_convergence: true
10+
11+
# state transition
12+
drive_state_stop_dist: 0.5
13+
drive_state_offset_stop_dist: 1.0
14+
stopping_state_stop_dist: 0.5
15+
stopped_state_entry_duration_time: 0.1
16+
stopped_state_entry_vel: 0.01
17+
stopped_state_entry_acc: 0.1
18+
emergency_state_overshoot_stop_dist: 1.5
19+
emergency_state_traj_trans_dev: 3.0
20+
emergency_state_traj_rot_dev: 0.7854
21+
22+
# drive state
23+
kp: 2.0
24+
ki: 0.02
25+
kd: 0.0
26+
max_out: 1.0
27+
min_out: -5.0
28+
max_p_effort: 0.5
29+
min_p_effort: -5.0
30+
max_i_effort: 0.3
31+
min_i_effort: -0.3
32+
max_d_effort: 0.0
33+
min_d_effort: 0.0
34+
lpf_vel_error_gain: 0.9
35+
enable_integration_at_low_speed: false
36+
current_vel_threshold_pid_integration: 0.5
37+
time_threshold_before_pid_integration: 2.0
38+
enable_brake_keeping_before_stop: false
39+
brake_keeping_acc: -0.2
40+
41+
# smooth stop state
42+
smooth_stop_max_strong_acc: -0.8
43+
smooth_stop_min_strong_acc: -1.3
44+
smooth_stop_weak_acc: -0.4
45+
smooth_stop_weak_stop_acc: -0.8
46+
smooth_stop_strong_stop_acc: -3.4
47+
smooth_stop_max_fast_vel: 0.5
48+
smooth_stop_min_running_vel: 0.01
49+
smooth_stop_min_running_acc: 0.01
50+
smooth_stop_weak_stop_time: 4.0
51+
smooth_stop_weak_stop_dist: -0.3
52+
smooth_stop_strong_stop_dist: -0.5
53+
54+
# stopped state
55+
stopped_vel: 0.0
56+
stopped_acc: -3.4
57+
stopped_jerk: -5.0
58+
59+
# emergency state
60+
emergency_vel: 0.0
61+
emergency_acc: -5.0
62+
emergency_jerk: -3.0
63+
64+
# acceleration limit
65+
max_acc: 3.0
66+
min_acc: -5.0
67+
68+
# jerk limit
69+
max_jerk: 3.5
70+
min_jerk: -5.0
71+
72+
# pitch
73+
use_trajectory_for_pitch_calculation: false
74+
lpf_pitch_gain: 0.95
75+
max_pitch_rad: 0.1
76+
min_pitch_rad: -0.1
Original file line numberDiff line numberDiff line change
@@ -1,21 +1,32 @@
11
/**:
22
ros__parameters:
3+
trt_precision: fp16
34
encoder_onnx_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"
45
encoder_engine_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).engine"
56
head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"
67
head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"
7-
trt_precision: fp16
8+
9+
model_params:
10+
class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
11+
paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"]
12+
point_feature_size: 7 # x, y, z, time-lag and car, pedestrian, bicycle
13+
max_voxel_size: 40000
14+
point_cloud_range: [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0]
15+
voxel_size: [0.32, 0.32, 8.0]
16+
downsample_factor: 1
17+
encoder_in_feature_size: 12
18+
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
19+
has_twist: false
20+
densification_params:
21+
world_frame_id: "map"
22+
num_past_frames: 0
823
post_process_params:
924
# post-process params
1025
circle_nms_dist_threshold: 0.3
1126
iou_nms_target_class_names: ["CAR"]
1227
iou_nms_search_distance_2d: 10.0
1328
iou_nms_threshold: 0.1
14-
score_threshold: 0.45
15-
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
16-
densification_params:
17-
world_frame_id: "map"
18-
num_past_frames: 1
29+
score_threshold: 0.35
1930
omp_params:
2031
# omp params
2132
num_threads: 1

autoware_launch/config/perception/occupancy_grid_map/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml

+12-11
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,3 @@
1-
# sample grid map fusion parameters for sample sensor kit
21
/**:
32
ros__parameters:
43
# shared parameters
@@ -12,10 +11,6 @@
1211
map_length_x: 150.0 # [m]
1312
map_length_y: 150.0 # [m]
1413

15-
# downsample input pointcloud
16-
downsample_input_pointcloud: true
17-
downsample_voxel_size: 0.25 # [m]
18-
1914
# each grid map parameters
2015
ogm_creation_config:
2116
height_filter:
@@ -24,7 +19,7 @@
2419
max_height: 2.0
2520
enable_single_frame_mode: true
2621
# use sensor pointcloud to filter obstacle pointcloud
27-
filter_obstacle_pointcloud_by_raw_pointcloud: false
22+
filter_obstacle_pointcloud_by_raw_pointcloud: true
2823

2924
grid_map_type: "OccupancyGridMapFixedBlindSpot"
3025
OccupancyGridMapFixedBlindSpot:
@@ -40,17 +35,23 @@
4035
# Setting1: tune ogm creation parameters
4136
raw_pointcloud_topics: # put each sensor's pointcloud topic
4237
- "/sensing/lidar/top/pointcloud"
43-
- "/sensing/lidar/left/pointcloud"
44-
- "/sensing/lidar/right/pointcloud"
38+
- "/sensing/lidar/side_left/pointcloud"
39+
- "/sensing/lidar/side_right/pointcloud"
40+
- "/sensing/lidar/front_left/pointcloud"
41+
- "/sensing/lidar/front_right/pointcloud"
4542
fusion_input_ogm_topics:
46-
- "/perception/occupancy_grid_map/top_lidar/map"
47-
- "/perception/occupancy_grid_map/left_lidar/map"
48-
- "/perception/occupancy_grid_map/right_lidar/map"
43+
- "/perception/occupancy_grid_map/top/map"
44+
- "/perception/occupancy_grid_map/side_left/map"
45+
- "/perception/occupancy_grid_map/side_right/map"
46+
- "/perception/occupancy_grid_map/front_left/map"
47+
- "/perception/occupancy_grid_map/front_right/map"
4948
# reliability of each sensor (0.0 ~ 1.0) only work with "log-odds" and "dempster-shafer"
5049
input_ogm_reliabilities:
5150
- 1.0
5251
- 0.6
5352
- 0.6
53+
- 0.6
54+
- 0.6
5455

5556
# Setting2: tune ogm fusion parameters
5657
## choose fusion method from ["overwrite", "log-odds", "dempster-shafer"]

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

+8-1
Original file line numberDiff line numberDiff line change
@@ -293,4 +293,11 @@
293293

294294
# for debug
295295
debug:
296-
marker: false
296+
enable_other_objects_marker: true
297+
enable_other_objects_info: true
298+
enable_detection_area_marker: false
299+
enable_drivable_bound_marker: false
300+
enable_safety_check_marker: false
301+
enable_shift_line_marker: false
302+
enable_lane_marker: false
303+
enable_misc_marker: false

autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml

+7-5
Original file line numberDiff line numberDiff line change
@@ -3,10 +3,12 @@
33
blind_spot:
44
use_pass_judge_line: true
55
stop_line_margin: 1.0 # [m]
6-
backward_length: 50.0 # [m]
7-
ignore_width_from_center_line: 0.0 # [m]
8-
max_future_movement_time: 10.0 # [second]
9-
threshold_yaw_diff: 0.523 # [rad]
6+
backward_detection_length: 100.0 # [m]
7+
ignore_width_from_center_line: 0.7 # [m]
108
adjacent_extend_width: 1.5 # [m]
119
opposite_adjacent_extend_width: 1.5 # [m]
12-
enable_rtc: false # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc.
10+
max_future_movement_time: 10.0 # [second]
11+
ttc_min: -5.0 # [s]
12+
ttc_max: 5.0 # [s]
13+
ttc_ego_minimal_velocity: 5.0 # [m/s]
14+
enable_rtc: false # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval

autoware_launch/launch/autoware.launch.xml

+4
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222
<arg name="launch_planning" default="true" description="launch planning"/>
2323
<arg name="launch_control" default="true" description="launch control"/>
2424
<arg name="launch_api" default="true" description="launch api"/>
25+
2526
<!-- Global parameters -->
2627
<arg name="use_sim_time" default="false" description="use_sim_time"/>
2728
<!-- Vehicle -->
@@ -115,8 +116,11 @@
115116

116117
<!-- Perception -->
117118
<group if="$(var launch_perception)">
119+
<let name="occupancy_grid_map_method" value="multi_lidar_pointcloud_based_occupancy_grid_map" if="$(eval &quot;'aip_xx1_gen2' == '$(var sensor_model)'&quot;)"/>
120+
<let name="occupancy_grid_map_method" value="pointcloud_based_occupancy_grid_map" unless="$(eval &quot;'aip_xx1_gen2' == '$(var sensor_model)'&quot;)"/>
118121
<include file="$(find-pkg-share autoware_launch)/launch/components/tier4_perception_component.launch.xml">
119122
<arg name="data_path" value="$(var data_path)"/>
123+
<arg name="occupancy_grid_map_method" value="$(var occupancy_grid_map_method)"/>
120124
</include>
121125
</group>
122126

autoware_launch/launch/components/tier4_perception_component.launch.xml

+6
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,12 @@
1616
<arg name="lidar_detection_model" default="pointpainting" description="options: `centerpoint`, `apollo`, `pointpainting`, `clustering`"/>
1717
<arg name="traffic_light_recognition/fusion_only" default="true" description="Whether to start only some of the signal recognition related nodes"/>
1818

19+
<!-- In the Gen2 sensor configuration, the traffic_light_recognition node is launched not through the conventional autoware.universe/launch/tier4_perception_launch but with its own custom launch file.
20+
This is because autoware.universe's launch files do not support an arbitrary number of cameras. If autoware.universe's launch files were to support it, it is recommended to use them instead. -->
21+
<include file="$(find-pkg-share autoware_launch)/launch/components/traffic_light_recognition/traffic_light.launch.xml"/>
22+
<!-- NOTE: Override by false to disable conventional traffic light recognition launch -->
23+
<let name="use_traffic_light_recognition" value="false"/>
24+
1925
<include file="$(find-pkg-share tier4_perception_launch)/launch/perception.launch.xml">
2026
<arg name="mode" value="$(var perception_mode)"/>
2127
<arg name="vehicle_param_file" value="$(find-pkg-share $(var vehicle_model)_description)/config/vehicle_info.param.yaml"/>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,66 @@
1+
<?xml version="1.0"?>
2+
<launch>
3+
<arg name="use_crosswalk_traffic_light_estimator" default="true" description="output pedestrian's traffic light signals"/>
4+
5+
<arg name="input/cloud" default="/sensing/lidar/top/pointcloud_raw" description="point cloud for occlusion prediction"/>
6+
<arg name="internal/traffic_signals" default="/perception/traffic_light_recognition/internal/traffic_signals"/>
7+
<arg name="fusion/traffic_signals" default="/perception/traffic_light_recognition/fusion/traffic_signals"/>
8+
<arg name="external/traffic_signals" default="/perception/traffic_light_recognition/external/traffic_signals"/>
9+
<arg name="output/traffic_signals" default="/perception/traffic_light_recognition/traffic_signals"/>
10+
<arg name="crosswalk_traffic_light_estimator_param_file" default="$(find-pkg-share crosswalk_traffic_light_estimator)/config/crosswalk_traffic_light_estimator.param.yaml"/>
11+
12+
<group>
13+
<push-ros-namespace namespace="perception"/>
14+
<push-ros-namespace namespace="traffic_light_recognition"/>
15+
16+
<!-- traffic light occlusion predictor for some cameras -->
17+
<arg name="all_camera_namespaces" default="[camera6, camera5, camera2, camera0]"/>
18+
<include file="$(find-pkg-share autoware_launch)/launch/components/traffic_light_recognition/traffic_light_occlusion_predictor.launch.py">
19+
<arg name="all_camera_namespaces" value="$(var all_camera_namespaces)"/>
20+
</include>
21+
22+
<!-- traffic light multi camera fusion -->
23+
<group>
24+
<node pkg="traffic_light_multi_camera_fusion" exec="traffic_light_multi_camera_fusion_node" name="traffic_light_multi_camera_fusion" output="screen">
25+
<param name="camera_namespaces" value="$(var all_camera_namespaces)"/>
26+
<param name="perform_group_fusion" value="true"/>
27+
<remap from="~/input/vector_map" to="/map/vector_map"/>
28+
<remap from="~/output/traffic_signals" to="$(var fusion/traffic_signals)"/>
29+
</node>
30+
</group>
31+
32+
<!-- crosswalk traffic light estimator -->
33+
<group if="$(var use_crosswalk_traffic_light_estimator)">
34+
<node pkg="crosswalk_traffic_light_estimator" exec="crosswalk_traffic_light_estimator_node" name="crosswalk_traffic_light_estimator" output="screen">
35+
<remap from="~/input/vector_map" to="/map/vector_map"/>
36+
<remap from="~/input/route" to="/planning/mission_planning/route"/>
37+
<remap from="~/input/classified/traffic_signals" to="$(var fusion/traffic_signals)"/>
38+
<remap from="~/output/traffic_signals" to="$(var internal/traffic_signals)"/>
39+
<param from="$(var crosswalk_traffic_light_estimator_param_file)"/>
40+
</node>
41+
</group>
42+
43+
<!-- topic relay (only when crosswalk traffic light estimator is disabled) -->
44+
<group unless="$(var use_crosswalk_traffic_light_estimator)">
45+
<node pkg="topic_tools" exec="relay" name="fusion_signals_relay" output="screen">
46+
<param name="input_topic" value="$(var fusion/traffic_signals)"/>
47+
<param name="output_topic" value="$(var internal/traffic_signals)"/>
48+
<param name="type" value="autoware_auto_perception_msgs/msg/TrafficSignalArray"/>
49+
</node>
50+
</group>
51+
52+
<!-- V2X fusion -->
53+
<group>
54+
<include file="$(find-pkg-share traffic_light_arbiter)/launch/traffic_light_arbiter.launch.xml">
55+
<arg name="perception_traffic_signals" value="$(var internal/traffic_signals)"/>
56+
<arg name="external_traffic_signals" value="$(var external/traffic_signals)"/>
57+
<arg name="output_traffic_signals" value="$(var output/traffic_signals)"/>
58+
</include>
59+
</group>
60+
61+
<!-- visualizer -->
62+
<group>
63+
<include file="$(find-pkg-share traffic_light_visualization)/launch/traffic_light_map_visualizer.launch.xml"/>
64+
</group>
65+
</group>
66+
</launch>

0 commit comments

Comments
 (0)