Skip to content

Commit f8fed79

Browse files
authored
Merge pull request #1675 from tier4/revert/behavior_velocity/unknown-traffic-light
revert(behavior_velocity): revert unknown traffic light handling PR6036
2 parents 2113fae + 8ae20e2 commit f8fed79

File tree

5 files changed

+16
-40
lines changed

5 files changed

+16
-40
lines changed

planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp

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

10351035
for (const auto & traffic_lights_reg_elem : traffic_lights_reg_elems) {
1036-
const auto traffic_signal_stamped_opt =
1036+
const auto traffic_signal_stamped =
10371037
planner_data_->getTrafficSignal(traffic_lights_reg_elem->id());
1038-
if (!traffic_signal_stamped_opt) {
1038+
if (!traffic_signal_stamped) {
10391039
continue;
10401040
}
1041-
const auto traffic_signal_stamped = traffic_signal_stamped_opt.value();
10421041

10431042
if (
10441043
planner_param_.traffic_light_state_timeout <
1045-
(clock_->now() - traffic_signal_stamped.stamp).seconds()) {
1044+
(clock_->now() - traffic_signal_stamped->stamp).seconds()) {
10461045
continue;
10471046
}
10481047

1049-
const auto & lights = traffic_signal_stamped.signal.elements;
1048+
const auto & lights = traffic_signal_stamped->signal.elements;
10501049
if (lights.empty()) {
10511050
continue;
10521051
}

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

+4-6
Original file line numberDiff line numberDiff line change
@@ -1175,13 +1175,12 @@ bool IntersectionModule::isGreenSolidOn() const
11751175
// this lane has no traffic light
11761176
return false;
11771177
}
1178-
const auto tl_info_opt = planner_data_->getTrafficSignal(
1179-
tl_id.value(), true /* traffic light module keeps last observation*/);
1178+
const auto tl_info_opt = planner_data_->getTrafficSignal(tl_id.value());
11801179
if (!tl_info_opt) {
11811180
// the info of this traffic light is not available
11821181
return false;
11831182
}
1184-
const auto & tl_info = tl_info_opt.value();
1183+
const auto & tl_info = *tl_info_opt;
11851184
for (auto && tl_light : tl_info.signal.elements) {
11861185
if (
11871186
tl_light.color == TrafficSignalElement::GREEN &&
@@ -1208,12 +1207,11 @@ IntersectionModule::TrafficPrioritizedLevel IntersectionModule::getTrafficPriori
12081207
// this lane has no traffic light
12091208
return TrafficPrioritizedLevel::NOT_PRIORITIZED;
12101209
}
1211-
const auto tl_info_opt = planner_data_->getTrafficSignal(
1212-
tl_id.value(), true /* traffic light module keeps last observation*/);
1210+
const auto tl_info_opt = planner_data_->getTrafficSignal(tl_id.value());
12131211
if (!tl_info_opt) {
12141212
return TrafficPrioritizedLevel::NOT_PRIORITIZED;
12151213
}
1216-
const auto & tl_info = tl_info_opt.value();
1214+
const auto & tl_info = *tl_info_opt;
12171215
bool has_amber_signal{false};
12181216
for (auto && tl_light : tl_info.signal.elements) {
12191217
if (tl_light.color == TrafficSignalElement::AMBER) {

planning/behavior_velocity_planner/src/node.cpp

+1-15
Original file line numberDiff line numberDiff line change
@@ -334,21 +334,7 @@ void BehaviorVelocityPlannerNode::onTrafficSignals(
334334
TrafficSignalStamped traffic_signal;
335335
traffic_signal.stamp = msg->stamp;
336336
traffic_signal.signal = signal;
337-
planner_data_.traffic_light_id_map_raw_[signal.traffic_signal_id] = traffic_signal;
338-
const bool is_unknown_observation =
339-
std::any_of(signal.elements.begin(), signal.elements.end(), [](const auto & element) {
340-
return element.color == autoware_perception_msgs::msg::TrafficSignalElement::UNKNOWN;
341-
});
342-
// if the observation is UNKNOWN and past observation is available, only update the timestamp
343-
// and keep the body of the info
344-
if (
345-
is_unknown_observation &&
346-
planner_data_.traffic_light_id_map_last_observed_.count(signal.traffic_signal_id) == 1) {
347-
planner_data_.traffic_light_id_map_last_observed_[signal.traffic_signal_id].stamp =
348-
msg->stamp;
349-
} else {
350-
planner_data_.traffic_light_id_map_last_observed_[signal.traffic_signal_id] = traffic_signal;
351-
}
337+
planner_data_.traffic_light_id_map[signal.traffic_signal_id] = traffic_signal;
352338
}
353339
}
354340

planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp

+4-10
Original file line numberDiff line numberDiff line change
@@ -77,10 +77,7 @@ struct PlannerData
7777
double ego_nearest_yaw_threshold;
7878

7979
// other internal data
80-
// traffic_light_id_map_raw is the raw observation, while traffic_light_id_map_keep_last keeps the
81-
// last observed infomation for UNKNOWN
82-
std::map<lanelet::Id, TrafficSignalStamped> traffic_light_id_map_raw_;
83-
std::map<lanelet::Id, TrafficSignalStamped> traffic_light_id_map_last_observed_;
80+
std::map<lanelet::Id, TrafficSignalStamped> traffic_light_id_map;
8481
std::optional<tier4_planning_msgs::msg::VelocityLimit> external_velocity_limit;
8582
std::map<int, TrafficSignalTimeToRedStamped> traffic_light_time_to_red_id_map;
8683
tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr virtual_traffic_light_states;
@@ -139,15 +136,12 @@ struct PlannerData
139136
*@brief queries the traffic signal information of given Id. if keep_last_observation = true,
140137
*recent UNKNOWN observation is overwritten as the last non-UNKNOWN observation
141138
*/
142-
std::optional<TrafficSignalStamped> getTrafficSignal(
143-
const lanelet::Id id, const bool keep_last_observation = false) const
139+
std::shared_ptr<TrafficSignalStamped> getTrafficSignal(const lanelet::Id id) const
144140
{
145-
const auto & traffic_light_id_map =
146-
keep_last_observation ? traffic_light_id_map_last_observed_ : traffic_light_id_map_raw_;
147141
if (traffic_light_id_map.count(id) == 0) {
148-
return std::nullopt;
142+
return {};
149143
}
150-
return std::make_optional<TrafficSignalStamped>(traffic_light_id_map.at(id));
144+
return std::make_shared<TrafficSignalStamped>(traffic_light_id_map.at(id));
151145
}
152146

153147
std::optional<TrafficSignalTimeToRedStamped> getRestTimeToRedSignal(const int id) const

planning/behavior_velocity_traffic_light_module/src/scene.cpp

+3-4
Original file line numberDiff line numberDiff line change
@@ -413,15 +413,14 @@ bool TrafficLightModule::isTrafficSignalStop(
413413
bool TrafficLightModule::findValidTrafficSignal(TrafficSignalStamped & valid_traffic_signal) const
414414
{
415415
// get traffic signal associated with the regulatory element id
416-
const auto traffic_signal_stamped_opt = planner_data_->getTrafficSignal(
417-
traffic_light_reg_elem_.id(), true /* traffic light module keeps last observation */);
418-
if (!traffic_signal_stamped_opt) {
416+
const auto traffic_signal_stamped = planner_data_->getTrafficSignal(traffic_light_reg_elem_.id());
417+
if (!traffic_signal_stamped) {
419418
RCLCPP_WARN_THROTTLE(
420419
logger_, *clock_, 5000 /* ms */,
421420
"the traffic signal data associated with regulatory element id is not received");
422421
return false;
423422
}
424-
valid_traffic_signal = traffic_signal_stamped_opt.value();
423+
valid_traffic_signal = *traffic_signal_stamped;
425424
return true;
426425
}
427426

0 commit comments

Comments
 (0)