Skip to content

Commit ea36f9e

Browse files
authored
Merge branch 'main' into refactor/image_projection_param
2 parents 0b8979f + 9039471 commit ea36f9e

File tree

45 files changed

+296
-154
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

45 files changed

+296
-154
lines changed

autoware_launch/config/control/control_validator/control_validator.param.yaml

-2
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,6 @@
11
/**:
22
ros__parameters:
33

4-
publish_diag: false # if true, diagnostic msg is published
5-
64
# If the number of consecutive invalid predicted_path exceeds this threshold, the Diag will be set to ERROR.
75
# (For example, threshold = 1 means, even if the predicted_path is invalid, Diag will not be ERROR if
86
# the next predicted_path is valid.)

autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@
1313
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)
1414

1515
# -- trajectory extending --
16-
extend_trajectory_for_end_yaw_control: true # flag of trajectory extending for terminal yaw control
16+
extend_trajectory_for_end_yaw_control: false # flag of trajectory extending for terminal yaw control
1717

1818
# -- mpc optimization --
1919
qp_solver_type: "osqp" # optimization solver option (unconstraint_fast or osqp)

autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml

+3-2
Original file line numberDiff line numberDiff line change
@@ -69,8 +69,9 @@
6969
max_jerk: 2.0
7070
min_jerk: -5.0
7171

72-
# pitch
73-
use_trajectory_for_pitch_calculation: false
72+
# slope compensation
7473
lpf_pitch_gain: 0.95
74+
slope_source: "raw_pitch" # raw_pitch, trajectory_pitch or trajectory_adaptive
75+
adaptive_trajectory_velocity_th: 1.0
7576
max_pitch_rad: 0.1
7677
min_pitch_rad: -0.1

autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
update_rate: 10.0
44
system_emergency_heartbeat_timeout: 0.5
55
use_emergency_handling: false
6-
check_external_emergency_heartbeat: false
6+
check_external_emergency_heartbeat: $(var check_external_emergency_heartbeat)
77
use_start_request: false
88
enable_cmd_limit_filter: true
99
filter_activated_count_threshold: 5
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,40 @@
1+
/**:
2+
ros__parameters:
3+
# marker_size
4+
marker_size: 0.6
5+
6+
# target_tag_ids
7+
target_tag_ids: ['0','1','2','3','4','5','6']
8+
9+
# base_covariance
10+
# This value is dynamically scaled according to the distance at which AR tags are detected.
11+
base_covariance: [0.2, 0.0, 0.0, 0.0, 0.0, 0.0,
12+
0.0, 0.2, 0.0, 0.0, 0.0, 0.0,
13+
0.0, 0.0, 0.2, 0.0, 0.0, 0.0,
14+
0.0, 0.0, 0.0, 0.02, 0.0, 0.0,
15+
0.0, 0.0, 0.0, 0.0, 0.02, 0.0,
16+
0.0, 0.0, 0.0, 0.0, 0.0, 0.02]
17+
18+
# Detect AR-Tags within this range and publish the pose of ego vehicle
19+
distance_threshold: 13.0 # [m]
20+
21+
# consider_orientation
22+
consider_orientation: false
23+
24+
# Detector parameters
25+
# See https://github.com/pal-robotics/aruco_ros/blob/7787a6794d30c248bc546d1582e65dd47bc40c12/aruco/include/aruco/markerdetector.h#L106-L126
26+
detection_mode: "DM_NORMAL" # select from [DM_NORMAL, DM_FAST, DM_VIDEO_FAST]
27+
min_marker_size: 0.02
28+
29+
# Parameters for comparison with EKF Pose
30+
# If the difference between the EKF pose and the current pose is within the range of values set below, the current pose is published.
31+
# [How to determine the value]
32+
# * ekf_time_tolerance: Since it is abnormal if the data comes too old from EKF, the tentative tolerance value is set at 5 seconds.
33+
# This value is assumed to be unaffected even if it is increased or decreased by some amount.
34+
# * ekf_position_tolerance: Since it is possible that multiple AR tags with the same ID could be placed, the tolerance should be as small as possible.
35+
# And if the vehicle is running only on odometry in a section without AR tags,
36+
# it is possible that self-position estimation could be off by a few meters.
37+
# it should be fixed by AR tag detection, so tolerance should not be smaller than 10 meters.
38+
# Therefore, the tolerance is set at 10 meters.
39+
ekf_time_tolerance: 5.0 # [s]
40+
ekf_position_tolerance: 10.0 # [m]
Original file line numberDiff line numberDiff line change
@@ -1,37 +1,46 @@
11
/**:
22
ros__parameters:
3-
show_debug_info: false
4-
enable_yaw_bias_estimation: true
5-
predict_frequency: 50.0
6-
tf_rate: 50.0
7-
publish_tf: true
8-
extend_state_step: 50
3+
node:
4+
show_debug_info: false
5+
enable_yaw_bias_estimation: true
6+
predict_frequency: 50.0
7+
tf_rate: 50.0
8+
publish_tf: true
9+
extend_state_step: 50
910

10-
# for Pose measurement
11-
pose_additional_delay: 0.0
12-
pose_measure_uncertainty_time: 0.01
13-
pose_smoothing_steps: 5
14-
pose_gate_dist: 10000.0
11+
pose_measurement:
12+
# for Pose measurement
13+
pose_additional_delay: 0.0
14+
pose_measure_uncertainty_time: 0.01
15+
pose_smoothing_steps: 5
16+
pose_gate_dist: 10000.0
1517

16-
# for twist measurement
17-
twist_additional_delay: 0.0
18-
twist_smoothing_steps: 2
19-
twist_gate_dist: 10000.0
18+
twist_measurement:
19+
# for twist measurement
20+
twist_additional_delay: 0.0
21+
twist_smoothing_steps: 2
22+
twist_gate_dist: 10000.0
2023

21-
# for process model
22-
proc_stddev_yaw_c: 0.005
23-
proc_stddev_vx_c: 10.0
24-
proc_stddev_wz_c: 5.0
24+
process_noise:
25+
# for process model
26+
proc_stddev_yaw_c: 0.005
27+
proc_stddev_vx_c: 10.0
28+
proc_stddev_wz_c: 5.0
2529

26-
#Simple1DFilter parameters
27-
z_filter_proc_dev: 1.0
28-
roll_filter_proc_dev: 0.01
29-
pitch_filter_proc_dev: 0.01
30-
# for diagnostics
31-
pose_no_update_count_threshold_warn: 50
32-
pose_no_update_count_threshold_error: 100
33-
twist_no_update_count_threshold_warn: 50
34-
twist_no_update_count_threshold_error: 100
30+
simple_1d_filter_parameters:
31+
#Simple1DFilter parameters
32+
z_filter_proc_dev: 1.0
33+
roll_filter_proc_dev: 0.01
34+
pitch_filter_proc_dev: 0.01
3535

36-
# for velocity measurement limitation (Set 0.0 if you want to ignore)
37-
threshold_observable_velocity_mps: 0.0 # [m/s]
36+
diagnostics:
37+
# for diagnostics
38+
pose_no_update_count_threshold_warn: 50
39+
pose_no_update_count_threshold_error: 100
40+
twist_no_update_count_threshold_warn: 50
41+
twist_no_update_count_threshold_error: 100
42+
43+
misc:
44+
# for velocity measurement limitation (Set 0.0 if you want to ignore)
45+
threshold_observable_velocity_mps: 0.0 # [m/s]
46+
pose_frame_id: "map"

autoware_launch/config/localization/pose_initializer.param.yaml

+5
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,11 @@
22
ros__parameters:
33
gnss_pose_timeout: 3.0 # [sec]
44
stop_check_duration: 3.0 # [sec]
5+
ekf_enabled: $(var ekf_enabled)
6+
gnss_enabled: $(var gnss_enabled)
7+
yabloc_enabled: $(var yabloc_enabled)
8+
ndt_enabled: $(var ndt_enabled)
9+
stop_check_enabled: $(var stop_check_enabled)
510

611
# from gnss
712
gnss_particle_covariance:
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,4 @@
11
/**:
22
ros__parameters:
33
center_line_resolution: 5.0 # [m]
4+
lanelet2_map_path: $(var lanelet2_map_path) # The lanelet2 map path
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
/**:
2+
ros__parameters:
3+
map_frame: map
4+
viewer_frame: viewer

autoware_launch/config/map/pointcloud_map_loader.param.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -7,3 +7,5 @@
77

88
# only used when downsample_whole_load enabled
99
leaf_size: 3.0 # downsample leaf size [m]
10+
pcd_paths_or_directory: [$(var pointcloud_map_path)] # Path to the pointcloud map file or directory
11+
pcd_metadata_path: $(var pointcloud_map_metadata_path) # Path to pointcloud metadata file

autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint.param.yaml

+11
Original file line numberDiff line numberDiff line change
@@ -13,3 +13,14 @@
1313
iou_nms_search_distance_2d: 10.0
1414
iou_nms_threshold: 0.1
1515
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
16+
score_threshold: 0.35
17+
has_twist: false
18+
trt_precision: fp16
19+
densification_num_past_frames: 1
20+
densification_world_frame_id: map
21+
22+
# weight files
23+
encoder_onnx_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"
24+
encoder_engine_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).engine"
25+
head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"
26+
head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"

autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_tiny.param.yaml

+11
Original file line numberDiff line numberDiff line change
@@ -13,3 +13,14 @@
1313
iou_nms_search_distance_2d: 10.0
1414
iou_nms_threshold: 0.1
1515
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
16+
score_threshold: 0.35
17+
has_twist: false
18+
trt_precision: fp16
19+
densification_num_past_frames: 1
20+
densification_world_frame_id: map
21+
22+
# weight files
23+
encoder_onnx_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"
24+
encoder_engine_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).engine"
25+
head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"
26+
head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"

autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml

+6
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,11 @@
11
/**:
22
ros__parameters:
3+
trt_precision: fp16
4+
encoder_onnx_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"
5+
encoder_engine_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).engine"
6+
head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"
7+
head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"
8+
39
model_params:
410
class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
511
paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"]

autoware_launch/config/perception/object_recognition/prediction/map_based_prediction.param.yaml

+6
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,12 @@
1919
use_vehicle_acceleration: false # whether to consider current vehicle acceleration when predicting paths or not
2020
speed_limit_multiplier: 1.5 # When using vehicle acceleration. Set vehicle's maximum predicted speed as the legal speed limit in that lanelet times this value
2121
acceleration_exponential_half_life: 2.5 # [s] When using vehicle acceleration. The decaying acceleration model considers that the current vehicle acceleration will be halved after this many seconds
22+
crosswalk_with_signal:
23+
use_crosswalk_signal: true
24+
threshold_velocity_assumed_as_stopping: 0.25 # [m/s] velocity threshold for the module to judge whether the objects is stopped
25+
# If the pedestrian does not move for X seconds against green signal, the module judge that the pedestrian has no intention to walk.
26+
distance_set_for_no_intention_to_walk: [1.0, 5.0] # [m] ascending order, keys of map
27+
timeout_set_for_no_intention_to_walk: [1.0, 0.0] # [s] values of map
2228
# parameter for shoulder lane prediction
2329
prediction_time_horizon_rate_for_validate_shoulder_lane_length: 0.8
2430

autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/radar_object_tracker.param.yaml

+3
Original file line numberDiff line numberDiff line change
@@ -24,3 +24,6 @@
2424
max_distance_from_lane: 5.0 # [m]
2525
max_angle_diff_from_lane: 0.785398 # [rad] (45 deg)
2626
max_lateral_velocity: 7.0 # [m/s]
27+
28+
# tracking model parameters
29+
tracking_config_directory: $(find-pkg-share autoware_launch)/config/perception/object_recognition/tracking/radar_object_tracker/tracking/

autoware_launch/config/perception/traffic_light_arbiter/traffic_light_arbiter.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -3,3 +3,4 @@
33
external_time_tolerance: 5.0
44
perception_time_tolerance: 1.0
55
external_priority: false
6+
enable_signal_matching: false

autoware_launch/config/planning/preset/default_preset.yaml

+3
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,9 @@ launch:
99
- arg:
1010
name: launch_dynamic_avoidance_module
1111
default: "false"
12+
- arg:
13+
name: launch_sampling_planner_module
14+
default: "false" # Warning, experimental module, use only in simulations
1215
- arg:
1316
name: launch_lane_change_right_module
1417
default: "true"

autoware_launch/config/planning/scenario_planning/common/common.param.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,7 @@
11
/**:
22
ros__parameters:
3+
max_vel: 11.1 # max velocity limit [m/s]
4+
35
# constraints param for normal driving
46
normal:
57
min_acc: -1.0 # min deceleration [m/ss]

autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml

+4-5
Original file line numberDiff line numberDiff line change
@@ -1,32 +1,31 @@
11
/**:
22
ros__parameters:
33
# motion state constraints
4-
max_velocity: 20.0 # max velocity limit [m/s]
54
stop_decel: 0.0 # deceleration at a stop point[m/ss]
65

76
# external velocity limit parameter
87
margin_to_insert_external_velocity_limit: 0.3 # margin distance to insert external velocity limit [m]
98

109
# -- curve parameters --
1110
# common parameters
12-
curvature_calculation_distance: 5.0 # distance of points while curvature is calculating for the steer rate and lateral acceleration limit [m]
11+
curvature_calculation_distance: 2.0 # distance of points while curvature is calculating for the steer rate and lateral acceleration limit [m]
1312
# lateral acceleration limit parameters
1413
enable_lateral_acc_limit: true # To toggle the lateral acc filter on and off. You can switch it dynamically at runtime.
1514
max_lateral_accel: 1.0 # max lateral acceleration limit [m/ss]
16-
min_curve_velocity: 2.74 # min velocity at lateral acceleration limit and steering angle rate limit [m/s]
15+
min_curve_velocity: 2.0 # min velocity at lateral acceleration limit and steering angle rate limit [m/s]
1716
decel_distance_before_curve: 3.5 # slow speed distance before a curve for lateral acceleration limit
1817
decel_distance_after_curve: 2.0 # slow speed distance after a curve for lateral acceleration limit
1918
min_decel_for_lateral_acc_lim_filter: -2.5 # deceleration limit applied in the lateral acceleration filter to avoid sudden braking [m/ss]
2019
# steering angle rate limit parameters
2120
enable_steering_rate_limit: true # To toggle the steer rate filter on and off. You can switch it dynamically at runtime.
22-
max_steering_angle_rate: 40.0 # maximum steering angle rate [degree/s]
21+
max_steering_angle_rate: 11.5 # maximum steering angle rate [degree/s]
2322
resample_ds: 0.1 # distance between trajectory points [m]
2423
curvature_threshold: 0.02 # if curvature > curvature_threshold, steeringRateLimit is triggered [1/m]
2524

2625
# engage & replan parameters
2726
replan_vel_deviation: 5.53 # velocity deviation to replan initial velocity [m/s]
2827
engage_velocity: 0.25 # engage velocity threshold [m/s] (if the trajectory velocity is higher than this value, use this velocity for engage vehicle speed)
29-
engage_acceleration: 0.1 # engage acceleration [m/ss] (use this acceleration when engagement)
28+
engage_acceleration: 0.5 # engage acceleration [m/ss] (use this acceleration when engagement)
3029
engage_exit_ratio: 0.5 # exit engage sequence to normal velocity planning when the velocity exceeds engage_exit_ratio x engage_velocity.
3130
stop_dist_to_prohibit_engage: 0.5 # if the stop point is in this distance, the speed is set to 0 not to move the vehicle [m]
3231

autoware_launch/config/planning/scenario_planning/common/planning_validator/planning_validator.param.yaml

+11
Original file line numberDiff line numberDiff line change
@@ -26,3 +26,14 @@
2626
steering_rate: 10.0
2727
velocity_deviation: 100.0
2828
distance_deviation: 100.0
29+
longitudinal_distance_deviation: 1.0
30+
31+
parameters:
32+
# The required trajectory length is calculated as the distance needed
33+
# to stop from the current speed at this deceleration.
34+
forward_trajectory_length_acceleration: -3.0
35+
36+
# An error is raised if the required trajectory length is less than this distance.
37+
# Setting it to 0 means an error will occur if even slightly exceeding the end of the path,
38+
# therefore, a certain margin is necessary.
39+
forward_trajectory_length_margin: 2.0

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

+3-2
Original file line numberDiff line numberDiff line change
@@ -127,7 +127,7 @@
127127
object_check_return_pose_distance: 20.0 # [m]
128128
# filtering parking objects
129129
threshold_distance_object_is_on_center: 1.0 # [m]
130-
object_check_shiftable_ratio: 0.6 # [-]
130+
object_check_shiftable_ratio: 0.8 # [-]
131131
object_check_min_road_shoulder_width: 0.5 # [m]
132132
# lost object compensation
133133
object_last_seen_threshold: 2.0
@@ -187,6 +187,7 @@
187187
time_horizon_for_rear_object: 10.0 # [s]
188188
delay_until_departure: 0.0 # [s]
189189
# rss parameters
190+
extended_polygon_policy: "along_path" # [-] select "rectangle" or "along_path"
190191
expected_front_deceleration: -1.0 # [m/ss]
191192
expected_rear_deceleration: -1.0 # [m/ss]
192193
rear_vehicle_reaction_time: 2.0 # [s]
@@ -206,7 +207,7 @@
206207
hard_road_shoulder_margin: 0.3 # [m]
207208
max_right_shift_length: 5.0
208209
max_left_shift_length: 5.0
209-
max_deviation_from_lane: 0.5 # [m]
210+
max_deviation_from_lane: 0.2 # [m]
210211
# avoidance distance parameters
211212
longitudinal:
212213
min_prepare_time: 1.0 # [s]

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

+4-2
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,9 @@
3939
object_recognition_collision_check_max_extra_stopping_margin: 1.0
4040
th_moving_object_velocity: 1.0
4141
detection_bound_offset: 15.0
42+
outer_road_detection_offset: 1.0
43+
inner_road_detection_offset: 0.0
44+
4245

4346
# pull over
4447
pull_over:
@@ -128,7 +131,7 @@
128131
delay_until_departure: 1.0
129132
# For target object filtering
130133
target_filtering:
131-
safety_check_time_horizon: 5.0
134+
safety_check_time_horizon: 10.0
132135
safety_check_time_resolution: 1.0
133136
# detection range
134137
object_check_forward_distance: 100.0
@@ -164,7 +167,6 @@
164167
method: "integral_predicted_polygon"
165168
keep_unsafe_time: 3.0
166169
# collision check parameters
167-
check_all_predicted_path: true
168170
publish_debug_marker: false
169171
rss_params:
170172
rear_vehicle_reaction_time: 2.0

0 commit comments

Comments
 (0)