Skip to content

Commit

Permalink
Merge pull request autowarefoundation#879 from tier4/feature/xx1-gen1…
Browse files Browse the repository at this point in the history
…_2-launcher

feat(autoware_launcher): update for xx1 gen2
  • Loading branch information
N-Eiki authored Jun 21, 2024
2 parents 68ab822 + 7792f69 commit c86f45e
Show file tree
Hide file tree
Showing 10 changed files with 356 additions and 23 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,76 @@
/**:
ros__parameters:
# -- system --
traj_resample_dist: 0.1 # path resampling interval [m]
use_steer_prediction: false # flag for using steer prediction (do not use steer measurement)
admissible_position_error: 5.0 # stop mpc calculation when error is larger than the following value
admissible_yaw_error_rad: 1.57 # stop mpc calculation when error is larger than the following value

# -- path smoothing --
enable_path_smoothing: true # flag for path smoothing
path_filter_moving_ave_num: 25 # param of moving average filter for path smoothing
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)
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)

# -- trajectory extending --
extend_trajectory_for_end_yaw_control: true # flag of trajectory extending for terminal yaw control

# -- mpc optimization --
qp_solver_type: "osqp" # optimization solver option (unconstraint_fast or osqp)
mpc_prediction_horizon: 50 # prediction horizon step
mpc_prediction_dt: 0.1 # prediction horizon period [s]
mpc_weight_lat_error: 0.2 # lateral error weight in matrix Q
mpc_weight_heading_error: 0.0 # heading error weight in matrix Q
mpc_weight_heading_error_squared_vel: 0.03 # heading error * velocity weight in matrix Q
mpc_weight_steering_input: 1.0 # steering error weight in matrix R
mpc_weight_steering_input_squared_vel: 1.00 # steering error * velocity weight in matrix R
mpc_weight_lat_jerk: 0.0 # lateral jerk weight in matrix R
mpc_weight_steer_rate: 0.0 # steering rate weight in matrix R
mpc_weight_steer_acc: 0.000001 # steering angular acceleration weight in matrix R
mpc_low_curvature_weight_lat_error: 0.05 # lateral error weight in matrix Q in low curvature point
mpc_low_curvature_weight_heading_error: 0.0 # heading error weight in matrix Q in low curvature point
mpc_low_curvature_weight_heading_error_squared_vel: 0.03 # heading error * velocity weight in matrix Q in low curvature point
mpc_low_curvature_weight_steering_input: 1.0 # steering error weight in matrix R in low curvature point
mpc_low_curvature_weight_steering_input_squared_vel: 2.00 # steering error * velocity weight in matrix R in low curvature point
mpc_low_curvature_weight_lat_jerk: 0.0 # lateral jerk weight in matrix R in low curvature point
mpc_low_curvature_weight_steer_rate: 0.0 # steering rate weight in matrix R in low curvature point
mpc_low_curvature_weight_steer_acc: 0.000001 # steering angular acceleration weight in matrix R in low curvature point
mpc_low_curvature_thresh_curvature: 0.03 # threshold of curvature to use "low_curvature" parameter (recommend: 0.01~0.03)
mpc_weight_terminal_lat_error: 1.0 # terminal lateral error weight in matrix Q to improve mpc stability
mpc_weight_terminal_heading_error: 0.1 # terminal heading error weight in matrix Q to improve mpc stability
mpc_zero_ff_steer_deg: 0.5 # threshold that feed-forward angle becomes zero
mpc_acceleration_limit: 2.0 # limit on the vehicle's acceleration
mpc_velocity_time_constant: 0.3 # time constant used for velocity smoothing
mpc_min_prediction_length: 5.0 # minimum prediction length

# -- vehicle model --
vehicle_model_type: "kinematics" # vehicle model type for mpc prediction. option is kinematics, kinematics_no_delay, and dynamics
input_delay: 0.1 # steering input delay time for delay compensation
vehicle_model_steer_tau: 0.1 # steering dynamics time constant (1d approximation) [s]
steer_rate_lim_dps_list_by_curvature: [20.0, 20.0, 20.0] # steering angle rate limit list depending on curvature [deg/s]
curvature_list_for_steer_rate_lim: [0.001, 0.002, 0.01] # curvature list for steering angle rate limit interpolation in ascending order [/m]
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]
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]
acceleration_limit: 1.0 # acceleration limit for trajectory velocity modification [m/ss]
velocity_time_constant: 0.3 # velocity dynamics time constant for trajectory velocity modification [s]

# -- lowpass filter for noise reduction --
steering_lpf_cutoff_hz: 10.0 # cutoff frequency of lowpass filter for steering command [Hz]
error_deriv_lpf_cutoff_hz: 5.0

# stop state: steering command is kept in the previous value in the stop state.
stop_state_entry_ego_speed: 0.2
stop_state_entry_target_speed: 0.2
converged_steer_rad: 0.1
keep_steer_control_until_converged: true
new_traj_duration_time: 1.0
new_traj_end_dist: 0.3
mpc_converged_threshold_rps: 0.01 # threshold of mpc convergence check [rad/s]

# steer offset
steering_offset:
enable_auto_steering_offset_removal: true
update_vel_threshold: 5.56
update_steer_threshold: 0.035
average_num: 1000
steering_offset_limit: 0.02
Original file line number Diff line number Diff line change
@@ -0,0 +1,76 @@
/**:
ros__parameters:
delay_compensation_time: 0.40

enable_smooth_stop: true
enable_overshoot_emergency: false
enable_large_tracking_error_emergency: false
enable_slope_compensation: true
enable_keep_stopped_until_steer_convergence: true

# state transition
drive_state_stop_dist: 0.5
drive_state_offset_stop_dist: 1.0
stopping_state_stop_dist: 0.5
stopped_state_entry_duration_time: 0.1
stopped_state_entry_vel: 0.01
stopped_state_entry_acc: 0.1
emergency_state_overshoot_stop_dist: 1.5
emergency_state_traj_trans_dev: 3.0
emergency_state_traj_rot_dev: 0.7854

# drive state
kp: 2.0
ki: 0.02
kd: 0.0
max_out: 1.0
min_out: -5.0
max_p_effort: 0.5
min_p_effort: -5.0
max_i_effort: 0.3
min_i_effort: -0.3
max_d_effort: 0.0
min_d_effort: 0.0
lpf_vel_error_gain: 0.9
enable_integration_at_low_speed: false
current_vel_threshold_pid_integration: 0.5
time_threshold_before_pid_integration: 2.0
enable_brake_keeping_before_stop: false
brake_keeping_acc: -0.2

# smooth stop state
smooth_stop_max_strong_acc: -0.8
smooth_stop_min_strong_acc: -1.3
smooth_stop_weak_acc: -0.4
smooth_stop_weak_stop_acc: -0.8
smooth_stop_strong_stop_acc: -3.4
smooth_stop_max_fast_vel: 0.5
smooth_stop_min_running_vel: 0.01
smooth_stop_min_running_acc: 0.01
smooth_stop_weak_stop_time: 4.0
smooth_stop_weak_stop_dist: -0.3
smooth_stop_strong_stop_dist: -0.5

# stopped state
stopped_vel: 0.0
stopped_acc: -3.4
stopped_jerk: -5.0

# emergency state
emergency_vel: 0.0
emergency_acc: -5.0
emergency_jerk: -3.0

# acceleration limit
max_acc: 3.0
min_acc: -5.0

# jerk limit
max_jerk: 3.5
min_jerk: -5.0

# pitch
use_trajectory_for_pitch_calculation: false
lpf_pitch_gain: 0.95
max_pitch_rad: 0.1
min_pitch_rad: -0.1
Original file line number Diff line number Diff line change
@@ -1,21 +1,32 @@
/**:
ros__parameters:
trt_precision: fp16
encoder_onnx_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"
encoder_engine_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).engine"
head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"
head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"
trt_precision: fp16

model_params:
class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"]
point_feature_size: 7 # x, y, z, time-lag and car, pedestrian, bicycle
max_voxel_size: 40000
point_cloud_range: [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0]
voxel_size: [0.32, 0.32, 8.0]
downsample_factor: 1
encoder_in_feature_size: 12
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
has_twist: false
densification_params:
world_frame_id: "map"
num_past_frames: 0
post_process_params:
# post-process params
circle_nms_dist_threshold: 0.3
iou_nms_target_class_names: ["CAR"]
iou_nms_search_distance_2d: 10.0
iou_nms_threshold: 0.1
score_threshold: 0.45
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
densification_params:
world_frame_id: "map"
num_past_frames: 1
score_threshold: 0.35
omp_params:
# omp params
num_threads: 1
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
# sample grid map fusion parameters for sample sensor kit
/**:
ros__parameters:
# shared parameters
Expand All @@ -12,10 +11,6 @@
map_length_x: 150.0 # [m]
map_length_y: 150.0 # [m]

# downsample input pointcloud
downsample_input_pointcloud: true
downsample_voxel_size: 0.25 # [m]

# each grid map parameters
ogm_creation_config:
height_filter:
Expand All @@ -24,7 +19,7 @@
max_height: 2.0
enable_single_frame_mode: true
# use sensor pointcloud to filter obstacle pointcloud
filter_obstacle_pointcloud_by_raw_pointcloud: false
filter_obstacle_pointcloud_by_raw_pointcloud: true

grid_map_type: "OccupancyGridMapFixedBlindSpot"
OccupancyGridMapFixedBlindSpot:
Expand All @@ -40,17 +35,23 @@
# Setting1: tune ogm creation parameters
raw_pointcloud_topics: # put each sensor's pointcloud topic
- "/sensing/lidar/top/pointcloud"
- "/sensing/lidar/left/pointcloud"
- "/sensing/lidar/right/pointcloud"
- "/sensing/lidar/side_left/pointcloud"
- "/sensing/lidar/side_right/pointcloud"
- "/sensing/lidar/front_left/pointcloud"
- "/sensing/lidar/front_right/pointcloud"
fusion_input_ogm_topics:
- "/perception/occupancy_grid_map/top_lidar/map"
- "/perception/occupancy_grid_map/left_lidar/map"
- "/perception/occupancy_grid_map/right_lidar/map"
- "/perception/occupancy_grid_map/top/map"
- "/perception/occupancy_grid_map/side_left/map"
- "/perception/occupancy_grid_map/side_right/map"
- "/perception/occupancy_grid_map/front_left/map"
- "/perception/occupancy_grid_map/front_right/map"
# reliability of each sensor (0.0 ~ 1.0) only work with "log-odds" and "dempster-shafer"
input_ogm_reliabilities:
- 1.0
- 0.6
- 0.6
- 0.6
- 0.6

# Setting2: tune ogm fusion parameters
## choose fusion method from ["overwrite", "log-odds", "dempster-shafer"]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -293,4 +293,11 @@

# for debug
debug:
marker: false
enable_other_objects_marker: true
enable_other_objects_info: true
enable_detection_area_marker: false
enable_drivable_bound_marker: false
enable_safety_check_marker: false
enable_shift_line_marker: false
enable_lane_marker: false
enable_misc_marker: false
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,12 @@
blind_spot:
use_pass_judge_line: true
stop_line_margin: 1.0 # [m]
backward_length: 50.0 # [m]
ignore_width_from_center_line: 0.0 # [m]
max_future_movement_time: 10.0 # [second]
threshold_yaw_diff: 0.523 # [rad]
backward_detection_length: 100.0 # [m]
ignore_width_from_center_line: 0.7 # [m]
adjacent_extend_width: 1.5 # [m]
opposite_adjacent_extend_width: 1.5 # [m]
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.
max_future_movement_time: 10.0 # [second]
ttc_min: -5.0 # [s]
ttc_max: 5.0 # [s]
ttc_ego_minimal_velocity: 5.0 # [m/s]
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
4 changes: 4 additions & 0 deletions autoware_launch/launch/autoware.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
<arg name="launch_planning" default="true" description="launch planning"/>
<arg name="launch_control" default="true" description="launch control"/>
<arg name="launch_api" default="true" description="launch api"/>

<!-- Global parameters -->
<arg name="use_sim_time" default="false" description="use_sim_time"/>
<!-- Vehicle -->
Expand Down Expand Up @@ -115,8 +116,11 @@

<!-- Perception -->
<group if="$(var launch_perception)">
<let name="occupancy_grid_map_method" value="multi_lidar_pointcloud_based_occupancy_grid_map" if="$(eval &quot;'aip_xx1_gen2' == '$(var sensor_model)'&quot;)"/>
<let name="occupancy_grid_map_method" value="pointcloud_based_occupancy_grid_map" unless="$(eval &quot;'aip_xx1_gen2' == '$(var sensor_model)'&quot;)"/>
<include file="$(find-pkg-share autoware_launch)/launch/components/tier4_perception_component.launch.xml">
<arg name="data_path" value="$(var data_path)"/>
<arg name="occupancy_grid_map_method" value="$(var occupancy_grid_map_method)"/>
</include>
</group>

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

<!-- 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.
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. -->
<include file="$(find-pkg-share autoware_launch)/launch/components/traffic_light_recognition/traffic_light.launch.xml"/>
<!-- NOTE: Override by false to disable conventional traffic light recognition launch -->
<let name="use_traffic_light_recognition" value="false"/>

<include file="$(find-pkg-share tier4_perception_launch)/launch/perception.launch.xml">
<arg name="mode" value="$(var perception_mode)"/>
<arg name="vehicle_param_file" value="$(find-pkg-share $(var vehicle_model)_description)/config/vehicle_info.param.yaml"/>
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
<?xml version="1.0"?>
<launch>
<arg name="use_crosswalk_traffic_light_estimator" default="true" description="output pedestrian's traffic light signals"/>

<arg name="input/cloud" default="/sensing/lidar/top/pointcloud_raw" description="point cloud for occlusion prediction"/>
<arg name="internal/traffic_signals" default="/perception/traffic_light_recognition/internal/traffic_signals"/>
<arg name="fusion/traffic_signals" default="/perception/traffic_light_recognition/fusion/traffic_signals"/>
<arg name="external/traffic_signals" default="/perception/traffic_light_recognition/external/traffic_signals"/>
<arg name="output/traffic_signals" default="/perception/traffic_light_recognition/traffic_signals"/>
<arg name="crosswalk_traffic_light_estimator_param_file" default="$(find-pkg-share crosswalk_traffic_light_estimator)/config/crosswalk_traffic_light_estimator.param.yaml"/>

<group>
<push-ros-namespace namespace="perception"/>
<push-ros-namespace namespace="traffic_light_recognition"/>

<!-- traffic light occlusion predictor for some cameras -->
<arg name="all_camera_namespaces" default="[camera6, camera5, camera2, camera0]"/>
<include file="$(find-pkg-share autoware_launch)/launch/components/traffic_light_recognition/traffic_light_occlusion_predictor.launch.py">
<arg name="all_camera_namespaces" value="$(var all_camera_namespaces)"/>
</include>

<!-- traffic light multi camera fusion -->
<group>
<node pkg="traffic_light_multi_camera_fusion" exec="traffic_light_multi_camera_fusion_node" name="traffic_light_multi_camera_fusion" output="screen">
<param name="camera_namespaces" value="$(var all_camera_namespaces)"/>
<param name="perform_group_fusion" value="true"/>
<remap from="~/input/vector_map" to="/map/vector_map"/>
<remap from="~/output/traffic_signals" to="$(var fusion/traffic_signals)"/>
</node>
</group>

<!-- crosswalk traffic light estimator -->
<group if="$(var use_crosswalk_traffic_light_estimator)">
<node pkg="crosswalk_traffic_light_estimator" exec="crosswalk_traffic_light_estimator_node" name="crosswalk_traffic_light_estimator" output="screen">
<remap from="~/input/vector_map" to="/map/vector_map"/>
<remap from="~/input/route" to="/planning/mission_planning/route"/>
<remap from="~/input/classified/traffic_signals" to="$(var fusion/traffic_signals)"/>
<remap from="~/output/traffic_signals" to="$(var internal/traffic_signals)"/>
<param from="$(var crosswalk_traffic_light_estimator_param_file)"/>
</node>
</group>

<!-- topic relay (only when crosswalk traffic light estimator is disabled) -->
<group unless="$(var use_crosswalk_traffic_light_estimator)">
<node pkg="topic_tools" exec="relay" name="fusion_signals_relay" output="screen">
<param name="input_topic" value="$(var fusion/traffic_signals)"/>
<param name="output_topic" value="$(var internal/traffic_signals)"/>
<param name="type" value="autoware_auto_perception_msgs/msg/TrafficSignalArray"/>
</node>
</group>

<!-- V2X fusion -->
<group>
<include file="$(find-pkg-share traffic_light_arbiter)/launch/traffic_light_arbiter.launch.xml">
<arg name="perception_traffic_signals" value="$(var internal/traffic_signals)"/>
<arg name="external_traffic_signals" value="$(var external/traffic_signals)"/>
<arg name="output_traffic_signals" value="$(var output/traffic_signals)"/>
</include>
</group>

<!-- visualizer -->
<group>
<include file="$(find-pkg-share traffic_light_visualization)/launch/traffic_light_map_visualizer.launch.xml"/>
</group>
</group>
</launch>
Loading

0 comments on commit c86f45e

Please sign in to comment.