Skip to content

Commit 2b1a33f

Browse files
authored
feat(intersection): memorize last observed valid traffic light information (#6272)
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent e063f2d commit 2b1a33f

File tree

4 files changed

+163
-55
lines changed

4 files changed

+163
-55
lines changed

planning/behavior_velocity_intersection_module/src/debug.cpp

+41-2
Original file line numberDiff line numberDiff line change
@@ -111,7 +111,7 @@ visualization_msgs::msg::MarkerArray createPoseMarkerArray(
111111
return msg;
112112
}
113113

114-
visualization_msgs::msg::MarkerArray createLineMarkerArray(
114+
visualization_msgs::msg::MarkerArray createArrowLineMarkerArray(
115115
const geometry_msgs::msg::Point & point_start, const geometry_msgs::msg::Point & point_end,
116116
const std::string & ns, const int64_t id, const double r, const double g, const double b)
117117
{
@@ -137,6 +137,28 @@ visualization_msgs::msg::MarkerArray createLineMarkerArray(
137137
return msg;
138138
}
139139

140+
visualization_msgs::msg::MarkerArray createLineMarkerArray(
141+
const geometry_msgs::msg::Point & point_start, const geometry_msgs::msg::Point & point_end,
142+
const std::string & ns, const int64_t id, const double r, const double g, const double b)
143+
{
144+
visualization_msgs::msg::MarkerArray msg;
145+
146+
visualization_msgs::msg::Marker marker;
147+
marker.header.frame_id = "map";
148+
marker.ns = ns + "_line";
149+
marker.id = id;
150+
marker.lifetime = rclcpp::Duration::from_seconds(0.3);
151+
marker.type = visualization_msgs::msg::Marker::LINE_STRIP;
152+
marker.action = visualization_msgs::msg::Marker::ADD;
153+
marker.scale.x = 0.1;
154+
marker.color = createMarkerColor(r, g, b, 0.999);
155+
marker.points.push_back(point_start);
156+
marker.points.push_back(point_end);
157+
158+
msg.markers.push_back(marker);
159+
return msg;
160+
}
161+
140162
[[maybe_unused]] visualization_msgs::msg::Marker createPointMarkerArray(
141163
const geometry_msgs::msg::Point & point, const std::string & ns, const int64_t id, const double r,
142164
const double g, const double b)
@@ -362,10 +384,27 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray(
362384
if (debug_data_.nearest_occlusion_projection) {
363385
const auto [point_start, point_end] = debug_data_.nearest_occlusion_projection.value();
364386
appendMarkerArray(
365-
::createLineMarkerArray(
387+
::createArrowLineMarkerArray(
366388
point_start, point_end, "nearest_occlusion_projection", lane_id_, 0.5, 0.5, 0.0),
367389
&debug_marker_array, now);
368390
}
391+
392+
if (debug_data_.traffic_light_observation) {
393+
const auto GREEN = autoware_perception_msgs::msg::TrafficSignalElement::GREEN;
394+
const auto YELLOW = autoware_perception_msgs::msg::TrafficSignalElement::AMBER;
395+
396+
const auto [ego, tl_point, id, color] = debug_data_.traffic_light_observation.value();
397+
geometry_msgs::msg::Point tl_point_point;
398+
tl_point_point.x = tl_point.x();
399+
tl_point_point.y = tl_point.y();
400+
tl_point_point.z = tl_point.z();
401+
const auto tl_color = (color == GREEN) ? green : (color == YELLOW ? yellow : red);
402+
const auto [r, g, b] = tl_color;
403+
appendMarkerArray(
404+
::createLineMarkerArray(
405+
ego.position, tl_point_point, "intersection_traffic_light", lane_id_, r, g, b),
406+
&debug_marker_array, now);
407+
}
369408
return debug_marker_array;
370409
}
371410

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

+77-40
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818

1919
#include <behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp> // for toGeomPoly
2020
#include <behavior_velocity_planner_common/utilization/util.hpp>
21+
#include <lanelet2_extension/regulatory_elements/autoware_traffic_light.hpp>
2122
#include <lanelet2_extension/utility/utilities.hpp>
2223
#include <motion_utils/trajectory/trajectory.hpp>
2324
#include <tier4_autoware_utils/geometry/boost_polygon_utils.hpp> // for toPolygon2d
@@ -1143,25 +1144,11 @@ void IntersectionModule::reactRTCApproval(
11431144
bool IntersectionModule::isGreenSolidOn() const
11441145
{
11451146
using TrafficSignalElement = autoware_perception_msgs::msg::TrafficSignalElement;
1146-
const auto lanelet_map_ptr = planner_data_->route_handler_->getLaneletMapPtr();
1147-
const auto & lane = lanelet_map_ptr->laneletLayer.get(lane_id_);
11481147

1149-
std::optional<lanelet::Id> tl_id = std::nullopt;
1150-
for (auto && tl_reg_elem : lane.regulatoryElementsAs<lanelet::TrafficLight>()) {
1151-
tl_id = tl_reg_elem->id();
1152-
break;
1153-
}
1154-
if (!tl_id) {
1155-
// this lane has no traffic light
1156-
return false;
1157-
}
1158-
const auto tl_info_opt = planner_data_->getTrafficSignal(
1159-
tl_id.value(), true /* traffic light module keeps last observation*/);
1160-
if (!tl_info_opt) {
1161-
// the info of this traffic light is not available
1148+
if (!last_tl_valid_observation_) {
11621149
return false;
11631150
}
1164-
const auto & tl_info = tl_info_opt.value();
1151+
const auto & tl_info = last_tl_valid_observation_.value();
11651152
for (auto && tl_light : tl_info.signal.elements) {
11661153
if (
11671154
tl_light.color == TrafficSignalElement::GREEN &&
@@ -1176,38 +1163,88 @@ IntersectionModule::TrafficPrioritizedLevel IntersectionModule::getTrafficPriori
11761163
{
11771164
using TrafficSignalElement = autoware_perception_msgs::msg::TrafficSignalElement;
11781165

1166+
auto corresponding_arrow = [&](const TrafficSignalElement & element) {
1167+
if (turn_direction_ == "straight" && element.shape == TrafficSignalElement::UP_ARROW) {
1168+
return true;
1169+
}
1170+
if (turn_direction_ == "left" && element.shape == TrafficSignalElement::LEFT_ARROW) {
1171+
return true;
1172+
}
1173+
if (turn_direction_ == "right" && element.shape == TrafficSignalElement::RIGHT_ARROW) {
1174+
return true;
1175+
}
1176+
return false;
1177+
};
1178+
1179+
// ==========================================================================================
1180+
// if no traffic light information has been available, it is UNKNOWN state which is treated as
1181+
// NOT_PRIORITIZED
1182+
//
1183+
// if there has been any information available in the past more than once, the last valid
1184+
// information is kept and used for planning
1185+
// ==========================================================================================
1186+
auto level = TrafficPrioritizedLevel::NOT_PRIORITIZED;
1187+
if (last_tl_valid_observation_) {
1188+
auto color = TrafficSignalElement::GREEN;
1189+
const auto & tl_info = last_tl_valid_observation_.value();
1190+
bool has_amber_signal{false};
1191+
for (auto && tl_light : tl_info.signal.elements) {
1192+
if (
1193+
tl_light.color == TrafficSignalElement::AMBER &&
1194+
tl_light.shape == TrafficSignalElement::CIRCLE) {
1195+
has_amber_signal = true;
1196+
}
1197+
if (
1198+
(tl_light.color == TrafficSignalElement::RED &&
1199+
tl_light.shape == TrafficSignalElement::CIRCLE) ||
1200+
(tl_light.color == TrafficSignalElement::GREEN && corresponding_arrow(tl_light))) {
1201+
// NOTE: Return here since the red signal has the highest priority.
1202+
level = TrafficPrioritizedLevel::FULLY_PRIORITIZED;
1203+
color = TrafficSignalElement::RED;
1204+
break;
1205+
}
1206+
}
1207+
if (has_amber_signal) {
1208+
level = TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED;
1209+
color = TrafficSignalElement::AMBER;
1210+
}
1211+
if (tl_id_and_point_) {
1212+
const auto [tl_id, point] = tl_id_and_point_.value();
1213+
debug_data_.traffic_light_observation =
1214+
std::make_tuple(planner_data_->current_odometry->pose, point, tl_id, color);
1215+
}
1216+
}
1217+
return level;
1218+
}
1219+
1220+
void IntersectionModule::updateTrafficSignalObservation()
1221+
{
11791222
const auto lanelet_map_ptr = planner_data_->route_handler_->getLaneletMapPtr();
11801223
const auto & lane = lanelet_map_ptr->laneletLayer.get(lane_id_);
11811224

1182-
std::optional<lanelet::Id> tl_id = std::nullopt;
1183-
for (auto && tl_reg_elem : lane.regulatoryElementsAs<lanelet::TrafficLight>()) {
1184-
tl_id = tl_reg_elem->id();
1185-
break;
1225+
if (!tl_id_and_point_) {
1226+
for (auto && tl_reg_elem :
1227+
lane.regulatoryElementsAs<lanelet::autoware::AutowareTrafficLight>()) {
1228+
for (const auto & ls : tl_reg_elem->lightBulbs()) {
1229+
if (ls.hasAttribute("traffic_light_id")) {
1230+
tl_id_and_point_ = std::make_pair(tl_reg_elem->id(), ls.front());
1231+
break;
1232+
}
1233+
}
1234+
}
11861235
}
1187-
if (!tl_id) {
1236+
if (!tl_id_and_point_) {
11881237
// this lane has no traffic light
1189-
return TrafficPrioritizedLevel::NOT_PRIORITIZED;
1238+
return;
11901239
}
1191-
const auto tl_info_opt = planner_data_->getTrafficSignal(
1192-
tl_id.value(), true /* traffic light module keeps last observation*/);
1240+
const auto [tl_id, point] = tl_id_and_point_.value();
1241+
const auto tl_info_opt =
1242+
planner_data_->getTrafficSignal(tl_id, true /* traffic light module keeps last observation*/);
11931243
if (!tl_info_opt) {
1194-
return TrafficPrioritizedLevel::NOT_PRIORITIZED;
1195-
}
1196-
const auto & tl_info = tl_info_opt.value();
1197-
bool has_amber_signal{false};
1198-
for (auto && tl_light : tl_info.signal.elements) {
1199-
if (tl_light.color == TrafficSignalElement::AMBER) {
1200-
has_amber_signal = true;
1201-
}
1202-
if (tl_light.color == TrafficSignalElement::RED) {
1203-
// NOTE: Return here since the red signal has the highest priority.
1204-
return TrafficPrioritizedLevel::FULLY_PRIORITIZED;
1205-
}
1206-
}
1207-
if (has_amber_signal) {
1208-
return TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED;
1244+
// the info of this traffic light is not available
1245+
return;
12091246
}
1210-
return TrafficPrioritizedLevel::NOT_PRIORITIZED;
1247+
last_tl_valid_observation_ = tl_info_opt.value();
12111248
}
12121249

12131250
IntersectionModule::PassJudgeStatus IntersectionModule::isOverPassJudgeLinesStatus(

planning/behavior_velocity_intersection_module/src/scene_intersection.hpp

+24
Original file line numberDiff line numberDiff line change
@@ -209,6 +209,9 @@ class IntersectionModule : public SceneModuleInterface
209209
std::optional<std::pair<geometry_msgs::msg::Point, geometry_msgs::msg::Point>>
210210
nearest_occlusion_projection{std::nullopt};
211211
std::optional<double> static_occlusion_with_traffic_light_timeout{std::nullopt};
212+
213+
std::optional<std::tuple<geometry_msgs::msg::Pose, lanelet::ConstPoint3d, lanelet::Id, uint8_t>>
214+
traffic_light_observation{std::nullopt};
212215
};
213216

214217
using TimeDistanceArray = std::vector<std::pair<double /* time*/, double /* distance*/>>;
@@ -388,6 +391,20 @@ class IntersectionModule : public SceneModuleInterface
388391
intersection::ObjectInfoManager object_info_manager_;
389392
/** @} */
390393

394+
private:
395+
/**
396+
***********************************************************
397+
***********************************************************
398+
***********************************************************
399+
* @defgroup collision-variables [var] collision detection
400+
* @{
401+
*/
402+
//! save the last UNKNOWN traffic light information of this intersection(keep even if the info got
403+
//! unavailable)
404+
std::optional<std::pair<lanelet::Id, lanelet::ConstPoint3d>> tl_id_and_point_;
405+
std::optional<TrafficSignalStamped> last_tl_valid_observation_{std::nullopt};
406+
/** @} */
407+
391408
private:
392409
/**
393410
***********************************************************
@@ -556,6 +573,13 @@ class IntersectionModule : public SceneModuleInterface
556573
* @brief find TrafficPrioritizedLevel
557574
*/
558575
TrafficPrioritizedLevel getTrafficPrioritizedLevel() const;
576+
577+
/**
578+
* @brief update the valid traffic signal information if still available, otherwise keep last
579+
* observation
580+
*/
581+
void updateTrafficSignalObservation();
582+
559583
/** @} */
560584

561585
private:

planning/behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp

+21-13
Original file line numberDiff line numberDiff line change
@@ -258,19 +258,27 @@ IntersectionModule::prepareIntersectionData(const bool is_prioritized, PathWithL
258258
planner_data_->occupancy_grid->info.resolution);
259259
}
260260

261-
const bool is_green_solid_on = isGreenSolidOn();
262-
if (is_green_solid_on && !initial_green_light_observed_time_) {
263-
const auto assigned_lane_begin_point = assigned_lanelet.centerline().front();
264-
const bool approached_assigned_lane =
265-
motion_utils::calcSignedArcLength(
266-
path->points, closest_idx,
267-
tier4_autoware_utils::createPoint(
268-
assigned_lane_begin_point.x(), assigned_lane_begin_point.y(),
269-
assigned_lane_begin_point.z())) <
270-
planner_param_.collision_detection.yield_on_green_traffic_light
271-
.distance_to_assigned_lanelet_start;
272-
if (approached_assigned_lane) {
273-
initial_green_light_observed_time_ = clock_->now();
261+
// ==========================================================================================
262+
// update traffic light information
263+
// updateTrafficSignalObservation() must be called at first to because other traffic signal
264+
// fuctions use last_valid_observation_
265+
// ==========================================================================================
266+
if (has_traffic_light_) {
267+
updateTrafficSignalObservation();
268+
const bool is_green_solid_on = isGreenSolidOn();
269+
if (is_green_solid_on && !initial_green_light_observed_time_) {
270+
const auto assigned_lane_begin_point = assigned_lanelet.centerline().front();
271+
const bool approached_assigned_lane =
272+
motion_utils::calcSignedArcLength(
273+
path->points, closest_idx,
274+
tier4_autoware_utils::createPoint(
275+
assigned_lane_begin_point.x(), assigned_lane_begin_point.y(),
276+
assigned_lane_begin_point.z())) <
277+
planner_param_.collision_detection.yield_on_green_traffic_light
278+
.distance_to_assigned_lanelet_start;
279+
if (approached_assigned_lane) {
280+
initial_green_light_observed_time_ = clock_->now();
281+
}
274282
}
275283
}
276284

0 commit comments

Comments
 (0)