diff --git a/autoware_launch/config/control/autonomous_emergency_braking/autonomous_emergency_braking.param.yaml b/autoware_launch/config/control/autonomous_emergency_braking/autonomous_emergency_braking.param.yaml index 09db0feb34..6206fd9f1d 100644 --- a/autoware_launch/config/control/autonomous_emergency_braking/autonomous_emergency_braking.param.yaml +++ b/autoware_launch/config/control/autonomous_emergency_braking/autonomous_emergency_braking.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: use_predicted_trajectory: true - use_imu_path: true + use_imu_path: false voxel_grid_x: 0.05 voxel_grid_y: 0.05 voxel_grid_z: 100000.0 @@ -13,5 +13,5 @@ a_obj_min: -1.0 prediction_time_horizon: 1.5 prediction_time_interval: 0.1 - collision_keeping_sec: 0.0 + collision_keeping_sec: 2.0 aeb_hz: 10.0 diff --git a/autoware_launch/config/perception/occupancy_grid_map/binary_bayes_filter_updater.param.yaml b/autoware_launch/config/perception/occupancy_grid_map/binary_bayes_filter_updater.param.yaml index 4e335e3574..4f730a9460 100644 --- a/autoware_launch/config/perception/occupancy_grid_map/binary_bayes_filter_updater.param.yaml +++ b/autoware_launch/config/perception/occupancy_grid_map/binary_bayes_filter_updater.param.yaml @@ -5,4 +5,4 @@ occupied_to_free: 0.05 free_to_occupied: 0.2 free_to_free: 0.8 - v_ratio: 10.0 + v_ratio: 0.5 diff --git a/autoware_launch/config/perception/occupancy_grid_map/pointcloud_based_occupancy_grid_map.param.yaml b/autoware_launch/config/perception/occupancy_grid_map/pointcloud_based_occupancy_grid_map.param.yaml index 8077bdec50..e8344bee3a 100644 --- a/autoware_launch/config/perception/occupancy_grid_map/pointcloud_based_occupancy_grid_map.param.yaml +++ b/autoware_launch/config/perception/occupancy_grid_map/pointcloud_based_occupancy_grid_map.param.yaml @@ -19,9 +19,9 @@ gridmap_origin_frame: "base_link" # ray-tracing center: main sensor frame is preferable like: "velodyne_top" # base_link should not be used with "OccupancyGridMapProjectiveBlindSpot" - scan_origin_frame: "base_link" + scan_origin_frame: "velodyne_top" - grid_map_type: "OccupancyGridMapFixedBlindSpot" + grid_map_type: "OccupancyGridMapProjectiveBlindSpot" OccupancyGridMapFixedBlindSpot: distance_margin: 1.0 OccupancyGridMapProjectiveBlindSpot: 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 efbdf2276e..ba2dbe5f2d 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 @@ -40,7 +40,7 @@ truck: is_target: true execute_num: 1 - moving_speed_threshold: 1.0 # 3.6km/h + moving_speed_threshold: 2.0 # 7.2km/h moving_time_threshold: 2.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 @@ -50,7 +50,7 @@ bus: is_target: true execute_num: 1 - moving_speed_threshold: 1.0 # 3.6km/h + moving_speed_threshold: 2.0 # 7.2km/h moving_time_threshold: 2.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 @@ -60,7 +60,7 @@ trailer: is_target: true execute_num: 1 - moving_speed_threshold: 1.0 # 3.6km/h + moving_speed_threshold: 2.0 # 7.2km/h moving_time_threshold: 2.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 @@ -73,9 +73,9 @@ moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 - envelope_buffer_margin: 0.5 + envelope_buffer_margin: 0.1 avoid_margin_lateral: 0.7 - safety_buffer_lateral: 0.3 + safety_buffer_lateral: -0.2 safety_buffer_longitudinal: 0.0 bicycle: is_target: true @@ -165,7 +165,7 @@ lateral_execution_threshold: 0.09 # [m] lateral_small_shift_threshold: 0.501 # [m] lateral_avoid_check_threshold: 0.1 # [m] - soft_road_shoulder_margin: 0.3 # [m] + soft_road_shoulder_margin: 0.8 # [m] hard_road_shoulder_margin: 0.3 # [m] max_right_shift_length: 5.0 max_left_shift_length: 5.0 diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance_by_lc/avoidance_by_lc.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance_by_lc/avoidance_by_lc.param.yaml index bd8545d9e6..da45e24ce9 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance_by_lc/avoidance_by_lc.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance_by_lc/avoidance_by_lc.param.yaml @@ -43,7 +43,7 @@ avoid_margin_lateral: 0.0 safety_buffer_lateral: 0.0 unknown: - is_target: true + is_target: false execute_num: 1 moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/scene_module_manager_foa.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/scene_module_manager_foa.param.yaml index d4da549dcd..65582656b9 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/scene_module_manager_foa.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/scene_module_manager_foa.param.yaml @@ -67,9 +67,8 @@ priority: 5 max_module_size: 1 - # NOTE: This module is unstable. Deprecated for now. avoidance_by_lc: - enable_module: false + enable_module: true enable_rtc: true enable_simultaneous_execution_as_approved_module: false enable_simultaneous_execution_as_candidate_module: false 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 92aa8acd18..151df8192a 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 @@ -34,7 +34,7 @@ not_prioritized: collision_start_margin_time: 4.0 # [s] this + state_transit_margin_time should be higher to account for collision with fast/accelerating object collision_end_margin_time: 6.0 # [s] this + state_transit_margin_time should be higher to account for collision with slow/decelerating object - keep_detection_vel_thr: 0.833 # == 3.0km/h. keep detection if ego is ego.vel < keep_detection_vel_thr + keep_detection_vel_thr: 1.5 # == 5.4km/h. keep detection if ego is ego.vel < keep_detection_vel_thr use_upstream_velocity: true # flag to use the planned velocity profile from the upstream module minimum_upstream_velocity: 0.01 # [m/s] minimum velocity to avoid null division for the stop line from the upstream velocity yield_on_green_traffic_light: @@ -47,7 +47,7 @@ occlusion_attention_area_length: 70.0 # [m] enable_creeping: false # flag to use the creep velocity when reaching occlusion limit stop line occlusion_creep_velocity: 0.8333 # the creep velocity to occlusion limit stop line - peeking_offset: -0.5 # [m] offset for peeking into detection area + peeking_offset: 1.0 # [m] offset for peeking into detection area free_space_max: 43 occupied_min: 58 do_dp: true @@ -63,7 +63,7 @@ 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 + attention_lane_curvature_calculation_ds: 0.6 enable_rtc: intersection: false # 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/system/system_error_monitor/system_error_monitor.awsim.param.yaml b/autoware_launch/config/system/system_error_monitor/system_error_monitor.awsim.param.yaml index 950e808a6e..e138c9fe94 100644 --- a/autoware_launch/config/system/system_error_monitor/system_error_monitor.awsim.param.yaml +++ b/autoware_launch/config/system/system_error_monitor/system_error_monitor.awsim.param.yaml @@ -19,6 +19,7 @@ autonomous_driving: /autoware/control/autonomous_driving/node_alive_monitoring: default # /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default # tmp + /autoware/control/autonomous_emergency_braking/performance_monitoring/emergency_stop: { sf_at: "none", lf_at: "warn", spf_at: "error"} /autoware/control/control_command_gate/node_alive_monitoring: default # /autoware/control/external_control/local_external_control/device_connection: default diff --git a/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml b/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml index 18a91ebaee..ea4ab8481e 100644 --- a/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml +++ b/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml @@ -19,6 +19,7 @@ autonomous_driving: /autoware/control/autonomous_driving/node_alive_monitoring: default # /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default # tmp + /autoware/control/autonomous_emergency_braking/performance_monitoring/emergency_stop: { sf_at: "none", lf_at: "warn", spf_at: "error"} /autoware/control/control_command_gate/node_alive_monitoring: default /autoware/control/external_control/local_external_control/device_connection: default diff --git a/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml b/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml index a8a562689f..f3636bf460 100644 --- a/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml +++ b/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml @@ -20,6 +20,7 @@ /autoware/control/autonomous_driving/node_alive_monitoring: default # /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default /autoware/control/autonomous_driving/performance_monitoring/trajectory_deviation: default + /autoware/control/autonomous_emergency_braking/performance_monitoring/emergency_stop: { sf_at: "none", lf_at: "warn", spf_at: "error"} /autoware/control/control_command_gate/node_alive_monitoring: default /autoware/localization/node_alive_monitoring: default diff --git a/autoware_launch/launch/components/tier4_control_component.launch.xml b/autoware_launch/launch/components/tier4_control_component.launch.xml index d4baac0a46..e3d792ccb6 100644 --- a/autoware_launch/launch/components/tier4_control_component.launch.xml +++ b/autoware_launch/launch/components/tier4_control_component.launch.xml @@ -4,7 +4,7 @@ - + @@ -13,6 +13,7 @@ +