diff --git a/launch/tier4_planning_launch/launch/planning.launch.xml b/launch/tier4_planning_launch/launch/planning.launch.xml
index e02ba883d5115..710fb20631a45 100644
--- a/launch/tier4_planning_launch/launch/planning.launch.xml
+++ b/launch/tier4_planning_launch/launch/planning.launch.xml
@@ -9,6 +9,7 @@
+
@@ -25,6 +26,7 @@
+
diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving.launch.xml
index bae084f80b51e..1ec74793b741b 100644
--- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving.launch.xml
+++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving.launch.xml
@@ -1,5 +1,6 @@
+
@@ -11,6 +12,7 @@
+
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 90ebd23215be5..d2aa009d9c699 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
@@ -5,6 +5,7 @@
+
@@ -203,6 +204,7 @@
+
@@ -245,6 +247,7 @@
+
diff --git a/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml
index e673d28804480..0a30204ca3c99 100644
--- a/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml
+++ b/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml
@@ -1,5 +1,6 @@
+
@@ -53,6 +54,7 @@
+
diff --git a/planning/behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/src/node.cpp
index 9f18a1a6de816..854f3c8852c29 100644
--- a/planning/behavior_velocity_planner/src/node.cpp
+++ b/planning/behavior_velocity_planner/src/node.cpp
@@ -146,6 +146,9 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
declare_parameter("ego_nearest_dist_threshold");
planner_data_.ego_nearest_yaw_threshold = declare_parameter("ego_nearest_yaw_threshold");
+ // is simulation or not
+ planner_data_.is_simulation = declare_parameter("is_simulation");
+
// Initialize PlannerManager
for (const auto & name : declare_parameter>("launch_modules")) {
// workaround: Since ROS 2 can't get empty list, launcher set [''] on the parameter.
@@ -323,8 +326,6 @@ void BehaviorVelocityPlannerNode::onTrafficSignals(
{
std::lock_guard lock(mutex_);
- planner_data_.has_received_signal_ = true;
-
// clear previous observation
planner_data_.traffic_light_id_map_raw_.clear();
const auto traffic_light_id_map_last_observed_old =
diff --git a/planning/behavior_velocity_planner/test/src/test_node_interface.cpp b/planning/behavior_velocity_planner/test/src/test_node_interface.cpp
index 239abbde27609..935530b52e175 100644
--- a/planning/behavior_velocity_planner/test/src/test_node_interface.cpp
+++ b/planning/behavior_velocity_planner/test/src/test_node_interface.cpp
@@ -79,6 +79,7 @@ std::shared_ptr generateNode()
std::vector params;
params.emplace_back("launch_modules", module_names);
+ params.emplace_back("is_simulation", false);
node_options.parameter_overrides(params);
test_utils::updateNodeOptions(
diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp
index 23997e34fbfea..1511d430ddd0c 100644
--- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp
+++ b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp
@@ -83,8 +83,9 @@ struct PlannerData
std::optional external_velocity_limit;
tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr virtual_traffic_light_states;
- // this value becomes true once the signal message is received
- bool has_received_signal_ = false;
+ // This variable is used when the Autoware's behavior has to depend on whether it's simulation or
+ // not.
+ bool is_simulation = false;
// velocity smoother
std::shared_ptr velocity_smoother_;
diff --git a/planning/behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_traffic_light_module/src/scene.cpp
index 946741b14cf78..413ce78beacee 100644
--- a/planning/behavior_velocity_traffic_light_module/src/scene.cpp
+++ b/planning/behavior_velocity_traffic_light_module/src/scene.cpp
@@ -281,16 +281,15 @@ bool TrafficLightModule::isStopSignal()
{
updateTrafficSignal();
- // Pass through if no traffic signal information has been received yet
- // This is to prevent stopping on the planning simulator
- if (!planner_data_->has_received_signal_) {
- return false;
- }
-
- // Stop if there is no upcoming traffic signal information
- // This is to safely stop in cases such that traffic light recognition is not working properly or
- // the map is incorrect
+ // If there is no upcoming traffic signal information,
+ // SIMULATION: it will PASS to prevent stopping on the planning simulator
+ // or scenario simulator.
+ // REAL ENVIRONMENT: it will STOP for safety in cases such that traffic light
+ // recognition is not working properly or the map is incorrect.
if (!traffic_signal_stamp_) {
+ if (planner_data_->is_simulation) {
+ return false;
+ }
return true;
}