Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

chore: sync awf/autoware_launch #210

Merged
merged 3 commits into from
Jul 21, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
/**:
ros__parameters:
can_assign_matrix:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN
[0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
0, 1, 1, 1, 1, 0, 0, 0, #CAR
0, 1, 1, 1, 1, 0, 0, 0, #TRUCK
0, 1, 1, 1, 1, 0, 0, 0, #BUS
0, 1, 1, 1, 1, 0, 0, 0, #TRAILER
0, 0, 0, 0, 0, 1, 1, 1, #MOTORBIKE
0, 0, 0, 0, 0, 1, 1, 1, #BICYCLE
0, 0, 0, 0, 0, 1, 1, 1] #PEDESTRIAN

max_dist_matrix:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[4.0, 4.0, 5.0, 5.0, 5.0, 2.0, 2.0, 2.0, #UNKNOWN
4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #CAR
5.0, 5.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRUCK
5.0, 5.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #BUS
5.0, 5.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRAILER
2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, #MOTORBIKE
2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, #BICYCLE
2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0] #PEDESTRIAN
max_rad_matrix: # If value is greater than pi, it will be ignored.
#UNKNOWN, CAR, TRUCK, BUS, TRAILER MOTORBIKE, BICYCLE, PEDESTRIAN
[3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #UNKNOWN
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #CAR
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRUCK
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #BUS
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRAILER
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #PEDESTRIAN

min_iou_matrix: # If value is negative, it will be ignored.
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN
0.1, 0.3, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, #CAR
0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRUCK
0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #BUS
0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRAILER
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #MOTORBIKE
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #BICYCLE
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] #PEDESTRIAN
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
/**:
ros__parameters:
distance_threshold_list:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN
[9.0, 9.0, 9.0, 9.0, 9.0, 9.0, 9.0, 9.0] #UNKNOWN
Original file line number Diff line number Diff line change
Expand Up @@ -175,7 +175,7 @@
longitudinal:
nominal_deceleration: -1.0 # [m/ss]
nominal_jerk: 0.5 # [m/sss]
max_deceleration: -2.0 # [m/ss]
max_deceleration: -1.5 # [m/ss]
max_jerk: 1.0 # [m/sss]
max_acceleration: 1.0 # [m/ss]

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
output_delta_arc_length: 0.5 # delta arc length for output trajectory [m]
output_backward_traj_length: 5.0 # backward length for backward trajectory from base_link [m]

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] .
vehicle_stop_margin_outside_drivable_area: 0.0 # vehicle stop margin to let the vehicle stop before the calculated stop point if it is calculated outside the drivable area [m] .
# This margin will be realized with delta_arc_length_for_mpt_points m precision.

# replanning & trimming trajectory param outside algorithm
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,14 @@
name="object_recognition_prediction_map_based_prediction_param_path"
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/prediction/map_based_prediction.param.yaml"
/>
<arg
name="object_recognition_detection_object_merger_data_association_matrix_param_path"
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/detection/object_merger/data_association_matrix.param.yaml"
/>
<arg
name="object_recognition_detection_object_merger_distance_threshold_list_path"
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/detection/object_merger/overlapped_judge.param.yaml"
/>
<arg
name="object_recognition_tracking_multi_object_tracker_data_association_matrix_param_path"
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml"
Expand Down
Loading