diff --git a/README.md b/README.md
index b22428a81..c88abfc7f 100644
--- a/README.md
+++ b/README.md
@@ -22,6 +22,4 @@ ros2 launch autoware_launch planning_simulator.launch.xml map_path:=/path/to/map
- [localization_launch](./localization_launch)
- [perception_launch](./perception_launch)
- [planning_launch](./planning_launch)
-- [sensing_launch](./sensing_launch)
- [system_launch](./system_launch)
-- [vehicle_launch](./vehicle_launch)
diff --git a/autoware_api_launch/launch/include/internal_api_adaptor.launch.py b/autoware_api_launch/launch/include/internal_api_adaptor.launch.py
index 422c35abe..f1962908c 100644
--- a/autoware_api_launch/launch/include/internal_api_adaptor.launch.py
+++ b/autoware_api_launch/launch/include/internal_api_adaptor.launch.py
@@ -31,7 +31,6 @@ def generate_launch_description():
components = [
_create_api_node("iv_msgs", "IVMsgs"),
_create_api_node("operator", "Operator"),
- _create_api_node("route", "Route"),
_create_api_node("velocity", "Velocity"),
]
container = ComposableNodeContainer(
diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml
index 65c153c3d..f966932c1 100644
--- a/autoware_launch/launch/logging_simulator.launch.xml
+++ b/autoware_launch/launch/logging_simulator.launch.xml
@@ -23,6 +23,7 @@
+
@@ -100,6 +101,7 @@
+
diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml
index f5291f3e5..7ff1b4afb 100644
--- a/autoware_launch/launch/planning_simulator.launch.xml
+++ b/autoware_launch/launch/planning_simulator.launch.xml
@@ -11,6 +11,7 @@
+
@@ -58,7 +59,9 @@
-
+
+
+
@@ -68,6 +71,8 @@
+
+
diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml
index 845c05f06..ee4cd99d6 100644
--- a/control_launch/launch/control.launch.xml
+++ b/control_launch/launch/control.launch.xml
@@ -7,6 +7,7 @@
+
@@ -16,6 +17,7 @@
+
diff --git a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml
index 1b820b2c2..b90ddf20b 100644
--- a/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml
+++ b/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml
@@ -12,8 +12,10 @@
threshold_distance_object_is_on_center: 1.0 # [m]
threshold_speed_object_is_stopped: 1.0 # [m/s]
+ threshold_time_object_is_moving: 1.0 # [s]
object_check_forward_distance: 150.0 # [m]
object_check_backward_distance: 2.0 # [m]
+ object_envelope_buffer: 0.3 # [m]
lateral_collision_margin: 1.0 # [m]
lateral_collision_safety_buffer: 0.7 # [m]
diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml
index 09bc4a8d7..aec537f01 100644
--- a/system_launch/launch/system.launch.xml
+++ b/system_launch/launch/system.launch.xml
@@ -31,6 +31,14 @@
+
+
+
+
+
+
+
+