From df34fa76756649871330a8b8a4d93eafc2209cb2 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 14 Aug 2023 10:11:35 +0900 Subject: [PATCH] feat: update parameter for intersection auto mode (#602) Signed-off-by: tomoya.kimura --- .../occupancy_grid_map/binary_bayes_filter_updater.param.yaml | 2 +- .../pointcloud_based_occupancy_grid_map.param.yaml | 4 ++-- .../behavior_velocity_planner/intersection.param.yaml | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) 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_velocity_planner/intersection.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml index 4ab18f1835..a201cdbc15 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 @@ -33,14 +33,14 @@ 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 occlusion: enable: true 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