diff --git a/autoware_launch/config/localization/localization_error_monitor.param.yaml b/autoware_launch/config/localization/localization_error_monitor.param.yaml
index 026daf0532..2aa28014ea 100644
--- a/autoware_launch/config/localization/localization_error_monitor.param.yaml
+++ b/autoware_launch/config/localization/localization_error_monitor.param.yaml
@@ -4,4 +4,4 @@
error_ellipse_size: 1.0
warn_ellipse_size: 0.8
error_ellipse_size_lateral_direction: 0.3
- warn_ellipse_size_lateral_direction: 0.2
+ warn_ellipse_size_lateral_direction: 0.25
diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml
deleted file mode 100644
index 3dd303464a..0000000000
--- a/autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml
+++ /dev/null
@@ -1,20 +0,0 @@
-/**:
- ros__parameters:
-
- # distance threshold for compare compare
- distance_threshold: 0.5
-
- # publish voxelized map pointcloud for debug
- publish_debug_pcd: False
-
- # use dynamic map loading
- use_dynamic_map_loading: True
-
- # time interval to check dynamic map loading
- timer_interval_ms: 100
-
- # distance threshold for dynamic map update
- map_update_distance_threshold: 10.0
-
- # radius map for dynamic map loading
- map_loader_radius: 150.0
diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml
deleted file mode 100644
index 1962fba1f3..0000000000
--- a/autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml
+++ /dev/null
@@ -1,8 +0,0 @@
-/**:
- ros__parameters:
- input_frame: base_link
- output_frame: base_link
- voxel_size_x: 0.3
- voxel_size_y: 0.3
- voxel_size_z: 100.0
- voxel_points_threshold: 3
diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml
deleted file mode 100644
index 3ff32bfbb7..0000000000
--- a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml
+++ /dev/null
@@ -1,7 +0,0 @@
-/**:
- ros__parameters:
- input_frame: base_link
- output_frame: base_link
- voxel_size_x: 0.15
- voxel_size_y: 0.15
- voxel_size_z: 0.15
diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml
index 2f3de2b789..26b027f007 100644
--- a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml
@@ -7,9 +7,11 @@
max_cluster_size: 3000
use_height: false
input_frame: "base_link"
- max_x: 70.0
- min_x: -70.0
- max_y: 70.0
- min_y: -70.0
- max_z: 4.5
- min_z: -4.5
+
+ # low height crop box filter param
+ max_x: 200.0
+ min_x: -200.0
+ max_y: 200.0
+ min_y: -200.0
+ max_z: 2.0
+ min_z: -10.0
diff --git a/autoware_launch/config/perception/object_recognition/detection/object_filter/radar_lanelet_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/object_filter/radar_lanelet_filter.param.yaml
new file mode 100644
index 0000000000..62051e1c5e
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/detection/object_filter/radar_lanelet_filter.param.yaml
@@ -0,0 +1,11 @@
+/**:
+ ros__parameters:
+ filter_target_label:
+ UNKNOWN : true
+ CAR : true
+ TRUCK : true
+ BUS : true
+ TRAILER : true
+ MOTORCYCLE : true
+ BICYCLE : true
+ PEDESTRIAN : true
diff --git a/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml
index 0423217582..62b3074c15 100644
--- a/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml
@@ -1,7 +1,5 @@
/**:
ros__parameters:
- # use downsample filter before compare map
- use_down_sample_filter: False
# voxel size for downsample filter
down_sample_voxel_size: 0.1
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 c1fd848857..0c11077ea6 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
@@ -21,8 +21,9 @@
# occupancy grid map
occupancy_grid:
- use_occupancy_grid: true
- use_occupancy_grid_for_longitudinal_margin: false
+ use_occupancy_grid_for_goal_search: true
+ use_occupancy_grid_for_goal_longitudinal_margin: false
+ use_occupancy_grid_for_path_collision_check: false
occupancy_grid_collision_check_margin: 0.0
theta_size: 360
obstacle_threshold: 60
@@ -111,12 +112,13 @@
path_safety_check:
# EgoPredictedPath
ego_predicted_path:
+ min_velocity: 0.0
acceleration: 1.0
- time_horizon: 10.0
+ max_velocity: 1.0
+ time_horizon_for_front_object: 10.0
+ time_horizon_for_rear_object: 10.0
time_resolution: 0.5
- min_slow_speed: 0.0
delay_until_departure: 1.0
- target_velocity: 1.0
# For target object filtering
target_filtering:
safety_check_time_horizon: 5.0
@@ -124,7 +126,7 @@
# detection range
object_check_forward_distance: 10.0
object_check_backward_distance: 100.0
- ignore_object_velocity_threshold: 0.0
+ ignore_object_velocity_threshold: 1.0
# ObjectTypesToCheck
object_types_to_check:
check_car: true
@@ -151,7 +153,7 @@
# For safety check
safety_check_params:
# safety check configuration
- enable_safety_check: true
+ enable_safety_check: false # Don't set to true if auto_mode is enabled
# collision check parameters
check_all_predicted_path: true
publish_debug_marker: false
@@ -161,6 +163,8 @@
lateral_distance_max_threshold: 1.0
longitudinal_distance_min_threshold: 1.0
longitudinal_velocity_delta_time: 1.0
+ # hysteresis factor to expand/shrink polygon with the value
+ hysteresis_factor_expand_rate: 1.0
# temporary
backward_path_length: 30.0
forward_path_length: 100.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 b62262423f..4fa1c09958 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
@@ -79,12 +79,13 @@
path_safety_check:
# EgoPredictedPath
ego_predicted_path:
+ min_velocity: 0.0
acceleration: 1.0
- time_horizon: 10.0
+ max_velocity: 1.0
+ time_horizon_for_front_object: 10.0
+ time_horizon_for_rear_object: 10.0
time_resolution: 0.5
- min_slow_speed: 0.0
delay_until_departure: 1.0
- target_velocity: 1.0
# For target object filtering
target_filtering:
safety_check_time_horizon: 5.0
@@ -92,7 +93,7 @@
# detection range
object_check_forward_distance: 10.0
object_check_backward_distance: 100.0
- ignore_object_velocity_threshold: 0.0
+ ignore_object_velocity_threshold: 1.0
# ObjectTypesToCheck
object_types_to_check:
check_car: true
@@ -119,7 +120,7 @@
# For safety check
safety_check_params:
# safety check configuration
- enable_safety_check: true
+ enable_safety_check: false # Don't set to true if auto_mode is enabled
# collision check parameters
check_all_predicted_path: true
publish_debug_marker: false
@@ -129,6 +130,8 @@
lateral_distance_max_threshold: 1.0
longitudinal_distance_min_threshold: 1.0
longitudinal_velocity_delta_time: 1.0
+ # hysteresis factor to expand/shrink polygon
+ hysteresis_factor_expand_rate: 1.0
# temporary
backward_path_length: 30.0
forward_path_length: 100.0
diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml
index cf5b2dd98c..10da418468 100644
--- a/autoware_launch/launch/components/tier4_perception_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml
@@ -21,16 +21,11 @@
-
-
+