Skip to content

Commit fb973cf

Browse files
rej55TomohitoAndo
authored andcommitted
fix(traffic_light): stop if the traffic light signal timed out (autowarefoundation#5819)
* fix(traffic_light): stop if the traffic light signal timed out Signed-off-by: Fumiya Watanabe <rej55.g@gmail.com> * fix(traffic_light): fix README format Signed-off-by: Fumiya Watanabe <rej55.g@gmail.com> --------- Signed-off-by: Fumiya Watanabe <rej55.g@gmail.com> Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>
1 parent fcc11e1 commit fb973cf

File tree

5 files changed

+85
-31
lines changed

5 files changed

+85
-31
lines changed

planning/behavior_velocity_traffic_light_module/README.md

+15-8
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,13 @@ This module is activated when there is traffic light in ego lane.
1919

2020
1. Obtains a traffic light mapped to the route and a stop line correspond to the traffic light from a map information.
2121

22-
2. Uses the highest reliability one of the traffic light recognition result and if the color of that was red, generates a stop point.
22+
- If a corresponding traffic light signal have never been found, it treats as a signal to pass.
23+
24+
- If a corresponding traffic light signal is found but timed out, it treats as a signal to stop.
25+
26+
2. Uses the highest reliability one of the traffic light recognition result and if the color of that was not green or corresponding arrow signal, generates a stop point.
27+
28+
- If an elapsed time to receive stop signal is less than `stop_time_hysteresis`, it treats as a signal to pass. This feature is to prevent chattering.
2329

2430
3. When vehicle current velocity is
2531

@@ -63,12 +69,13 @@ This module is activated when there is traffic light in ego lane.
6369

6470
#### Module Parameters
6571

66-
| Parameter | Type | Description |
67-
| -------------------- | ------ | ----------------------------------------------- |
68-
| `stop_margin` | double | [m] margin before stop point |
69-
| `tl_state_timeout` | double | [s] time out for detected traffic light result. |
70-
| `yellow_lamp_period` | double | [s] time for yellow lamp |
71-
| `enable_pass_judge` | bool | [-] whether to use pass judge |
72+
| Parameter | Type | Description |
73+
| ---------------------- | ------ | -------------------------------------------------------------------- |
74+
| `stop_margin` | double | [m] margin before stop point |
75+
| `tl_state_timeout` | double | [s] time out for detected traffic light result. |
76+
| `stop_time_hysteresis` | double | [s] time threshold to decide stop planning for chattering prevention |
77+
| `yellow_lamp_period` | double | [s] time for yellow lamp |
78+
| `enable_pass_judge` | bool | [-] whether to use pass judge |
7279

7380
#### Flowchart
7481

@@ -91,7 +98,7 @@ if (state is APPROACH) then (yes)
9198
:change state to GO_OUT;
9299
stop
93100
elseif (no stop signal) then (yes)
94-
:change previous state to STOP;
101+
:change previous state to PASS;
95102
stop
96103
elseif (not pass through) then (yes)
97104
:insert stop pose;

planning/behavior_velocity_traffic_light_module/config/traffic_light.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
traffic_light:
44
stop_margin: 0.0
55
tl_state_timeout: 1.0
6+
stop_time_hysteresis: 0.1
67
yellow_lamp_period: 2.75
78
enable_pass_judge: true
89
enable_rtc: true # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval

planning/behavior_velocity_traffic_light_module/src/manager.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,8 @@ TrafficLightModuleManager::TrafficLightModuleManager(rclcpp::Node & node)
3838
const std::string ns(getModuleName());
3939
planner_param_.stop_margin = getOrDeclareParameter<double>(node, ns + ".stop_margin");
4040
planner_param_.tl_state_timeout = getOrDeclareParameter<double>(node, ns + ".tl_state_timeout");
41+
planner_param_.stop_time_hysteresis =
42+
getOrDeclareParameter<double>(node, ns + ".stop_time_hysteresis");
4143
planner_param_.enable_pass_judge = getOrDeclareParameter<bool>(node, ns + ".enable_pass_judge");
4244
planner_param_.yellow_lamp_period =
4345
getOrDeclareParameter<double>(node, ns + ".yellow_lamp_period");

planning/behavior_velocity_traffic_light_module/src/scene.cpp

+55-20
Original file line numberDiff line numberDiff line change
@@ -220,14 +220,35 @@ bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopReason *
220220
if (signed_arc_length_to_stop_point < signed_deadline_length) {
221221
RCLCPP_INFO(logger_, "APPROACH -> GO_OUT");
222222
state_ = State::GO_OUT;
223+
stop_signal_received_time_ptr_.reset();
223224
return true;
224225
}
225226

226227
first_ref_stop_path_point_index_ = stop_line_point_idx;
227228

228229
// Check if stop is coming.
229-
setSafe(!isStopSignal());
230+
const bool is_stop_signal = isStopSignal();
230231

232+
// Update stop signal received time
233+
if (is_stop_signal) {
234+
if (!stop_signal_received_time_ptr_) {
235+
stop_signal_received_time_ptr_ = std::make_unique<Time>(clock_->now());
236+
}
237+
} else {
238+
stop_signal_received_time_ptr_.reset();
239+
}
240+
241+
// Check hysteresis
242+
const double time_diff =
243+
stop_signal_received_time_ptr_
244+
? std::max((clock_->now() - *stop_signal_received_time_ptr_).seconds(), 0.0)
245+
: 0.0;
246+
const bool to_be_stopped =
247+
is_stop_signal && (is_prev_state_stop_ || time_diff > planner_param_.stop_time_hysteresis);
248+
249+
setSafe(!to_be_stopped);
250+
251+
// If the remaining time to red signal is available, decide stop or proceed from it
231252
const auto rest_time_to_red_signal =
232253
planner_data_->getRestTimeToRedSignal(traffic_light_reg_elem_.id());
233254
if (
@@ -270,6 +291,7 @@ bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopReason *
270291
state_ = State::APPROACH;
271292
}
272293
}
294+
stop_signal_received_time_ptr_.reset();
273295
return true;
274296
}
275297

