Skip to content

Commit 0afead5

Browse files
committed
feat(behavior_velocity): add the option to keep the last valid observation (autowarefoundation#6036)
* feat(behavior_velocity): add the option to keep the last valid observation Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp> * keep_last_observation is false by default and intersection/traffic_light is explicily true Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp> * for intersection Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp> --------- Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 2ea2390 commit 0afead5

File tree

6 files changed

+60
-32
lines changed

6 files changed

+60
-32
lines changed

planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp

+5-4
Original file line numberDiff line numberDiff line change
@@ -1055,19 +1055,20 @@ bool CrosswalkModule::isRedSignalForPedestrians() const
10551055
crosswalk_.regulatoryElementsAs<const lanelet::TrafficLight>();
10561056

10571057
for (const auto & traffic_lights_reg_elem : traffic_lights_reg_elems) {
1058-
const auto traffic_signal_stamped =
1058+
const auto traffic_signal_stamped_opt =
10591059
planner_data_->getTrafficSignal(traffic_lights_reg_elem->id());
1060-
if (!traffic_signal_stamped) {
1060+
if (!traffic_signal_stamped_opt) {
10611061
continue;
10621062
}
1063+
const auto traffic_signal_stamped = traffic_signal_stamped_opt.value();
10631064

10641065
if (
10651066
planner_param_.traffic_light_state_timeout <
1066-
(clock_->now() - traffic_signal_stamped->stamp).seconds()) {
1067+
(clock_->now() - traffic_signal_stamped.stamp).seconds()) {
10671068
continue;
10681069
}
10691070

1070-
const auto & lights = traffic_signal_stamped->signal.elements;
1071+
const auto & lights = traffic_signal_stamped.signal.elements;
10711072
if (lights.empty()) {
10721073
continue;
10731074
}

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

+14-17
Original file line numberDiff line numberDiff line change
@@ -940,12 +940,11 @@ bool IntersectionModule::modifyPathVelocity(PathWithLaneId * path, StopReason *
940940
return true;
941941
}
942942

943-
static bool isGreenSolidOn(
944-
lanelet::ConstLanelet lane, const std::map<int, TrafficSignalStamped> & tl_infos)
943+
bool IntersectionModule::isGreenSolidOn(lanelet::ConstLanelet lane)
945944
{
946945
using TrafficSignalElement = autoware_perception_msgs::msg::TrafficSignalElement;
947946

948-
std::optional<int> tl_id = std::nullopt;
947+
std::optional<lanelet::Id> tl_id = std::nullopt;
949948
for (auto && tl_reg_elem : lane.regulatoryElementsAs<lanelet::TrafficLight>()) {
950949
tl_id = tl_reg_elem->id();
951950
break;
@@ -954,12 +953,13 @@ static bool isGreenSolidOn(
954953
// this lane has no traffic light
955954
return false;
956955
}
957-
const auto tl_info_it = tl_infos.find(tl_id.value());
958-
if (tl_info_it == tl_infos.end()) {
956+
const auto tl_info_opt = planner_data_->getTrafficSignal(
957+
tl_id.value(), true /* traffic light module keeps last observation*/);
958+
if (!tl_info_opt) {
959959
// the info of this traffic light is not available
960960
return false;
961961
}
962-
const auto & tl_info = tl_info_it->second;
962+
const auto & tl_info = tl_info_opt.value();
963963
for (auto && tl_light : tl_info.signal.elements) {
964964
if (
965965
tl_light.color == TrafficSignalElement::GREEN &&
@@ -1004,8 +1004,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
10041004

10051005
// at the very first time of regisTration of this module, the path may not be conflicting with the
10061006
// attention area, so update() is called to update the internal data as well as traffic light info
1007-
const auto traffic_prioritized_level =
1008-
getTrafficPrioritizedLevel(assigned_lanelet, planner_data_->traffic_light_id_map);
1007+
const auto traffic_prioritized_level = getTrafficPrioritizedLevel(assigned_lanelet);
10091008
const bool is_prioritized =
10101009
traffic_prioritized_level == TrafficPrioritizedLevel::FULLY_PRIORITIZED;
10111010
intersection_lanelets.update(is_prioritized, interpolated_path_info, footprint, baselink2front);
@@ -1259,8 +1258,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
12591258
// If there are any vehicles on the attention area when ego entered the intersection on green
12601259
// light, do pseudo collision detection because the vehicles are very slow and no collisions may
12611260
// be detected. check if ego vehicle entered assigned lanelet
1262-
const bool is_green_solid_on =
1263-
isGreenSolidOn(assigned_lanelet, planner_data_->traffic_light_id_map);
1261+
const bool is_green_solid_on = isGreenSolidOn(assigned_lanelet);
12641262
if (is_green_solid_on) {
12651263
if (!initial_green_light_observed_time_) {
12661264
const auto assigned_lane_begin_point = assigned_lanelet.centerline().front();
@@ -1413,12 +1411,11 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
14131411
}
14141412
}
14151413

1416-
TrafficPrioritizedLevel IntersectionModule::getTrafficPrioritizedLevel(
1417-
lanelet::ConstLanelet lane, const std::map<int, TrafficSignalStamped> & tl_infos)
1414+
TrafficPrioritizedLevel IntersectionModule::getTrafficPrioritizedLevel(lanelet::ConstLanelet lane)
14181415
{
14191416
using TrafficSignalElement = autoware_perception_msgs::msg::TrafficSignalElement;
14201417

1421-
std::optional<int> tl_id = std::nullopt;
1418+
std::optional<lanelet::Id> tl_id = std::nullopt;
14221419
for (auto && tl_reg_elem : lane.regulatoryElementsAs<lanelet::TrafficLight>()) {
14231420
tl_id = tl_reg_elem->id();
14241421
break;
@@ -1427,12 +1424,12 @@ TrafficPrioritizedLevel IntersectionModule::getTrafficPrioritizedLevel(
14271424
// this lane has no traffic light
14281425
return TrafficPrioritizedLevel::NOT_PRIORITIZED;
14291426
}
1430-
const auto tl_info_it = tl_infos.find(tl_id.value());
1431-
if (tl_info_it == tl_infos.end()) {
1432-
// the info of this traffic light is not available
1427+
const auto tl_info_opt = planner_data_->getTrafficSignal(
1428+
tl_id.value(), true /* traffic light module keeps last observation*/);
1429+
if (!tl_info_opt) {
14331430
return TrafficPrioritizedLevel::NOT_PRIORITIZED;
14341431
}
1435-
const auto & tl_info = tl_info_it->second;
1432+
const auto & tl_info = tl_info_opt.value();
14361433
bool has_amber_signal{false};
14371434
for (auto && tl_light : tl_info.signal.elements) {
14381435
if (tl_light.color == TrafficSignalElement::AMBER) {

planning/behavior_velocity_intersection_module/src/scene_intersection.hpp

+7-2
Original file line numberDiff line numberDiff line change
@@ -631,8 +631,7 @@ class IntersectionModule : public SceneModuleInterface
631631
* @fn
632632
* @brief find TrafficPrioritizedLevel
633633
*/
634-
TrafficPrioritizedLevel getTrafficPrioritizedLevel(
635-
lanelet::ConstLanelet lane, const std::map<int, TrafficSignalStamped> & tl_infos);
634+
TrafficPrioritizedLevel getTrafficPrioritizedLevel(lanelet::ConstLanelet lane);
636635

637636
/**
638637
* @fn
@@ -738,6 +737,12 @@ class IntersectionModule : public SceneModuleInterface
738737
const std::vector<lanelet::ConstLineString3d> & lane_divisions,
739738
const TargetObjects & target_objects);
740739

740+
/*
741+
* @fn
742+
* @brief check if associated traffic light is green
743+
*/
744+
bool isGreenSolidOn(lanelet::ConstLanelet lane);
745+
741746
/*
742747
bool IntersectionModule::checkFrontVehicleDeceleration(
743748
lanelet::ConstLanelets & ego_lane_with_next_lane, lanelet::ConstLanelet & closest_lanelet,

planning/behavior_velocity_planner/src/node.cpp

+15-1
Original file line numberDiff line numberDiff line change
@@ -327,7 +327,21 @@ void BehaviorVelocityPlannerNode::onTrafficSignals(
327327
TrafficSignalStamped traffic_signal;
328328
traffic_signal.stamp = msg->stamp;
329329
traffic_signal.signal = signal;
330-
planner_data_.traffic_light_id_map[signal.traffic_signal_id] = traffic_signal;
330+
planner_data_.traffic_light_id_map_raw_[signal.traffic_signal_id] = traffic_signal;
331+
const bool is_unknown_observation =
332+
std::any_of(signal.elements.begin(), signal.elements.end(), [](const auto & element) {
333+
return element.color == autoware_perception_msgs::msg::TrafficSignalElement::UNKNOWN;
334+
});
335+
// if the observation is UNKNOWN and past observation is available, only update the timestamp
336+
// and keep the body of the info
337+
if (
338+
is_unknown_observation &&
339+
planner_data_.traffic_light_id_map_last_observed_.count(signal.traffic_signal_id) == 1) {
340+
planner_data_.traffic_light_id_map_last_observed_[signal.traffic_signal_id].stamp =
341+
msg->stamp;
342+
} else {
343+
planner_data_.traffic_light_id_map_last_observed_[signal.traffic_signal_id] = traffic_signal;
344+
}
331345
}
332346
}
333347

planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp

+15-4
Original file line numberDiff line numberDiff line change
@@ -76,7 +76,10 @@ struct PlannerData
7676
double ego_nearest_yaw_threshold;
7777

7878
// other internal data
79-
std::map<int, TrafficSignalStamped> traffic_light_id_map;
79+
// traffic_light_id_map_raw is the raw observation, while traffic_light_id_map_keep_last keeps the
80+
// last observed infomation for UNKNOWN
81+
std::map<lanelet::Id, TrafficSignalStamped> traffic_light_id_map_raw_;
82+
std::map<lanelet::Id, TrafficSignalStamped> traffic_light_id_map_last_observed_;
8083
std::optional<tier4_planning_msgs::msg::VelocityLimit> external_velocity_limit;
8184
tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr virtual_traffic_light_states;
8285

@@ -125,12 +128,20 @@ struct PlannerData
125128
return true;
126129
}
127130

128-
std::shared_ptr<TrafficSignalStamped> getTrafficSignal(const int id) const
131+
/**
132+
*@fn
133+
*@brief queries the traffic signal information of given Id. if keep_last_observation = true,
134+
*recent UNKNOWN observation is overwritten as the last non-UNKNOWN observation
135+
*/
136+
std::optional<TrafficSignalStamped> getTrafficSignal(
137+
const lanelet::Id id, const bool keep_last_observation = false) const
129138
{
139+
const auto & traffic_light_id_map =
140+
keep_last_observation ? traffic_light_id_map_last_observed_ : traffic_light_id_map_raw_;
130141
if (traffic_light_id_map.count(id) == 0) {
131-
return {};
142+
return std::nullopt;
132143
}
133-
return std::make_shared<TrafficSignalStamped>(traffic_light_id_map.at(id));
144+
return std::make_optional<TrafficSignalStamped>(traffic_light_id_map.at(id));
134145
}
135146
};
136147
} // namespace behavior_velocity_planner

planning/behavior_velocity_traffic_light_module/src/scene.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -353,15 +353,15 @@ bool TrafficLightModule::isPassthrough(const double & signed_arc_length) const
353353
bool TrafficLightModule::findValidTrafficSignal(TrafficSignalStamped & valid_traffic_signal) const
354354
{
355355
// get traffic signal associated with the regulatory element id
356-
const auto traffic_signal_stamped = planner_data_->getTrafficSignal(traffic_light_reg_elem_.id());
357-
if (!traffic_signal_stamped) {
356+
const auto traffic_signal_stamped_opt = planner_data_->getTrafficSignal(
357+
traffic_light_reg_elem_.id(), true /* traffic light module keeps last observation */);
358+
if (!traffic_signal_stamped_opt) {
358359
RCLCPP_WARN_THROTTLE(
359360
logger_, *clock_, 5000 /* ms */,
360361
"the traffic signal data associated with regulatory element id is not received");
361362
return false;
362363
}
363-
364-
valid_traffic_signal = *traffic_signal_stamped;
364+
valid_traffic_signal = traffic_signal_stamped_opt.value();
365365
return true;
366366
}
367367

0 commit comments

Comments
 (0)