diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml
index d7da81c969da2..a297697234ef2 100644
--- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml
+++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml
@@ -237,6 +237,7 @@
+
diff --git a/planning/behavior_velocity_blind_spot_module/src/manager.cpp b/planning/behavior_velocity_blind_spot_module/src/manager.cpp
index d64f1ebc39a51..332cca21f7552 100644
--- a/planning/behavior_velocity_blind_spot_module/src/manager.cpp
+++ b/planning/behavior_velocity_blind_spot_module/src/manager.cpp
@@ -33,7 +33,8 @@ using tier4_autoware_utils::getOrDeclareParameter;
BlindSpotModuleManager::BlindSpotModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
- getOrDeclareParameter(node, std::string(getModuleName()) + ".enable_rtc"))
+ (!getOrDeclareParameter(node, "enable_all_modules_auto_mode") &&
+ getOrDeclareParameter(node, std::string(getModuleName()) + ".enable_rtc")))
{
const std::string ns(getModuleName());
planner_param_.use_pass_judge_line =
diff --git a/planning/behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_crosswalk_module/src/manager.cpp
index b8190cb6124e7..4f934149031bb 100644
--- a/planning/behavior_velocity_crosswalk_module/src/manager.cpp
+++ b/planning/behavior_velocity_crosswalk_module/src/manager.cpp
@@ -32,7 +32,8 @@ using tier4_autoware_utils::getOrDeclareParameter;
CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
- getOrDeclareParameter(node, std::string(getModuleName()) + ".common.enable_rtc"))
+ (!getOrDeclareParameter(node, "enable_all_modules_auto_mode") &&
+ getOrDeclareParameter(node, std::string(getModuleName()) + ".common.enable_rtc")))
{
const std::string ns(getModuleName());
diff --git a/planning/behavior_velocity_detection_area_module/src/manager.cpp b/planning/behavior_velocity_detection_area_module/src/manager.cpp
index e7ec6b37f7f20..4613d07aa5e4a 100644
--- a/planning/behavior_velocity_detection_area_module/src/manager.cpp
+++ b/planning/behavior_velocity_detection_area_module/src/manager.cpp
@@ -36,7 +36,8 @@ using tier4_autoware_utils::getOrDeclareParameter;
DetectionAreaModuleManager::DetectionAreaModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
- getOrDeclareParameter(node, std::string(getModuleName()) + ".enable_rtc"))
+ (!getOrDeclareParameter(node, "enable_all_modules_auto_mode") &&
+ getOrDeclareParameter(node, std::string(getModuleName()) + ".enable_rtc")))
{
const std::string ns(getModuleName());
planner_param_.stop_margin = getOrDeclareParameter(node, ns + ".stop_margin");
diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp
index c92f16dd7b474..6626091bef500 100644
--- a/planning/behavior_velocity_intersection_module/src/manager.cpp
+++ b/planning/behavior_velocity_intersection_module/src/manager.cpp
@@ -35,11 +35,13 @@ using tier4_autoware_utils::getOrDeclareParameter;
IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
- getOrDeclareParameter(node, std::string(getModuleName()) + ".enable_rtc.intersection")),
+ (!getOrDeclareParameter(node, "enable_all_modules_auto_mode") &&
+ getOrDeclareParameter(node, std::string(getModuleName()) + ".enable_rtc.intersection"))),
occlusion_rtc_interface_(
&node, "intersection_occlusion",
- getOrDeclareParameter(
- node, std::string(getModuleName()) + ".enable_rtc.intersection_to_occlusion"))
+ (!getOrDeclareParameter(node, "enable_all_modules_auto_mode") &&
+ getOrDeclareParameter(
+ node, std::string(getModuleName()) + ".enable_rtc.intersection_to_occlusion")))
{
const std::string ns(getModuleName());
auto & ip = intersection_param_;
diff --git a/planning/behavior_velocity_no_stopping_area_module/src/manager.cpp b/planning/behavior_velocity_no_stopping_area_module/src/manager.cpp
index d5e9eeddb6377..ed7d2c99c4793 100644
--- a/planning/behavior_velocity_no_stopping_area_module/src/manager.cpp
+++ b/planning/behavior_velocity_no_stopping_area_module/src/manager.cpp
@@ -36,7 +36,8 @@ using tier4_autoware_utils::getOrDeclareParameter;
NoStoppingAreaModuleManager::NoStoppingAreaModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
- getOrDeclareParameter(node, std::string(getModuleName()) + ".enable_rtc"))
+ (!getOrDeclareParameter(node, "enable_all_modules_auto_mode") &&
+ getOrDeclareParameter(node, std::string(getModuleName()) + ".enable_rtc")))
{
const std::string ns(getModuleName());
auto & pp = planner_param_;
diff --git a/planning/behavior_velocity_traffic_light_module/src/manager.cpp b/planning/behavior_velocity_traffic_light_module/src/manager.cpp
index fa1a516c107b0..3980f26d6e5a5 100644
--- a/planning/behavior_velocity_traffic_light_module/src/manager.cpp
+++ b/planning/behavior_velocity_traffic_light_module/src/manager.cpp
@@ -32,7 +32,8 @@ using tier4_autoware_utils::getOrDeclareParameter;
TrafficLightModuleManager::TrafficLightModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
- getOrDeclareParameter(node, std::string(getModuleName()) + ".enable_rtc"))
+ (!getOrDeclareParameter(node, "enable_all_modules_auto_mode") &&
+ getOrDeclareParameter(node, std::string(getModuleName()) + ".enable_rtc")))
{
const std::string ns(getModuleName());
planner_param_.stop_margin = getOrDeclareParameter(node, ns + ".stop_margin");