Skip to content

Commit 5e3de0b

Browse files
committed
feat(behavior_velocity_traffic_light): stop when the signal is unknown or timed out
Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>
1 parent 7cd94fc commit 5e3de0b

File tree

2 files changed

+57
-25
lines changed

2 files changed

+57
-25
lines changed

planning/behavior_velocity_traffic_light_module/src/scene.cpp

+51-25
Original file line numberDiff line numberDiff line change
@@ -228,33 +228,31 @@ bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopReason *
228228

229229
first_ref_stop_path_point_index_ = stop_line_point_idx;
230230

231-
// Check if stop is coming.
232-
const bool is_stop_signal = isStopSignal();
231+
// Update traffic signal information
232+
updateTrafficSignal();
233+
234+
const bool is_unknown_signal = isUnknownSignal(looking_tl_state_);
235+
const bool is_signal_timed_out = isTrafficSignalTimedOut();
233236

234237
// Decide if stop or proceed using the remaining time to red signal
238+
// If the upcoming traffic signal color is unknown or timed out, do not use the time to red and
239+
// stop for the traffic signal
235240
const auto rest_time_to_red_signal =
236241
planner_data_->getRestTimeToRedSignal(traffic_light_reg_elem_.id());
237-
if (
238-
planner_param_.v2i_use_rest_time && rest_time_to_red_signal &&
239-
!isDataTimeout(rest_time_to_red_signal->stamp)) {
240-
const double rest_time_allowed_to_go_ahead =
241-
rest_time_to_red_signal->time_to_red - planner_param_.v2i_last_time_allowed_to_pass;
242-
243-
const double ego_v = planner_data_->current_velocity->twist.linear.x;
244-
if (ego_v >= planner_param_.v2i_velocity_threshold) {
245-
if (ego_v * rest_time_allowed_to_go_ahead <= signed_arc_length_to_stop_point) {
246-
*path = insertStopPose(input_path, stop_line_point_idx, stop_line_point, stop_reason);
247-
}
248-
} else {
249-
if (rest_time_allowed_to_go_ahead < planner_param_.v2i_required_time_to_departure) {
250-
*path = insertStopPose(input_path, stop_line_point_idx, stop_line_point, stop_reason);
251-
}
242+
const bool is_stop_required = is_unknown_signal || is_signal_timed_out;
243+
244+
if (planner_param_.v2i_use_rest_time && rest_time_to_red_signal && !is_stop_required) {
245+
if (!canPassStopLineBeforeRed(*rest_time_to_red_signal, signed_arc_length_to_stop_point)) {
246+
*path = insertStopPose(input_path, stop_line_point_idx, stop_line_point, stop_reason);
252247
}
253248
return true;
254249
}
255250

251+
// Check if stop is coming.
252+
const bool is_stop_signal = isStopSignal();
253+
256254
// Update stop signal received time
257-
if (is_stop_signal) {
255+
if (is_stop_signal || is_unknown_signal || is_signal_timed_out) {
258256
if (!stop_signal_received_time_ptr_) {
259257
stop_signal_received_time_ptr_ = std::make_unique<Time>(clock_->now());
260258
}
@@ -301,8 +299,6 @@ bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopReason *
301299

302300
bool TrafficLightModule::isStopSignal()
303301
{
304-
updateTrafficSignal();
305-
306302
// Pass through if no traffic signal information has been received yet
307303
// This is to prevent stopping on the planning simulator
308304
if (!planner_data_->has_received_signal_) {
@@ -316,11 +312,6 @@ bool TrafficLightModule::isStopSignal()
316312
return true;
317313
}
318314

319-
// Stop if the traffic signal information has timed out
320-
if (isTrafficSignalTimedOut()) {
321-
return true;
322-
}
323-
324315
return isTrafficSignalStop(looking_tl_state_);
325316
}
326317

@@ -523,4 +514,39 @@ bool TrafficLightModule::isDataTimeout(const rclcpp::Time & data_time) const
523514
return is_data_timeout;
524515
}
525516

517+
bool TrafficLightModule::canPassStopLineBeforeRed(
518+
const TrafficSignalTimeToRedStamped & time_to_red_signal,
519+
const double distance_to_stop_line) const
520+
{
521+
if (isDataTimeout(time_to_red_signal.stamp)) {
522+
return false;
523+
}
524+
525+
const double rest_time_allowed_to_go_ahead =
526+
time_to_red_signal.time_to_red - planner_param_.v2i_last_time_allowed_to_pass;
527+
528+
const double ego_v = planner_data_->current_velocity->twist.linear.x;
529+
if (ego_v >= planner_param_.v2i_velocity_threshold) {
530+
if (ego_v * rest_time_allowed_to_go_ahead <= distance_to_stop_line) {
531+
return false;
532+
}
533+
} else {
534+
if (rest_time_allowed_to_go_ahead < planner_param_.v2i_required_time_to_departure) {
535+
return false;
536+
}
537+
}
538+
539+
return true;
540+
}
541+
542+
bool TrafficLightModule::isUnknownSignal(const TrafficSignal & tl_state) const
543+
{
544+
if (tl_state.elements.empty()) {
545+
return false;
546+
}
547+
548+
const bool has_unknown = hasTrafficLightCircleColor(tl_state, TrafficSignalElement::UNKNOWN);
549+
return has_unknown;
550+
}
551+
526552
} // namespace behavior_velocity_planner

planning/behavior_velocity_traffic_light_module/src/scene.hpp

+6
Original file line numberDiff line numberDiff line change
@@ -110,10 +110,16 @@ class TrafficLightModule : public SceneModuleInterface
110110

111111
bool isTrafficSignalTimedOut() const;
112112

113+
bool isUnknownSignal(const TrafficSignal & tl_state) const;
114+
113115
void updateTrafficSignal();
114116

115117
bool isDataTimeout(const rclcpp::Time & data_time) const;
116118

119+
bool canPassStopLineBeforeRed(
120+
const TrafficSignalTimeToRedStamped & time_to_red_signal,
121+
const double distance_to_stop_line) const;
122+
117123
// Lane id
118124
const int64_t lane_id_;
119125

0 commit comments

Comments
 (0)