Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(traffic_light_arbiter): publish traffic light info even when a map without traffic lights is subscribed #4428

Merged
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@

#include <lanelet2_core/Forward.h>

#include <memory>
#include <unordered_set>

class TrafficLightArbiter : public rclcpp::Node
Expand All @@ -45,7 +46,7 @@ class TrafficLightArbiter : public rclcpp::Node
void onExternalMsg(const TrafficSignalArray::ConstSharedPtr msg);
void arbitrateAndPublish(const builtin_interfaces::msg::Time & stamp);

std::unordered_set<lanelet::Id> map_regulatory_elements_set_;
std::shared_ptr<std::unordered_set<lanelet::Id>> map_regulatory_elements_set_;
tkimura4 marked this conversation as resolved.
Show resolved Hide resolved

double external_time_tolerance_;
double perception_time_tolerance_;
Expand Down
19 changes: 13 additions & 6 deletions perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,9 +72,10 @@ void TrafficLightArbiter::onMap(const LaneletMapBin::ConstSharedPtr msg)
lanelet::utils::conversion::fromBinMsg(*msg, map);

const auto signals = lanelet::filter_traffic_signals(map);
map_regulatory_elements_set_.clear();
map_regulatory_elements_set_ = std::make_shared<std::unordered_set<lanelet::Id>>();
tkimura4 marked this conversation as resolved.
Show resolved Hide resolved

for (const auto & signal : signals) {
map_regulatory_elements_set_.emplace(signal->id());
map_regulatory_elements_set_->emplace(signal->id());
}
}

Expand Down Expand Up @@ -109,14 +110,22 @@ void TrafficLightArbiter::arbitrateAndPublish(const builtin_interfaces::msg::Tim
using ElementAndPriority = std::pair<Element, bool>;
std::unordered_map<lanelet::Id, std::vector<ElementAndPriority>> regulatory_element_signals_map;

if (map_regulatory_elements_set_.empty()) {
if (map_regulatory_elements_set_ == nullptr) {
RCLCPP_WARN(get_logger(), "Received traffic signal messages before a map");
return;
}

TrafficSignalArray output_signals_msg;
output_signals_msg.stamp = stamp;

if (map_regulatory_elements_set_->empty()) {
pub_->publish(output_signals_msg);
return;
}

auto add_signal_function = [&](const auto & signal, bool priority) {
const auto id = signal.traffic_signal_id;
if (!map_regulatory_elements_set_.count(id)) {
if (!map_regulatory_elements_set_->count(id)) {
RCLCPP_WARN(
get_logger(), "Received a traffic signal not present in the current map (%lu)", id);
return;
Expand Down Expand Up @@ -165,8 +174,6 @@ void TrafficLightArbiter::arbitrateAndPublish(const builtin_interfaces::msg::Tim
return highest_score_elements_vector;
};

TrafficSignalArray output_signals_msg;
output_signals_msg.stamp = stamp;
output_signals_msg.signals.reserve(regulatory_element_signals_map.size());

for (const auto & [regulatory_element_id, elements] : regulatory_element_signals_map) {
Expand Down