diff --git a/autoware_launch/config/perception/object_recognition/detection/object_merger/data_association_matrix.param.yaml b/autoware_launch/config/perception/object_recognition/detection/object_merger/data_association_matrix.param.yaml
new file mode 100644
index 0000000000..e1bf2c67b3
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/detection/object_merger/data_association_matrix.param.yaml
@@ -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
diff --git a/autoware_launch/config/perception/object_recognition/detection/object_merger/overlapped_judge.param.yaml b/autoware_launch/config/perception/object_recognition/detection/object_merger/overlapped_judge.param.yaml
new file mode 100644
index 0000000000..94882fae4f
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/detection/object_merger/overlapped_judge.param.yaml
@@ -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
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml
index 189476d4f8..24bafc2e93 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml
@@ -140,6 +140,7 @@
lateral:
lateral_execution_threshold: 0.09 # [m]
lateral_small_shift_threshold: 0.501 # [m]
+ lateral_avoid_check_threshold: 0.1 # [m]
road_shoulder_safety_margin: 0.5 # [m]
max_right_shift_length: 5.0
max_left_shift_length: 5.0
@@ -147,11 +148,9 @@
longitudinal:
prepare_time: 2.0 # [s]
min_prepare_distance: 1.0 # [m]
- min_avoidance_distance: 10.0 # [m]
- min_nominal_avoidance_speed: 7.0 # [m/s]
- min_sharp_avoidance_speed: 2.78 # [m/s]
min_slow_down_speed: 1.38 # [m/s]
buf_slow_down_speed: 0.56 # [m/s]
+ nominal_avoidance_speed: 8.33 # [m/s]
# For yield maneuver
yield:
@@ -159,7 +158,6 @@
# For stop maneuver
stop:
- min_distance: 10.0 # [m]
max_distance: 20.0 # [m]
stop_buffer: 1.0 # [m]
@@ -169,9 +167,10 @@
# lateral constraints
lateral:
- nominal_lateral_jerk: 0.2 # [m/sss]
- max_lateral_jerk: 1.0 # [m/sss]
- max_lateral_acceleration: 0.5 # [m/ss]
+ velocity: [1.0, 1.38, 11.1] # [m/s]
+ max_accel_values: [0.5, 0.5, 0.5] # [m/ss]
+ min_jerk_values: [0.2, 0.2, 0.2] # [m/sss]
+ max_jerk_values: [1.0, 1.0, 1.0] # [m/sss]
# longitudinal constraints
longitudinal:
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml
index 7963766c03..8a57bfeabd 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml
@@ -8,3 +8,4 @@
max_future_movement_time: 10.0 # [second]
threshold_yaw_diff: 0.523 # [rad]
adjacent_extend_width: 1.5 # [m]
+ enable_rtc: true # 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.
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml
index 80017d85ff..903b405565 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml
@@ -5,6 +5,7 @@
show_processing_time: false # [-] whether to show processing time
# param for input data
traffic_light_state_timeout: 3.0 # [s] timeout threshold for traffic light signal
+ enable_rtc: true # 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.
# param for stop position
stop_position:
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml
index ad4e32cb4e..55b627cce7 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml
@@ -8,3 +8,4 @@
state_clear_time: 2.0
hold_stop_margin_distance: 0.0
distance_to_judge_over_stop_line: 0.5
+ enable_rtc: true # 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.
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml
index 8848c37e14..fb70a8a1a0 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml
@@ -48,5 +48,9 @@
denoise_kernel: 1.0 # [m]
pub_debug_grid: false
+ enable_rtc:
+ intersection: true # 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
+ intersection_to_occlusion: true
+
merge_from_private:
stop_duration_sec: 1.0
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml
index 32cd05a9cc..f550188d4f 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml
@@ -8,3 +8,4 @@
stop_line_margin: 1.0 # [m] margin to auto-gen stop line at no stopping area
detection_area_length: 200.0 # [m] used to create detection area polygon
stuck_vehicle_front_margin: 6.0 # [m] obstacle stop max distance(5.0m)
+ enable_rtc: true # 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
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml
index 0460e071a5..0d7461d798 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml
@@ -5,3 +5,4 @@
tl_state_timeout: 1.0
yellow_lamp_period: 2.75
enable_pass_judge: true
+ enable_rtc: true # 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
diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml
index 6fa7a06861..cc9d816661 100644
--- a/autoware_launch/launch/components/tier4_perception_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml
@@ -55,6 +55,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"
/>
+
+