Skip to content

Commit

Permalink
feat(behavior_velocity_traffic_light): ensure stopping if a signal, o…
Browse files Browse the repository at this point in the history
…nce received, is not received again (autowarefoundation#6468) (#1156)

feat(behavior_velocity_traffic_light): ensure stopping if a signal, once received, is not received again (autowarefoundation#6468)

* feat(behavior_velocity_traffic_light): ensure stopping if a signal, once received, is not received again."



* add comments for clarity



* fix comments for clarity



---------

Signed-off-by: Tomohito Ando <[email protected]>
  • Loading branch information
TomohitoAndo committed Apr 11, 2024
1 parent 202a178 commit 955c353
Show file tree
Hide file tree
Showing 3 changed files with 16 additions and 2 deletions.
2 changes: 2 additions & 0 deletions planning/behavior_velocity_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -298,6 +298,8 @@ void BehaviorVelocityPlannerNode::onTrafficSignals(
{
std::lock_guard<std::mutex> lock(mutex_);

planner_data_.has_received_signal_ = true;

for (const auto & signal : msg->signals) {
TrafficSignalStamped traffic_signal;
traffic_signal.stamp = msg->stamp;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,9 @@ struct PlannerData
boost::optional<tier4_planning_msgs::msg::VelocityLimit> 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;

// velocity smoother
std::shared_ptr<motion_velocity_smoother::SmootherBase> velocity_smoother_;
// route handler
Expand Down
13 changes: 11 additions & 2 deletions planning/behavior_velocity_traffic_light_module/src/scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -302,11 +302,20 @@ bool TrafficLightModule::isStopSignal()
{
updateTrafficSignal();

// If it never receives traffic signal, it will PASS.
if (!traffic_signal_stamp_) {
// 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 (!traffic_signal_stamp_) {
return true;
}

// Stop if the traffic signal information has timed out
if (isTrafficSignalTimedOut()) {
return true;
}
Expand Down

0 comments on commit 955c353

Please sign in to comment.