diff --git a/launch/tier4_planning_launch/launch/planning.launch.xml b/launch/tier4_planning_launch/launch/planning.launch.xml
index 7e78c8842f7df..655843e1bbc1b 100644
--- a/launch/tier4_planning_launch/launch/planning.launch.xml
+++ b/launch/tier4_planning_launch/launch/planning.launch.xml
@@ -47,6 +47,7 @@
+
@@ -68,6 +69,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 24a33b9d3f3df..4a0c10eed801f 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,4 +1,6 @@
+
+
@@ -12,6 +14,7 @@
+
diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py
index 5dcaa586506e5..09574dfb99c0e 100644
--- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py
+++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py
@@ -205,6 +205,7 @@ def launch_setup(context, *args, **kwargs):
common_param,
motion_velocity_smoother_param,
behavior_velocity_smoother_type_param,
+ {"is_simulation": LaunchConfiguration("is_simulation")},
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
@@ -301,6 +302,9 @@ def add_launch_arg(name: str, default_value=None, description=None):
add_launch_arg("use_pointcloud_container", "true")
add_launch_arg("container_name", "pointcloud_container")
+ # whether this is a simulation or not
+ add_launch_arg("is_simulation", "false", "whether this is a simulation or not")
+
set_container_executable = SetLaunchConfiguration(
"container_executable",
"component_container",
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 b293c5836817d..8a86a548400f3 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,4 +1,5 @@
+
@@ -58,6 +59,7 @@
+
diff --git a/planning/behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/src/node.cpp
index 7803942f2d16a..81e0515ab40d4 100644
--- a/planning/behavior_velocity_planner/src/node.cpp
+++ b/planning/behavior_velocity_planner/src/node.cpp
@@ -141,6 +141,9 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
planner_data_.ego_nearest_yaw_threshold =
this->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")) {
planner_manager_.launchScenePlugin(*this, name);
@@ -298,8 +301,6 @@ void BehaviorVelocityPlannerNode::onTrafficSignals(
{
std::lock_guard lock(mutex_);
- planner_data_.has_received_signal_ = true;
-
for (const auto & signal : msg->signals) {
TrafficSignalStamped traffic_signal;
traffic_signal.stamp = msg->stamp;
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 caeb134906608..3c606418628f8 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
@@ -89,8 +89,9 @@ struct PlannerData
boost::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 b42895c9927dd..f546db2dcbc9a 100644
--- a/planning/behavior_velocity_traffic_light_module/src/scene.cpp
+++ b/planning/behavior_velocity_traffic_light_module/src/scene.cpp
@@ -302,16 +302,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;
}