diff --git a/autoware_launch/config/planning/preset/default_preset.yaml b/autoware_launch/config/planning/preset/default_preset.yaml
index fa4a2e4308..f2879fb687 100644
--- a/autoware_launch/config/planning/preset/default_preset.yaml
+++ b/autoware_launch/config/planning/preset/default_preset.yaml
@@ -80,6 +80,9 @@ launch:
- arg:
name: launch_no_drivable_lane_module
default: "false"
+ - arg:
+ name: launch_dynamic_obstacle_stop_module
+ default: "true"
# motion planning modules
- arg:
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/dynamic_obstacle_stop.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/dynamic_obstacle_stop.param.yaml
new file mode 100644
index 0000000000..14483093e8
--- /dev/null
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/dynamic_obstacle_stop.param.yaml
@@ -0,0 +1,10 @@
+/**:
+ ros__parameters:
+ dynamic_obstacle_stop: # module to stop or before entering the immediate path of a moving object
+ extra_object_width: 1.0 # [m] extra width around detected objects
+ minimum_object_velocity: 0.5 # [m/s] objects with a velocity bellow this value are ignored
+ stop_distance_buffer: 0.5 # [m] extra distance to add between the stop point and the collision point
+ time_horizon: 5.0 # [s] time horizon used for collision checks
+ hysteresis: 1.0 # [m] once a collision has been detected, this hysteresis is used on the collision detection
+ decision_duration_buffer : 1.0 # [s] duration between no collision being detected and the stop decision being cancelled
+ minimum_object_distance_from_ego_path: 1.0 # [m] minimum distance between the footprints of ego and an object to consider for collision
diff --git a/autoware_launch/launch/components/tier4_planning_component.launch.xml b/autoware_launch/launch/components/tier4_planning_component.launch.xml
index 5fb17541cd..3e9061da80 100644
--- a/autoware_launch/launch/components/tier4_planning_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_planning_component.launch.xml
@@ -49,6 +49,7 @@
+
diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz
index bc22eadb70..d8d2602d1a 100644
--- a/autoware_launch/rviz/autoware.rviz
+++ b/autoware_launch/rviz/autoware.rviz
@@ -1676,6 +1676,18 @@ Visualization Manager:
Reliability Policy: Reliable
Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/no_drivable_lane
Value: true
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: VirtualWall (DynamicObstacleStop)
+ Namespaces:
+ {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/dynamic_obstacle_stop
+ Value: true
Enabled: true
Name: VirtualWall
- Class: rviz_common/Group
@@ -1944,6 +1956,18 @@ Visualization Manager:
Reliability Policy: Reliable
Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/no_drivable_lane
Value: false
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: false
+ Name: DynamicObstacleStop
+ Namespaces:
+ {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/dynamic_obstacle_stop
+ Value: false
Enabled: false
Name: DebugMarker
- Class: rviz_common/Group