From 9b7a16a82eab836286b93b1e70526c0bab8b7479 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Wed, 27 Mar 2024 11:40:40 +0900 Subject: [PATCH 1/3] feat: add dummy doors for planning simulator (#921) Signed-off-by: Takagi, Isamu --- .../launch/components/tier4_simulator_component.launch.xml | 2 ++ autoware_launch/launch/planning_simulator.launch.xml | 2 ++ 2 files changed, 4 insertions(+) diff --git a/autoware_launch/launch/components/tier4_simulator_component.launch.xml b/autoware_launch/launch/components/tier4_simulator_component.launch.xml index a8503818cd..c2f2b7ca92 100644 --- a/autoware_launch/launch/components/tier4_simulator_component.launch.xml +++ b/autoware_launch/launch/components/tier4_simulator_component.launch.xml @@ -3,6 +3,7 @@ + @@ -17,6 +18,7 @@ + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index bc53dfa834..b389abf61c 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -16,6 +16,7 @@ + @@ -86,6 +87,7 @@ + From 5375164d21f3a5b127e7f825e519bf57fb1581eb Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Wed, 27 Mar 2024 13:46:00 +0900 Subject: [PATCH 2/3] feat(run_out_module): new params for run out, add ego cut lane (#935) * new params for run out Signed-off-by: Daniel Sanchez * rename param Signed-off-by: Daniel Sanchez * update description Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../behavior_velocity_planner/run_out.param.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml index 3af5164a52..9af4442778 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml @@ -4,6 +4,7 @@ detection_method: "Object" # [-] candidate: Object, ObjectWithoutPath, Points use_partition_lanelet: true # [-] whether to use partition lanelet map data suppress_on_crosswalk: true # [-] whether to suppress on crosswalk lanelet + use_ego_cut_line: true # [-] filter obstacles that pass the backside of ego: if a dynamic obstacle's predicted path intersects this line, it is ignored specify_decel_jerk: true # [-] whether to specify jerk when ego decelerates stop_margin: 2.5 # [m] the vehicle decelerates to be able to stop with this margin passing_margin: 1.1 # [m] the vehicle begins to accelerate if the vehicle's front in predicted position is ahead of the obstacle + this margin @@ -11,6 +12,7 @@ detection_distance: 45.0 # [m] ahead distance from ego to detect the obstacles detection_span: 1.0 # [m] calculate collision with this span to reduce calculation time min_vel_ego_kmph: 3.6 # [km/h] min velocity to calculate time to collision + ego_cut_line_length: 3.0 # The width of the ego's cut line # Parameter to create abstracted dynamic obstacles dynamic_obstacle: From 954145a38aeba3b7076f9006eedd34b1c76951f3 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Wed, 27 Mar 2024 15:54:51 +0900 Subject: [PATCH 3/3] feat(run_out): add obstacle types to run out (#936) add obstacle types to run out Signed-off-by: Daniel Sanchez --- .../behavior_velocity_planner/run_out.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml index 9af4442778..898f303a75 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml @@ -2,6 +2,7 @@ ros__parameters: run_out: detection_method: "Object" # [-] candidate: Object, ObjectWithoutPath, Points + target_obstacle_types: ["PEDESTRIAN", "BICYCLE", "MOTORCYCLE"] # [-] Obstacle types considered by this module use_partition_lanelet: true # [-] whether to use partition lanelet map data suppress_on_crosswalk: true # [-] whether to suppress on crosswalk lanelet use_ego_cut_line: true # [-] filter obstacles that pass the backside of ego: if a dynamic obstacle's predicted path intersects this line, it is ignored