Skip to content

Commit b0cfbce

Browse files
Merge branch 'awf-latest' into feat/keep_distance_back_static_objects_from_start_pose
Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
2 parents 0a26726 + 7e116ff commit b0cfbce

File tree

35 files changed

+206
-189
lines changed

35 files changed

+206
-189
lines changed
Original file line numberDiff line numberDiff line change
@@ -1,103 +1,114 @@
11
/**:
22
ros__parameters:
3-
# Vehicle reference frame
4-
base_frame: "base_link"
3+
frame:
4+
# Vehicle reference frame
5+
base_frame: "base_link"
56

6-
# NDT reference frame
7-
ndt_base_frame: "ndt_base_link"
7+
# NDT reference frame
8+
ndt_base_frame: "ndt_base_link"
89

9-
# map frame
10-
map_frame: "map"
10+
# Map frame
11+
map_frame: "map"
1112

12-
# Subscriber queue size
13-
input_sensor_points_queue_size: 1
1413

15-
# The maximum difference between two consecutive
16-
# transformations in order to consider convergence
17-
trans_epsilon: 0.01
14+
ndt:
15+
# The maximum difference between two consecutive
16+
# transformations in order to consider convergence
17+
trans_epsilon: 0.01
1818

19-
# The newton line search maximum step length
20-
step_size: 0.1
19+
# The newton line search maximum step length
20+
step_size: 0.1
2121

22-
# The ND voxel grid resolution
23-
resolution: 2.0
22+
# The ND voxel grid resolution
23+
resolution: 2.0
2424

25-
# The number of iterations required to calculate alignment
26-
max_iterations: 30
25+
# The number of iterations required to calculate alignment
26+
max_iterations: 30
2727

28-
# Converged param type
29-
# 0=TRANSFORM_PROBABILITY, 1=NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD
30-
converged_param_type: 1
28+
# Number of threads used for parallel computing
29+
num_threads: 4
3130

32-
# If converged_param_type is 0
33-
# Threshold for deciding whether to trust the estimation result
34-
converged_param_transform_probability: 3.0
31+
regularization:
32+
enable: false
3533

36-
# If converged_param_type is 1
37-
# Threshold for deciding whether to trust the estimation result
38-
converged_param_nearest_voxel_transformation_likelihood: 2.3
34+
# Regularization scale factor
35+
scale_factor: 0.01
3936

40-
# The number of particles to estimate initial pose
41-
initial_estimate_particles_num: 200
4237

43-
# The number of initial random trials in the TPE (Tree-Structured Parzen Estimator).
44-
# This value should be equal to or less than 'initial_estimate_particles_num' and more than 0.
45-
# If it is equal to 'initial_estimate_particles_num', the search will be the same as a full random search.
46-
n_startup_trials: 20
38+
initial_pose_estimation:
39+
# The number of particles to estimate initial pose
40+
particles_num: 200
4741

48-
# Tolerance of timestamp difference between current time and sensor pointcloud. [sec]
49-
lidar_topic_timeout_sec: 1.0
42+
# The number of initial random trials in the TPE (Tree-Structured Parzen Estimator).
43+
# This value should be equal to or less than 'initial_estimate_particles_num' and more than 0.
44+
# If it is equal to 'initial_estimate_particles_num', the search will be the same as a full random search.
45+
n_startup_trials: 20
5046

51-
# Tolerance of timestamp difference between initial_pose and sensor pointcloud. [sec]
52-
initial_pose_timeout_sec: 1.0
5347

54-
# Tolerance of distance difference between two initial poses used for linear interpolation. [m]
55-
initial_pose_distance_tolerance_m: 10.0
48+
validation:
49+
# Tolerance of timestamp difference between current time and sensor pointcloud. [sec]
50+
lidar_topic_timeout_sec: 1.0
5651

57-
# Number of threads used for parallel computing
58-
num_threads: 4
52+
# Tolerance of timestamp difference between initial_pose and sensor pointcloud. [sec]
53+
initial_pose_timeout_sec: 1.0
5954

60-
# The covariance of output pose
61-
# Note that this covariance matrix is empirically derived
62-
output_pose_covariance:
63-
[
64-
0.0225, 0.0, 0.0, 0.0, 0.0, 0.0,
65-
0.0, 0.0225, 0.0, 0.0, 0.0, 0.0,
66-
0.0, 0.0, 0.0225, 0.0, 0.0, 0.0,
67-
0.0, 0.0, 0.0, 0.000625, 0.0, 0.0,
68-
0.0, 0.0, 0.0, 0.0, 0.000625, 0.0,
69-
0.0, 0.0, 0.0, 0.0, 0.0, 0.000625,
70-
]
55+
# Tolerance of distance difference between two initial poses used for linear interpolation. [m]
56+
initial_pose_distance_tolerance_m: 10.0
7157

72-
# 2D Real-time covariance estimation with multiple searches (output_pose_covariance is the minimum value)
73-
use_covariance_estimation: false
58+
# The execution time which means probably NDT cannot matches scans properly. [ms]
59+
critical_upper_bound_exe_time_ms: 100.0
7460

75-
# Offset arrangement in covariance estimation [m]
76-
# initial_pose_offset_model_x & initial_pose_offset_model_y must have the same number of elements.
77-
initial_pose_offset_model_x: [0.0, 0.0, 0.5, -0.5, 1.0, -1.0]
78-
initial_pose_offset_model_y: [0.5, -0.5, 0.0, 0.0, 0.0, 0.0]
7961

80-
# Regularization switch
81-
regularization_enabled: false
62+
score_estimation:
63+
# Converged param type
64+
# 0=TRANSFORM_PROBABILITY, 1=NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD
65+
converged_param_type: 1
8266

83-
# Regularization scale factor
84-
regularization_scale_factor: 0.01
67+
# If converged_param_type is 0
68+
# Threshold for deciding whether to trust the estimation result
69+
converged_param_transform_probability: 3.0
8570

86-
# Dynamic map loading distance
87-
dynamic_map_loading_update_distance: 20.0
71+
# If converged_param_type is 1
72+
# Threshold for deciding whether to trust the estimation result
73+
converged_param_nearest_voxel_transformation_likelihood: 2.3
8874

89-
# Dynamic map loading loading radius
90-
dynamic_map_loading_map_radius: 150.0
75+
# Scan matching score based on no ground LiDAR scan
76+
no_ground_points:
77+
enable: false
9178

92-
# Radius of input LiDAR range (used for diagnostics of dynamic map loading)
93-
lidar_radius: 100.0
79+
# If lidar_point.z - base_link.z <= this threshold , the point will be removed
80+
z_margin_for_ground_removal: 0.8
9481

95-
# cspell: ignore degrounded
96-
# A flag for using scan matching score based on de-grounded LiDAR scan
97-
estimate_scores_for_degrounded_scan: false
9882

99-
# If lidar_point.z - base_link.z <= this threshold , the point will be removed
100-
z_margin_for_ground_removal: 0.8
83+
covariance:
84+
# The covariance of output pose
85+
# Note that this covariance matrix is empirically derived
86+
output_pose_covariance:
87+
[
88+
0.0225, 0.0, 0.0, 0.0, 0.0, 0.0,
89+
0.0, 0.0225, 0.0, 0.0, 0.0, 0.0,
90+
0.0, 0.0, 0.0225, 0.0, 0.0, 0.0,
91+
0.0, 0.0, 0.0, 0.000625, 0.0, 0.0,
92+
0.0, 0.0, 0.0, 0.0, 0.000625, 0.0,
93+
0.0, 0.0, 0.0, 0.0, 0.0, 0.000625,
94+
]
10195

102-
# The execution time which means probably NDT cannot matches scans properly. [ms]
103-
critical_upper_bound_exe_time_ms: 100
96+
# 2D Real-time covariance estimation with multiple searches (output_pose_covariance is the minimum value)
97+
covariance_estimation:
98+
enable: false
99+
100+
# Offset arrangement in covariance estimation [m]
101+
# initial_pose_offset_model_x & initial_pose_offset_model_y must have the same number of elements.
102+
initial_pose_offset_model_x: [0.0, 0.0, 0.5, -0.5, 1.0, -1.0]
103+
initial_pose_offset_model_y: [0.5, -0.5, 0.0, 0.0, 0.0, 0.0]
104+
105+
106+
dynamic_map_loading:
107+
# Dynamic map loading distance
108+
update_distance: 20.0
109+
110+
# Dynamic map loading loading radius
111+
map_radius: 150.0
112+
113+
# Radius of input LiDAR range (used for diagnostics of dynamic map loading)
114+
lidar_radius: 100.0
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
/**:
2+
ros__parameters:
3+
use_odom: true
4+
accel_lowpass_gain: 0.9
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
/**:
2+
ros__parameters:
3+
map_projector_info_path: $(var map_projector_info_path)
4+
lanelet2_map_path: $(var lanelet2_map_path)

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

+3-3
Original file line numberDiff line numberDiff line change
@@ -29,9 +29,9 @@
2929
max_area_matrix:
3030
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
3131
[ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN
32-
0.000, 0.000, 36.000, 0.000, inf, 0.000, 0.000, 0.000, #CAR
33-
0.000, 0.000, 0.000, 0.000, inf, 0.000, 0.000, 0.000, #TRUCK
34-
0.000, 0.000, 0.000, 0.000, inf, 0.000, 0.000, 0.000, #BUS
32+
0.000, 0.000, 36.000, 0.000, 999.999, 0.000, 0.000, 0.000, #CAR
33+
0.000, 0.000, 0.000, 0.000, 999.999, 0.000, 0.000, 0.000, #TRUCK
34+
0.000, 0.000, 0.000, 0.000, 999.999, 0.000, 0.000, 0.000, #BUS
3535
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #TRAILER
3636
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #MOTORBIKE
3737
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #BICYCLE

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

+7
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,12 @@
11
/**:
22
ros__parameters:
3+
trt_precision: fp16
4+
build_only: false
5+
encoder_onnx_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"
6+
encoder_engine_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).engine"
7+
head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"
8+
head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"
9+
310
model_params:
411
class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
512
paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"]
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
/**:
2+
ros__parameters:
3+
split_range: 80.0
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
/**:
2+
ros__parameters:
3+
split_range: 70.0
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
/**:
2+
ros__parameters:
3+
velocity_threshold: 5.5
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
/**:
2+
ros__parameters:
3+
velocity_threshold: 4.5
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
/**:
2+
ros__parameters:
3+
angle_threshold: 1.2210
4+
velocity_threshold: 1.5

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

+1
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
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+
use_crosswalk_signal: true
2223
# parameter for shoulder lane prediction
2324
prediction_time_horizon_rate_for_validate_shoulder_lane_length: 0.8
2425

autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/data_association_matrix.param.yaml

+3-3
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
lidar-lidar:
44
can_assign_matrix:
55
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN
6-
[0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
6+
[1, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
77
0, 1, 1, 1, 1, 0, 0, 0, #CAR
88
0, 1, 1, 1, 1, 0, 0, 0, #TRUCK
99
0, 1, 1, 1, 1, 0, 0, 0, #BUS
@@ -59,7 +59,7 @@
5959
lidar-radar:
6060
can_assign_matrix:
6161
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN
62-
[0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
62+
[1, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
6363
0, 1, 1, 1, 1, 0, 0, 0, #CAR
6464
0, 1, 1, 1, 1, 0, 0, 0, #TRUCK
6565
0, 1, 1, 1, 1, 0, 0, 0, #BUS
@@ -115,7 +115,7 @@
115115
radar-radar:
116116
can_assign_matrix:
117117
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN
118-
[0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
118+
[1, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
119119
0, 1, 1, 1, 1, 0, 0, 0, #CAR
120120
0, 1, 1, 1, 1, 0, 0, 0, #TRUCK
121121
0, 1, 1, 1, 1, 0, 0, 0, #BUS

autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/decorative_tracker_merger.param.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -23,4 +23,4 @@
2323

2424
# logging
2525
enable_logging: false
26-
log_file_path: "/tmp/decorative_tracker_merger.log"
26+
logging_file_path: "/tmp/decorative_tracker_merger.log"

autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml

+3
Original file line numberDiff line numberDiff line change
@@ -30,3 +30,6 @@
3030
detection_range_z_max: 2.5
3131
elevation_grid_mode: true
3232
use_recheck_ground_cluster: true
33+
low_priority_region_x: -20.0
34+
center_pcl_shift: 0.0
35+
radial_divider_angle_deg: 1.0

autoware_launch/config/planning/preset/default_preset.yaml

+3-3
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@ launch:
88
default: "true"
99
- arg:
1010
name: launch_dynamic_avoidance_module
11-
default: "false"
11+
default: "true"
1212
- arg:
1313
name: launch_lane_change_right_module
1414
default: "true"
@@ -97,7 +97,7 @@ launch:
9797

9898
- arg:
9999
name: motion_stop_planner_type
100-
default: obstacle_stop_planner
100+
default: obstacle_cruise_planner
101101
# option: obstacle_stop_planner
102102
# obstacle_cruise_planner
103103
# none
@@ -112,7 +112,7 @@ launch:
112112

113113
- arg:
114114
name: launch_surround_obstacle_checker
115-
default: "false"
115+
default: "true"
116116

117117
# parking modules
118118
- arg:

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

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

77
# external velocity limit parameter
88
margin_to_insert_external_velocity_limit: 0.3 # margin distance to insert external velocity limit [m]
99

1010
# -- curve parameters --
1111
# common parameters
12-
curvature_calculation_distance: 5.0 # distance of points while curvature is calculating for the steer rate and lateral acceleration limit [m]
12+
curvature_calculation_distance: 2.0 # distance of points while curvature is calculating for the steer rate and lateral acceleration limit [m]
1313
# lateral acceleration limit parameters
1414
enable_lateral_acc_limit: true # To toggle the lateral acc filter on and off. You can switch it dynamically at runtime.
1515
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]
16+
min_curve_velocity: 2.0 # min velocity at lateral acceleration limit and steering angle rate limit [m/s]
1717
decel_distance_before_curve: 3.5 # slow speed distance before a curve for lateral acceleration limit
1818
decel_distance_after_curve: 2.0 # slow speed distance after a curve for lateral acceleration limit
1919
min_decel_for_lateral_acc_lim_filter: -2.5 # deceleration limit applied in the lateral acceleration filter to avoid sudden braking [m/ss]
2020
# steering angle rate limit parameters
2121
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]
22+
max_steering_angle_rate: 11.5 # maximum steering angle rate [degree/s]
2323
resample_ds: 0.1 # distance between trajectory points [m]
2424
curvature_threshold: 0.02 # if curvature > curvature_threshold, steeringRateLimit is triggered [1/m]
2525

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

+5-4
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
use_opposite_lane: true
2020
use_intersection_areas: true
2121
use_hatched_road_markings: true
22+
use_freespace_areas: true
2223

2324
# for debug
2425
publish_debug_marker: false
@@ -38,7 +39,7 @@
3839
use_conservative_buffer_longitudinal: true # [-] When set to true, the base_link2front is added to the longitudinal buffer before avoidance.
3940
truck:
4041
execute_num: 1
41-
moving_speed_threshold: 2.0 # 7.2km/h
42+
moving_speed_threshold: 1.0 # 3.6km/h
4243
moving_time_threshold: 2.0
4344
max_expand_ratio: 0.0
4445
envelope_buffer_margin: 0.5
@@ -48,7 +49,7 @@
4849
use_conservative_buffer_longitudinal: true
4950
bus:
5051
execute_num: 1
51-
moving_speed_threshold: 2.0 # 7.2km/h
52+
moving_speed_threshold: 1.0 # 3.6km/h
5253
moving_time_threshold: 2.0
5354
max_expand_ratio: 0.0
5455
envelope_buffer_margin: 0.5
@@ -58,7 +59,7 @@
5859
use_conservative_buffer_longitudinal: true
5960
trailer:
6061
execute_num: 1
61-
moving_speed_threshold: 2.0 # 7.2km/h
62+
moving_speed_threshold: 1.0 # 3.6km/h
6263
moving_time_threshold: 2.0
6364
max_expand_ratio: 0.0
6465
envelope_buffer_margin: 0.5
@@ -218,7 +219,7 @@
218219
return_dead_line:
219220
goal:
220221
enable: true # [-]
221-
buffer: 30.0 # [m]
222+
buffer: 3.0 # [m]
222223
traffic_light:
223224
enable: true # [-]
224225
buffer: 3.0 # [m]

0 commit comments

Comments
 (0)