From d05e5b2749f2cf23d19c232c323841096e0cadba Mon Sep 17 00:00:00 2001 From: Mitsuhiro Sakamoto <50359861+mitukou1109@users.noreply.github.com> Date: Thu, 4 Jul 2024 07:43:19 +0900 Subject: [PATCH] feat(obstacle_cruise_planner): support pointcloud-based obstacles (#980) * feat: use obstacle_cruise_planner and change safe_distance_margin Signed-off-by: Takayuki Murooka * feat: set max_vel to 40km/h Signed-off-by: Takayuki Murooka * feat: enable surround_obstacle_checker Signed-off-by: Takayuki Murooka * feat: enable surround_obstacle_checker Signed-off-by: Takayuki Murooka * feat: enable dynamic_avoidance and disable outside_drivable_area_stop Signed-off-by: Takayuki Murooka * feat: disable AEB and set the maximum velocity to 40km/h Signed-off-by: Takayuki Murooka * enable intersection_occlusion detection Signed-off-by: Mamoru Sobue * add parameters for obstacle_cruise_planner * add parameters for pointcloud filtering * chore(planning_launch): update motion module name (#1014) Signed-off-by: satoshi-ota * move use_pointcloud to common parameter * disable using pointcloud by default * disable AEB diag check Signed-off-by: Daniel Sanchez * remove use_pointcloud parameter * feat(diagnostic_graph_utils): launch logging node for diagnostic_graph Signed-off-by: Takamasa Horibe * reset to autowarefoundation:main --------- Signed-off-by: Takayuki Murooka Signed-off-by: Mamoru Sobue Signed-off-by: satoshi-ota Signed-off-by: Daniel Sanchez Signed-off-by: Takamasa Horibe Co-authored-by: Takayuki Murooka Co-authored-by: tier4-autoware-public-bot[bot] <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> Co-authored-by: Mamoru Sobue Co-authored-by: Mamoru Sobue Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Co-authored-by: Daniel Sanchez Co-authored-by: danielsanchezaran Co-authored-by: Takamasa Horibe --- .../obstacle_cruise_planner.param.yaml | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml index 59388eccf9..b68395aefc 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -37,6 +37,7 @@ motorcycle: true bicycle: true pedestrian: true + pointcloud: false cruise_obstacle_type: inside: @@ -68,8 +69,17 @@ motorcycle: true bicycle: true pedestrian: true + pointcloud: false behavior_determination: + pointcloud_search_radius: 5.0 + pointcloud_voxel_grid_x: 0.05 + pointcloud_voxel_grid_y: 0.05 + pointcloud_voxel_grid_z: 100000.0 + pointcloud_cluster_tolerance: 1.0 + pointcloud_min_cluster_size: 1 + pointcloud_max_cluster_size: 100000 + decimate_trajectory_step_length : 2.0 # longitudinal step length to calculate trajectory polygon for collision checking prediction_resampling_time_interval: 0.1