diff --git a/autoware_launch/config/control/predicted_path_checker/predicted_path_checker.param.yaml b/autoware_launch/config/control/predicted_path_checker/predicted_path_checker.param.yaml
new file mode 100644
index 0000000000..780d86b5e9
--- /dev/null
+++ b/autoware_launch/config/control/predicted_path_checker/predicted_path_checker.param.yaml
@@ -0,0 +1,22 @@
+/**:
+ ros__parameters:
+ # Node
+ update_rate: 10.0
+ delay_time: 0.17
+ max_deceleration: 1.5
+ resample_interval: 0.5
+ stop_margin: 0.5 # [m]
+ ego_nearest_dist_threshold: 3.0 # [m]
+ ego_nearest_yaw_threshold: 1.046 # [rad] = 60 [deg]
+ min_trajectory_check_length: 1.5 # [m]
+ trajectory_check_time: 3.0
+ distinct_point_distance_threshold: 0.3
+ distinct_point_yaw_threshold: 5.0 # [deg]
+ filtering_distance_threshold: 1.5 # [m]
+ use_object_prediction: true
+
+ collision_checker_params:
+ width_margin: 0.2
+ chattering_threshold: 0.2
+ z_axis_filtering_buffer: 0.3
+ enable_z_axis_obstacle_filtering: false
diff --git a/autoware_launch/config/localization/localization_error_monitor.param.yaml b/autoware_launch/config/localization/localization_error_monitor.param.yaml
index 2aa28014ea..def5c80164 100644
--- a/autoware_launch/config/localization/localization_error_monitor.param.yaml
+++ b/autoware_launch/config/localization/localization_error_monitor.param.yaml
@@ -1,7 +1,7 @@
/**:
ros__parameters:
scale: 3.0
- error_ellipse_size: 1.0
- warn_ellipse_size: 0.8
+ error_ellipse_size: 1.5
+ warn_ellipse_size: 1.2
error_ellipse_size_lateral_direction: 0.3
warn_ellipse_size_lateral_direction: 0.25
diff --git a/autoware_launch/config/localization/ndt_scan_matcher.param.yaml b/autoware_launch/config/localization/ndt_scan_matcher.param.yaml
index e3450e0a34..8026c744b7 100644
--- a/autoware_launch/config/localization/ndt_scan_matcher.param.yaml
+++ b/autoware_launch/config/localization/ndt_scan_matcher.param.yaml
@@ -41,7 +41,7 @@
converged_param_nearest_voxel_transformation_likelihood: 2.3
# The number of particles to estimate initial pose
- initial_estimate_particles_num: 100
+ initial_estimate_particles_num: 200
# The number of initial random trials in the TPE (Tree-Structured Parzen Estimator).
# This value should be equal to or less than 'initial_estimate_particles_num' and more than 0.
diff --git a/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/obstacle_pointcloud_based_validator.param.yaml b/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/obstacle_pointcloud_based_validator.param.yaml
new file mode 100644
index 0000000000..22999b411f
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/obstacle_pointcloud_based_validator.param.yaml
@@ -0,0 +1,13 @@
+/**:
+ ros__parameters:
+ min_points_num:
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [10, 10, 10, 10, 10,10, 10, 10]
+
+ max_points_num:
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [10, 10, 10, 10, 10,10, 10, 10]
+
+ min_points_and_distance_ratio:
+ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
+ [800.0, 880.0, 800.0, 800.0, 800.0, 800.0, 800.0, 800.0]
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 c91ec0e88b..5f80c76111 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
@@ -139,12 +139,16 @@
check_other_object: true # [-]
# collision check parameters
check_all_predicted_path: false # [-]
- time_resolution: 0.5 # [s]
- time_horizon_for_front_object: 3.0 # [s]
- time_horizon_for_rear_object: 10.0 # [s]
safety_check_backward_distance: 100.0 # [m]
hysteresis_factor_expand_rate: 1.5 # [-]
hysteresis_factor_safe_count: 10 # [-]
+ # predicted path parameters
+ min_velocity: 1.38 # [m/s]
+ max_velocity: 50.0 # [m/s]
+ time_resolution: 0.5 # [s]
+ time_horizon_for_front_object: 3.0 # [s]
+ time_horizon_for_rear_object: 10.0 # [s]
+ delay_until_departure: 0.0 # [s]
# rss parameters
expected_front_deceleration: -1.0 # [m/ss]
expected_rear_deceleration: -1.0 # [m/ss]
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml
index f52c36179b..0f1b441bed 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml
@@ -118,7 +118,7 @@
path_safety_check:
# EgoPredictedPath
ego_predicted_path:
- min_velocity: 0.0
+ min_velocity: 1.0
acceleration: 1.0
max_velocity: 1.0
time_horizon_for_front_object: 10.0
@@ -164,11 +164,11 @@
check_all_predicted_path: true
publish_debug_marker: false
rss_params:
- rear_vehicle_reaction_time: 1.0
+ rear_vehicle_reaction_time: 2.0
rear_vehicle_safety_time_margin: 1.0
- lateral_distance_max_threshold: 1.0
- longitudinal_distance_min_threshold: 1.0
- longitudinal_velocity_delta_time: 1.0
+ lateral_distance_max_threshold: 2.0
+ longitudinal_distance_min_threshold: 3.0
+ longitudinal_velocity_delta_time: 0.8
# hysteresis factor to expand/shrink polygon with the value
hysteresis_factor_expand_rate: 1.0
# temporary
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml
index 1accb1f709..1be71cae53 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml
@@ -38,6 +38,11 @@
longitudinal_distance_min_threshold: 3.0
longitudinal_velocity_delta_time: 0.8
+ # lane expansion for object filtering
+ lane_expansion:
+ left_offset: 0.0 # [m]
+ right_offset: 0.0 # [m]
+
# lateral acceleration map
lateral_acceleration:
velocity: [0.0, 4.0, 10.0]
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml
index 5487b0fde9..1424b58d22 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml
@@ -127,11 +127,11 @@
check_all_predicted_path: true
publish_debug_marker: false
rss_params:
- rear_vehicle_reaction_time: 1.0
+ rear_vehicle_reaction_time: 2.0
rear_vehicle_safety_time_margin: 1.0
- lateral_distance_max_threshold: 1.0
- longitudinal_distance_min_threshold: 1.0
- longitudinal_velocity_delta_time: 1.0
+ lateral_distance_max_threshold: 2.0
+ longitudinal_distance_min_threshold: 3.0
+ longitudinal_velocity_delta_time: 0.8
# hysteresis factor to expand/shrink polygon
hysteresis_factor_expand_rate: 1.0
# temporary
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 0c12624f3b..4b81a1e687 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
@@ -54,7 +54,9 @@
## param for yielding
disable_stop_for_yield_cancel: false # for the crosswalk where there is a traffic signal
disable_yield_for_new_stopped_object: false # for the crosswalk where there is a traffic signal
- timeout_no_intention_to_walk: 3.0 # [s] if the pedestrian does not move for X seconds after stopping before the crosswalk, the module judge that ego is able to pass first.
+ # if the pedestrian does not move for X seconds after stopping before the crosswalk, the module judge that ego is able to pass first.
+ distance_map_for_no_intention_to_walk: [1.0, 5.0] # [m] ascending order
+ timeout_map_for_no_intention_to_walk: [3.0, 0.0] # [s]
timeout_ego_stop_for_yield: 3.0 # [s] the amount of time which ego should be stopping to query whether it yields or not
# param for target object filtering
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 4042adeb36..ccd3612203 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
@@ -54,6 +54,11 @@
ignore_parked_vehicle_speed_threshold: 0.8333 # == 3.0km/h
stop_release_margin_time: 1.5 # [s]
temporal_stop_before_attention_area: false
+ absence_traffic_light:
+ creep_velocity: 1.388 # [m/s]
+ maximum_peeking_distance: 6.0 # [m]
+ attention_lane_crop_curvature_threshold: 0.25
+ attention_lane_curvature_calculation_ds: 0.5
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
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml
index 510dc86ef6..c74c5b3d87 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml
@@ -24,8 +24,7 @@
action: # action to insert in the path if an object causes a conflict at an overlap
skip_if_over_max_decel: true # if true, do not take an action that would cause more deceleration than the maximum allowed
- strict: true # if true, when a decision is taken to avoid entering a lane, the stop point will make sure no lane at all is entered by ego
- # if false, ego stops just before entering a lane but may then be overlapping another lane.
+ precision: 0.1 # [m] precision when inserting a stop pose in the path
distance_buffer: 1.5 # [m] buffer distance to try to keep between the ego footprint and lane
slowdown:
distance_threshold: 30.0 # [m] insert a slowdown when closer than this distance from an overlap
diff --git a/autoware_launch/launch/components/tier4_control_component.launch.xml b/autoware_launch/launch/components/tier4_control_component.launch.xml
index 8b29135048..d15e050d7a 100644
--- a/autoware_launch/launch/components/tier4_control_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_control_component.launch.xml
@@ -5,6 +5,7 @@
+
@@ -42,5 +43,7 @@
+
+
diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml
index 342396934c..1ec8f2c22f 100644
--- a/autoware_launch/launch/components/tier4_perception_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml
@@ -48,6 +48,10 @@
name="object_recognition_detection_fusion_sync_param_path"
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml"
/>
+