Skip to content

Commit 7452173

Browse files
committed
Apply changes from awf-latest and feat/traffic_light-v2i
Signed-off-by: Y.Hisaki <yhisaki31@gmail.com>
1 parent a270c6c commit 7452173

File tree

6 files changed

+162
-2
lines changed

6 files changed

+162
-2
lines changed

planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/config/traffic_light.param.yaml

+6
Original file line numberDiff line numberDiff line change
@@ -7,3 +7,9 @@
77
yellow_lamp_period: 2.75
88
enable_pass_judge: true
99
enable_rtc: false # 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
10+
11+
v2i:
12+
use_rest_time: false
13+
last_time_allowed_to_pass: 2.0 # relative time against at the time of turn to red
14+
velocity_threshold: 0.5 # change the decision logic whether the current velocity is faster or not
15+
required_time_to_departure: 3.0 # prevent low speed pass

planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@
3131
<depend>autoware_universe_utils</depend>
3232
<depend>eigen</depend>
3333
<depend>geometry_msgs</depend>
34+
<depend>jpn_signal_v2i_msgs</depend>
3435
<depend>pluginlib</depend>
3536
<depend>rclcpp</depend>
3637
<depend>tf2</depend>

planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp

+53
Original file line numberDiff line numberDiff line change
@@ -17,14 +17,17 @@
1717
#include <autoware/behavior_velocity_planner_common/utilization/util.hpp>
1818
#include <autoware/motion_utils/trajectory/trajectory.hpp>
1919
#include <autoware/universe_utils/ros/parameter.hpp>
20+
#include <rclcpp/logging.hpp>
2021

2122
#include <tf2/utils.h>
2223

2324
#include <limits>
2425
#include <memory>
26+
#include <optional>
2527
#include <set>
2628
#include <string>
2729
#include <utility>
30+
#include <vector>
2831
namespace autoware::behavior_velocity_planner
2932
{
3033
using autoware::universe_utils::getOrDeclareParameter;
@@ -42,8 +45,22 @@ TrafficLightModuleManager::TrafficLightModuleManager(rclcpp::Node & node)
4245
planner_param_.enable_pass_judge = getOrDeclareParameter<bool>(node, ns + ".enable_pass_judge");
4346
planner_param_.yellow_lamp_period =
4447
getOrDeclareParameter<double>(node, ns + ".yellow_lamp_period");
48+
planner_param_.v2i_use_rest_time = getOrDeclareParameter<bool>(node, ns + ".v2i.use_rest_time");
49+
planner_param_.v2i_last_time_allowed_to_pass =
50+
getOrDeclareParameter<double>(node, ns + ".v2i.last_time_allowed_to_pass");
51+
planner_param_.v2i_velocity_threshold =
52+
getOrDeclareParameter<double>(node, ns + ".v2i.velocity_threshold");
53+
planner_param_.v2i_required_time_to_departure =
54+
getOrDeclareParameter<double>(node, ns + ".v2i.required_time_to_departure");
4555
pub_tl_state_ = node.create_publisher<autoware_perception_msgs::msg::TrafficLightGroup>(
4656
"~/output/traffic_signal", 1);
57+
58+
if (planner_param_.v2i_use_rest_time) {
59+
RCLCPP_INFO(logger_, "V2I is enabled");
60+
v2i_subscriber_ = autoware::universe_utils::InterProcessPollingSubscriber<
61+
jpn_signal_v2i_msgs::msg::TrafficLightInfo>::
62+
create_subscription(&node, "/v2i/external/v2i_traffic_light_info", 1);
63+
}
4764
}
4865

