Skip to content

Commit 3106795

Browse files
committed
avoid using signal because it is used in std::signal
Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>
1 parent 95fd4dc commit 3106795

File tree

1 file changed

+12
-12
lines changed

1 file changed

+12
-12
lines changed

perception/traffic_light_arbiter/src/signal_match_validator.cpp

+12-12
Original file line numberDiff line numberDiff line change
@@ -35,11 +35,11 @@ std::optional<TrafficSignal> find_signal_by_id(
3535

3636
// Creates a map from signal IDs to TrafficSignal objects.
3737
std::unordered_map<lanelet::Id, TrafficSignal> create_id_signal_map(
38-
const TrafficSignalArray & signals)
38+
const TrafficSignalArray & traffic_signals)
3939
{
4040
std::unordered_map<lanelet::Id, TrafficSignal> id_signal_map;
41-
for (const auto & signal : signals.signals) {
42-
id_signal_map[signal.traffic_signal_id] = signal;
41+
for (const auto & traffic_signal : traffic_signals.signals) {
42+
id_signal_map[traffic_signal.traffic_signal_id] = traffic_signal;
4343
}
4444

4545
return id_signal_map;
@@ -82,11 +82,11 @@ std::vector<Element> create_unknown_elements(
8282
}
8383

8484
// Creates a 'unknown' signal with elements matching the shapes of a given signal's elements
85-
TrafficSignal create_unknown_signal(const TrafficSignal & signal)
85+
TrafficSignal create_unknown_signal(const TrafficSignal & traffic_signal)
8686
{
8787
TrafficSignal unknown_signal;
88-
unknown_signal.traffic_signal_id = signal.traffic_signal_id;
89-
for (const auto & element : signal.elements) {
88+
unknown_signal.traffic_signal_id = traffic_signal.traffic_signal_id;
89+
for (const auto & element : traffic_signal.elements) {
9090
// Confidence is set to a default value as it is not relevant for unknown signals
9191
const auto unknown_element =
9292
create_element(Element::UNKNOWN, element.shape, Element::UNKNOWN, /* confidence */ 1.0);
@@ -139,11 +139,11 @@ std::unordered_set<lanelet::Id> create_signal_id_set(
139139
const std::vector<TrafficSignal> & signals1, const std::vector<TrafficSignal> & signals2)
140140
{
141141
std::unordered_set<lanelet::Id> signal_id_set;
142-
for (const auto & signal : signals1) {
143-
signal_id_set.emplace(signal.traffic_signal_id);
142+
for (const auto & traffic_signal : signals1) {
143+
signal_id_set.emplace(traffic_signal.traffic_signal_id);
144144
}
145-
for (const auto & signal : signals2) {
146-
signal_id_set.emplace(signal.traffic_signal_id);
145+
for (const auto & traffic_signal : signals2) {
146+
signal_id_set.emplace(traffic_signal.traffic_signal_id);
147147
}
148148

149149
return signal_id_set;
@@ -270,8 +270,8 @@ autoware_perception_msgs::msg::TrafficSignalArray SignalMatchValidator::validate
270270
void SignalMatchValidator::setPedestrianSignals(
271271
const std::vector<TrafficLightConstPtr> & pedestrian_signals)
272272
{
273-
for (const auto & signal : pedestrian_signals) {
274-
map_pedestrian_signal_regulatory_elements_set_.emplace(signal->id());
273+
for (const auto & pedestrian_signal : pedestrian_signals) {
274+
map_pedestrian_signal_regulatory_elements_set_.emplace(pedestrian_signal->id());
275275
}
276276
}
277277

0 commit comments

Comments
 (0)