19
19
#include < autoware/behavior_velocity_planner_common/utilization/util.hpp>
20
20
#include < autoware/motion_utils/trajectory/trajectory.hpp>
21
21
#include < autoware/traffic_light_utils/traffic_light_utils.hpp>
22
+ #include < rclcpp/clock.hpp>
23
+ #include < rclcpp/logging.hpp>
22
24
23
25
#include < boost/geometry/algorithms/distance.hpp>
24
26
#include < boost/geometry/algorithms/intersection.hpp>
25
27
26
28
#include < tf2/utils.h>
27
29
30
+ #include < ctime>
28
31
#include < memory>
32
+ #include < optional>
29
33
30
34
#ifdef ROS_DISTRO_GALACTIC
31
35
#include < tf2_eigen/tf2_eigen.h>
@@ -45,6 +49,8 @@ TrafficLightModule::TrafficLightModule(
45
49
lanelet::ConstLanelet lane, const PlannerParam & planner_param, const rclcpp::Logger logger,
46
50
const rclcpp::Clock::SharedPtr clock,
47
51
const std::shared_ptr<universe_utils::TimeKeeper> time_keeper,
52
+ const std::function<std::optional<TrafficSignalTimeToRedStamped>(void )> &
53
+ get_rest_time_to_red_signal,
48
54
const std::shared_ptr<planning_factor_interface::PlanningFactorInterface>
49
55
planning_factor_interface)
50
56
: SceneModuleInterfaceWithRTC(lane_id, logger, clock, time_keeper, planning_factor_interface),
@@ -53,7 +59,8 @@ TrafficLightModule::TrafficLightModule(
53
59
lane_(lane),
54
60
state_(State::APPROACH),
55
61
debug_data_(),
56
- is_prev_state_stop_(false )
62
+ is_prev_state_stop_(false ),
63
+ get_rest_time_to_red_signal_(get_rest_time_to_red_signal)
57
64
{
58
65
planner_param_ = planner_param;
59
66
}
@@ -110,6 +117,16 @@ bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path)
110
117
// Check if stop is coming.
111
118
const bool is_stop_signal = isStopSignal ();
112
119
120
+ // Use V2I if available
121
+ if (planner_param_.v2i_use_rest_time && !is_stop_signal) {
122
+ bool is_v2i_handled = handleV2I (signed_arc_length_to_stop_point, [&]() {
123
+ *path = insertStopPose (input_path, stop_line.value ().first , stop_line.value ().second );
124
+ });
125
+ if (is_v2i_handled) {
126
+ return true ;
127
+ }
128
+ }
129
+
113
130
// Update stop signal received time
114
131
if (is_stop_signal) {
115
132
if (!stop_signal_received_time_ptr_) {
@@ -186,6 +203,9 @@ void TrafficLightModule::updateTrafficSignal()
186
203
TrafficSignalStamped signal ;
187
204
if (!findValidTrafficSignal (signal )) {
188
205
// Don't stop if it never receives traffic light topic.
206
+ // Reset looking_tl_state
207
+ looking_tl_state_.elements .clear ();
208
+ looking_tl_state_.traffic_light_group_id = 0 ;
189
209
return ;
190
210
}
191
211
@@ -213,7 +233,7 @@ bool TrafficLightModule::isPassthrough(const double & signed_arc_length) const
213
233
delay_response_time);
214
234
215
235
const bool distance_stoppable = pass_judge_line_distance < signed_arc_length;
216
- const bool slow_velocity = planner_data_->current_velocity ->twist .linear .x < 2 .0 ;
236
+ const bool slow_velocity = planner_data_->current_velocity ->twist .linear .x < 1 .0 ;
217
237
const bool stoppable = distance_stoppable || slow_velocity;
218
238
const bool reachable = signed_arc_length < reachable_distance;
219
239
@@ -302,4 +322,44 @@ tier4_planning_msgs::msg::PathWithLaneId TrafficLightModule::insertStopPose(
302
322
return modified_path;
303
323
}
304
324
325
+ bool TrafficLightModule::handleV2I (
326
+ const double & signed_arc_length_to_stop_point, const std::function<void ()> & insert_stop_pose)
327
+ {
328
+ std::optional<TrafficSignalTimeToRedStamped> rest_time_to_red_signal =
329
+ get_rest_time_to_red_signal_ ();
330
+
331
+ if (!rest_time_to_red_signal) {
332
+ RCLCPP_WARN_THROTTLE (
333
+ logger_, *clock_, 5000 ,
334
+ " Failed to get V2I rest time to red signal. traffic_light_lane_id: %ld" , lane_id_);
335
+ return false ;
336
+ }
337
+
338
+ auto time_diff = (clock_->now () - rest_time_to_red_signal->stamp ).seconds ();
339
+ if (time_diff > planner_param_.tl_state_timeout ) {
340
+ RCLCPP_WARN_THROTTLE (
341
+ logger_, *clock_, 5000 , " V2I data is timeout. traffic_light_lane_id: %ld, time diff: %f" ,
342
+ lane_id_, time_diff);
343
+ return false ;
344
+ }
345
+
346
+ const double rest_time_allowed_to_go_ahead =
347
+ rest_time_to_red_signal->time_to_red - planner_param_.v2i_last_time_allowed_to_pass ;
348
+ const double ego_v = planner_data_->current_velocity ->twist .linear .x ;
349
+
350
+ const bool should_stop =
351
+ (ego_v >= planner_param_.v2i_velocity_threshold &&
352
+ ego_v * rest_time_allowed_to_go_ahead <= signed_arc_length_to_stop_point) ||
353
+ (ego_v < planner_param_.v2i_velocity_threshold &&
354
+ rest_time_allowed_to_go_ahead < planner_param_.v2i_required_time_to_departure );
355
+
356
+ setSafe (!should_stop);
357
+ if (isActivated ()) {
358
+ is_prev_state_stop_ = false ;
359
+ return true ;
360
+ }
361
+ insert_stop_pose ();
362
+ is_prev_state_stop_ = true ;
363
+ return true ;
364
+ }
305
365
} // namespace autoware::behavior_velocity_planner
0 commit comments