4966
void TrafficLightModuleManager::modifyPathVelocity(tier4_planning_msgs::msg::PathWithLaneId * path)
@@ -53,6 +70,8 @@ void TrafficLightModuleManager::modifyPathVelocity(tier4_planning_msgs::msg::Pat
5370

5471
autoware_perception_msgs::msg::TrafficLightGroup tl_state;
5572

73+
if (planner_param_.v2i_use_rest_time) updateV2IRestTimeInfo();
74+
5675
nearest_ref_stop_path_point_index_ = static_cast<int>(path->points.size() - 1);
5776
for (const auto & scene_module : scene_modules_) {
5877
std::shared_ptr<TrafficLightModule> traffic_light_scene_module(
@@ -103,6 +122,9 @@ void TrafficLightModuleManager::launchNewModules(
103122
registerModule(std::make_shared<TrafficLightModule>(
104123
lane_id, *(traffic_light_reg_elem.first), traffic_light_reg_elem.second, planner_param_,
105124
logger_.get_child("traffic_light_module"), clock_, time_keeper_,
125+
std::bind(
126+
&TrafficLightModuleManager::getV2IRestTimeToRedSignal, this,
127+
traffic_light_reg_elem.first->id()),
106128
planning_factor_interface_));
107129
generateUUID(lane_id);
108130
updateRTCStatus(
@@ -163,6 +185,37 @@ bool TrafficLightModuleManager::hasSameTrafficLight(
163185
return false;
164186
}
165187

188+
void TrafficLightModuleManager::updateV2IRestTimeInfo()
189+
{
190+
if (!v2i_subscriber_) {
191+
return;
192+
}
193+
auto msg = v2i_subscriber_->takeData();
194+
if (!msg) {
195+
return;
196+
}
197+
198+
std::vector<lanelet::Id> traffic_light_ids;
199+
traffic_light_id_to_rest_time_map_.clear();
200+
for (const auto & car_light : msg->car_lights) {
201+
for (const auto & state : car_light.states) {
202+
traffic_light_id_to_rest_time_map_[state.traffic_light_group_id] = {
203+
msg->header.stamp, car_light.min_rest_time_to_red};
204+
traffic_light_ids.push_back(state.traffic_light_group_id);
205+
}
206+
}
207+
}
208+
209+
std::optional<TrafficSignalTimeToRedStamped> TrafficLightModuleManager::getV2IRestTimeToRedSignal(
210+
const lanelet::Id & id) const
211+
{
212+
const auto rest_time_to_red_signal = traffic_light_id_to_rest_time_map_.find(id);
213+
if (rest_time_to_red_signal == traffic_light_id_to_rest_time_map_.end()) {
214+
return std::nullopt;
215+
}
216+
return rest_time_to_red_signal->second;
217+
}
218+
166219
} // namespace autoware::behavior_velocity_planner
167220

168221
#include <pluginlib/class_list_macros.hpp>

planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.hpp

+13
Original file line numberDiff line numberDiff line change
@@ -20,11 +20,14 @@
2020
#include <autoware/behavior_velocity_planner_common/plugin_interface.hpp>
2121
#include <autoware/behavior_velocity_planner_common/plugin_wrapper.hpp>
2222
#include <autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp>
23+
#include <autoware/universe_utils/ros/polling_subscriber.hpp>
2324
#include <rclcpp/rclcpp.hpp>
2425

26+
#include <jpn_signal_v2i_msgs/msg/traffic_light_info.hpp>
2527
#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>
2628

2729
#include <functional>
30+
#include <map>
2831
#include <memory>
2932
#include <optional>
3033

@@ -55,6 +58,16 @@ class TrafficLightModuleManager : public SceneModuleManagerInterfaceWithRTC
5558
const lanelet::TrafficLightConstPtr element,
5659
const lanelet::TrafficLightConstPtr registered_element) const;
5760

61+
void updateV2IRestTimeInfo();
62+
63+
std::optional<TrafficSignalTimeToRedStamped> getV2IRestTimeToRedSignal(
64+
const lanelet::Id & id) const;
65+
66+
// V2I
67+
autoware::universe_utils::InterProcessPollingSubscriber<
68+
jpn_signal_v2i_msgs::msg::TrafficLightInfo>::SharedPtr v2i_subscriber_;
69+
std::map<lanelet::Id, TrafficSignalTimeToRedStamped> traffic_light_id_to_rest_time_map_;
70+
5871
// Debug
5972
rclcpp::Publisher<autoware_perception_msgs::msg::TrafficLightGroup>::SharedPtr pub_tl_state_;
6073

planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp

+62-2
Original file line numberDiff line numberDiff line change
@@ -19,13 +19,17 @@
1919
#include <autoware/behavior_velocity_planner_common/utilization/util.hpp>
2020
#include <autoware/motion_utils/trajectory/trajectory.hpp>
2121
#include <autoware/traffic_light_utils/traffic_light_utils.hpp>
22+
#include <rclcpp/clock.hpp>
23+
#include <rclcpp/logging.hpp>
2224

2325
#include <boost/geometry/algorithms/distance.hpp>
2426
#include <boost/geometry/algorithms/intersection.hpp>
2527

2628
#include <tf2/utils.h>
2729

30+
#include <ctime>
2831
#include <memory>
32+
#include <optional>
2933

3034
#ifdef ROS_DISTRO_GALACTIC
3135
#include <tf2_eigen/tf2_eigen.h>
@@ -45,6 +49,8 @@ TrafficLightModule::TrafficLightModule(
4549
lanelet::ConstLanelet lane, const PlannerParam & planner_param, const rclcpp::Logger logger,
4650
const rclcpp::Clock::SharedPtr clock,
4751
const std::shared_ptr<universe_utils::TimeKeeper> time_keeper,
52+
const std::function<std::optional<TrafficSignalTimeToRedStamped>(void)> &
53+
get_rest_time_to_red_signal,
4854
const std::shared_ptr<planning_factor_interface::PlanningFactorInterface>
4955
planning_factor_interface)
5056
: SceneModuleInterfaceWithRTC(lane_id, logger, clock, time_keeper, planning_factor_interface),
@@ -53,7 +59,8 @@ TrafficLightModule::TrafficLightModule(
5359
lane_(lane),
5460
state_(State::APPROACH),
5561
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)
5764
{
5865
planner_param_ = planner_param;
5966
}
@@ -110,6 +117,16 @@ bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path)
110117
// Check if stop is coming.
111118
const bool is_stop_signal = isStopSignal();
112119

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+
113130
// Update stop signal received time
114131
if (is_stop_signal) {
115132
if (!stop_signal_received_time_ptr_) {
@@ -186,6 +203,9 @@ void TrafficLightModule::updateTrafficSignal()
186203
TrafficSignalStamped signal;
187204
if (!findValidTrafficSignal(signal)) {
188205
// 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;
189209
return;
190210
}
191211

@@ -213,7 +233,7 @@ bool TrafficLightModule::isPassthrough(const double & signed_arc_length) const
213233
delay_response_time);
214234

215235
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;
217237
const bool stoppable = distance_stoppable || slow_velocity;
218238
const bool reachable = signed_arc_length < reachable_distance;
219239

@@ -302,4 +322,44 @@ tier4_planning_msgs::msg::PathWithLaneId TrafficLightModule::insertStopPose(
302322
return modified_path;
303323
}
304324

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+
}
305365
} // namespace autoware::behavior_velocity_planner

planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp

+27
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#ifndef SCENE_HPP_
1616
#define SCENE_HPP_
1717

18+
#include <functional>
1819
#include <memory>
1920
#include <optional>
2021
#include <tuple>
@@ -33,6 +34,13 @@
3334

3435
namespace autoware::behavior_velocity_planner
3536
{
37+
38+
struct TrafficSignalTimeToRedStamped
39+
{
40+
builtin_interfaces::msg::Time stamp;
41+
double time_to_red{};
42+
};
43+
3644
class TrafficLightModule : public SceneModuleInterfaceWithRTC
3745
{
3846
public:
@@ -63,6 +71,11 @@ class TrafficLightModule : public SceneModuleInterfaceWithRTC
6371
double yellow_lamp_period;
6472
double stop_time_hysteresis;
6573
bool enable_pass_judge;
74+
// V2I Parameter
75+
bool v2i_use_rest_time;
76+
double v2i_last_time_allowed_to_pass;
77+
double v2i_velocity_threshold;
78+
double v2i_required_time_to_departure;
6679
};
6780

6881
public:
@@ -71,6 +84,8 @@ class TrafficLightModule : public SceneModuleInterfaceWithRTC
7184
lanelet::ConstLanelet lane, const PlannerParam & planner_param, const rclcpp::Logger logger,
7285
const rclcpp::Clock::SharedPtr clock,
7386
const std::shared_ptr<universe_utils::TimeKeeper> time_keeper,
87+
const std::function<std::optional<TrafficSignalTimeToRedStamped>(void)> &
88+
get_rest_time_to_red_signal,
7489
const std::shared_ptr<planning_factor_interface::PlanningFactorInterface>
7590
planning_factor_interface);
7691

@@ -103,6 +118,15 @@ class TrafficLightModule : public SceneModuleInterfaceWithRTC
103118

104119
void updateTrafficSignal();
105120

121+
/**
122+
* @brief Handle V2I Rest Time to Red Signal
123+
* @param signed_arc_length_to_stop_point signed arc length to stop point
124+
* @param output_path output path
125+
* @return true if V2I is handled
126+
*/
127+
bool handleV2I(
128+
const double & signed_arc_length_to_stop_point, const std::function<void()> & insert_stop_pose);
129+
106130
// Lane id
107131
const int64_t lane_id_;
108132

@@ -131,6 +155,9 @@ class TrafficLightModule : public SceneModuleInterfaceWithRTC
131155

132156
// Traffic Light State
133157
TrafficSignal looking_tl_state_;
158+
159+
// V2I
160+
std::function<std::optional<TrafficSignalTimeToRedStamped>(void)> get_rest_time_to_red_signal_;
134161
};
135162
} // namespace autoware::behavior_velocity_planner
136163

0 commit comments

Comments
 (0)