@@ -278,30 +300,36 @@ bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopReason *
278300

279301
bool TrafficLightModule::isStopSignal()
280302
{
281-
if (!updateTrafficSignal()) {
303+
updateTrafficSignal();
304+
305+
// If it never receives traffic signal, it will PASS.
306+
if (!traffic_signal_stamp_) {
282307
return false;
283308
}
284309

310+
if (isTrafficSignalTimedOut()) {
311+
return true;
312+
}
313+
285314
return isTrafficSignalStop(looking_tl_state_);
286315
}
287316

288-
bool TrafficLightModule::updateTrafficSignal()
317+
void TrafficLightModule::updateTrafficSignal()
289318
{
290-
TrafficSignal signal;
291-
bool found_signal = findValidTrafficSignal(signal);
292-
293-
if (!found_signal) {
294-
// Don't stop when UNKNOWN or TIMEOUT as discussed at #508
319+
TrafficSignalStamped signal;
320+
if (!findValidTrafficSignal(signal)) {
321+
// Don't stop if it never receives traffic light topic.
295322
// Reset looking_tl_state
296323
looking_tl_state_.elements.clear();
297324
looking_tl_state_.traffic_signal_id = 0;
298-
return false;
325+
return;
299326
}
300327

301-
// Found signal associated with the lanelet
302-
looking_tl_state_ = signal;
328+
traffic_signal_stamp_ = signal.stamp;
303329

304-
return true;
330+
// Found signal associated with the lanelet
331+
looking_tl_state_ = signal.signal;
332+
return;
305333
}
306334

307335
bool TrafficLightModule::isPassthrough(const double & signed_arc_length) const
@@ -378,7 +406,7 @@ bool TrafficLightModule::isTrafficSignalStop(
378406
return true;
379407
}
380408

381-
bool TrafficLightModule::findValidTrafficSignal(TrafficSignal & valid_traffic_signal)
409+
bool TrafficLightModule::findValidTrafficSignal(TrafficSignalStamped & valid_traffic_signal) const
382410
{
383411
// get traffic signal associated with the regulatory element id
384412
const auto traffic_signal_stamped = planner_data_->getTrafficSignal(traffic_light_reg_elem_.id());
@@ -389,20 +417,27 @@ bool TrafficLightModule::findValidTrafficSignal(TrafficSignal & valid_traffic_si
389417
return false;
390418
}
391419

392-
// check if the traffic signal data is outdated
420+
valid_traffic_signal = *traffic_signal_stamped;
421+
return true;
422+
}
423+
424+
bool TrafficLightModule::isTrafficSignalTimedOut() const
425+
{
426+
if (!traffic_signal_stamp_) {
427+
return false;
428+
}
429+
393430
const auto is_traffic_signal_timeout =
394-
(clock_->now() - traffic_signal_stamped->stamp).seconds() > planner_param_.tl_state_timeout;
431+
(clock_->now() - *traffic_signal_stamp_).seconds() > planner_param_.tl_state_timeout;
395432
if (is_traffic_signal_timeout) {
396433
RCLCPP_WARN_THROTTLE(
397434
logger_, *clock_, 5000 /* ms */, "the received traffic signal data is outdated");
398435
RCLCPP_WARN_STREAM_THROTTLE(
399436
logger_, *clock_, 5000 /* ms */,
400-
"time diff: " << (clock_->now() - traffic_signal_stamped->stamp).seconds());
401-
return false;
437+
"time diff: " << (clock_->now() - *traffic_signal_stamp_).seconds());
438+
return true;
402439
}
403-
404-
valid_traffic_signal = traffic_signal_stamped->signal;
405-
return true;
440+
return false;
406441
}
407442

408443
autoware_auto_planning_msgs::msg::PathWithLaneId TrafficLightModule::insertStopPose(

planning/behavior_velocity_traffic_light_module/src/scene.hpp

+12-3
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@ class TrafficLightModule : public SceneModuleInterface
3939
public:
4040
using TrafficSignal = autoware_perception_msgs::msg::TrafficSignal;
4141
using TrafficSignalElement = autoware_perception_msgs::msg::TrafficSignalElement;
42+
using Time = rclcpp::Time;
4243
enum class State { APPROACH, GO_OUT };
4344

4445
struct DebugData
@@ -60,6 +61,7 @@ class TrafficLightModule : public SceneModuleInterface
6061
double stop_margin;
6162
double tl_state_timeout;
6263
double yellow_lamp_period;
64+
double stop_time_hysteresis;
6365
bool enable_pass_judge;
6466
bool v2i_use_rest_time;
6567
double v2i_last_time_allowed_to_pass;
@@ -104,9 +106,11 @@ class TrafficLightModule : public SceneModuleInterface
104106

105107
bool hasTrafficLightShape(const TrafficSignal & tl_state, const uint8_t & lamp_shape) const;
106108

107-
bool findValidTrafficSignal(TrafficSignal & valid_traffic_signal);
109+
bool findValidTrafficSignal(TrafficSignalStamped & valid_traffic_signal) const;
108110

109-
bool updateTrafficSignal();
111+
bool isTrafficSignalTimedOut() const;
112+
113+
void updateTrafficSignal();
110114

111115
bool isDataTimeout(const rclcpp::Time & data_time) const;
112116

@@ -126,11 +130,16 @@ class TrafficLightModule : public SceneModuleInterface
126130
// Debug
127131
DebugData debug_data_;
128132

129-
// prevent paththrough chattering
133+
// prevent pass through chattering
130134
bool is_prev_state_stop_;
131135

136+
// prevent stop chattering
137+
std::unique_ptr<Time> stop_signal_received_time_ptr_{};
138+
132139
boost::optional<int> first_ref_stop_path_point_index_;
133140

141+
boost::optional<Time> traffic_signal_stamp_;
142+
134143
// Traffic Light State
135144
TrafficSignal looking_tl_state_;
136145
};

0 commit comments

Comments
 (0)