diff --git a/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml b/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml index ca15b55b47..bf9249e91a 100644 --- a/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml +++ b/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml @@ -27,7 +27,8 @@ path_footprint_extra_margin: 4.0 # Point cloud clustering - cluster_tolerance: 0.1 #[m] + cluster_tolerance: 0.15 #[m] + cluster_minimum_height: 0.0 minimum_cluster_size: 10 maximum_cluster_size: 10000 diff --git a/autoware_launch/config/perception/object_recognition/detection/object_filter/object_lanelet_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/object_filter/object_lanelet_filter.param.yaml index 99050d9738..fb6f1131e1 100644 --- a/autoware_launch/config/perception/object_recognition/detection/object_filter/object_lanelet_filter.param.yaml +++ b/autoware_launch/config/perception/object_recognition/detection/object_filter/object_lanelet_filter.param.yaml @@ -13,7 +13,7 @@ filter_settings: # polygon overlap based filter polygon_overlap_filter: - enabled: true + enabled: true # velocity direction based filter lanelet_direction_filter: enabled: false 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 index 62051e1c5e..330a4605a1 100644 --- 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 @@ -9,3 +9,13 @@ MOTORCYCLE : true BICYCLE : true PEDESTRIAN : true + + filter_settings: + # polygon overlap based filter + polygon_overlap_filter: + enabled: true + # velocity direction based filter + lanelet_direction_filter: + enabled: false + velocity_yaw_threshold: 0.785398 # [rad] (45 deg) + object_speed_threshold: 3.0 # [m/s] diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml index 24e88c8ed6..dd2e13892d 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml @@ -5,10 +5,6 @@ resample_interval_for_planning: 0.3 # [m] FOR DEVELOPER resample_interval_for_output: 4.0 # [m] FOR DEVELOPER - # avoidance module common setting - enable_bound_clipping: false - disable_path_update: false - # drivable area setting use_adjacent_lane: true use_opposite_lane: true @@ -284,6 +280,19 @@ max_acceleration: 0.5 # [m/ss] min_velocity_to_limit_max_acceleration: 2.78 # [m/ss] + # path generation method. select "shift_line_base" or "optimization_base" or "both". + # "shift_line_base" : Create avoidance path based on shift line. + # User can control avoidance maneuver execution via RTC. + # However, this method doesn't support complex avoidance scenario (e.g. S-shape maneuver). + # "optimization_base": This module selects avoidance target object + # and bpp module clips drivable area based on avoidance target object polygon shape. + # But this module doesn't modify the path shape. + # On the other hand, autoware_path_optimizer module optimizes path shape instead of this module + # so that the path can be within drivable area. This method is able to deal with complex avoidance scenario. + # However, user can't control avoidance manuever execution. + # "both" : Use both method. + path_generation_method: "shift_line_base" + shift_line_pipeline: trim: quantize_size: 0.1 @@ -293,8 +302,8 @@ # for debug debug: - enable_other_objects_marker: false - enable_other_objects_info: false + enable_other_objects_marker: true + enable_other_objects_info: true enable_detection_area_marker: false enable_drivable_bound_marker: false enable_safety_check_marker: false diff --git a/autoware_launch/launch/components/tier4_system_component.launch.xml b/autoware_launch/launch/components/tier4_system_component.launch.xml index d5082a91e8..6fda11ac7a 100644 --- a/autoware_launch/launch/components/tier4_system_component.launch.xml +++ b/autoware_launch/launch/components/tier4_system_component.launch.xml @@ -34,4 +34,11 @@ + + + + + + +