scenario_simulator_v2 C++ API
traffic_light.hpp
Go to the documentation of this file.
1 // Copyright 2015 TIER IV, Inc. All rights reserved.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef TRAFFIC_SIMULATOR__TRAFFIC_LIGHTS__TRAFFIC_LIGHT_HPP_
16 #define TRAFFIC_SIMULATOR__TRAFFIC_LIGHTS__TRAFFIC_LIGHT_HPP_
17 
18 #include <simulation_interface/simulation_api_schema.pb.h>
19 
20 #include <color_names/color_names.hpp>
21 #include <cstdint>
22 #include <geometry_msgs/msg/point.hpp>
23 #include <iostream>
24 #include <limits>
25 #include <memory>
26 #include <optional>
27 #include <regex>
29 #include <set>
30 #include <stdexcept>
32 #include <traffic_simulator_msgs/msg/traffic_light_array_v1.hpp>
33 #include <tuple>
34 #include <type_traits>
35 #include <unordered_map>
36 #include <utility>
37 #include <vector>
38 
39 namespace traffic_simulator
40 {
42 {
43  struct Color
44  {
45  enum Value : std::uint8_t {
48  red,
51  } value;
52 
53  // clang-format off
54  static_assert(static_cast<std::uint8_t>(green ) == 0b0000'0000);
55  static_assert(static_cast<std::uint8_t>(yellow ) == 0b0000'0001);
56  static_assert(static_cast<std::uint8_t>(red ) == 0b0000'0010);
57  static_assert(static_cast<std::uint8_t>(white ) == 0b0000'0011);
58  static_assert(static_cast<std::uint8_t>(unknown) == 0b0000'0100);
59  // clang-format on
60 
61  constexpr Color(const Value value = green) : value(value) {}
62 
63  Color(const std::string & name) : value(make(name)) {}
64 
65  static inline const std::unordered_map<std::string, Value> table{
66  std::make_pair("amber", yellow),
67  std::make_pair("green", green),
68  std::make_pair("red", red),
69  std::make_pair("white", white),
70  std::make_pair("yellow", yellow),
71  std::make_pair("unknown", unknown),
72 
73  // BACKWARD COMPATIBILITY
74  std::make_pair("Green", green),
75  std::make_pair("Red", red),
76  std::make_pair("Yellow", yellow),
77  };
78 
79  static auto make(const std::string & name) -> Color;
80 
81  constexpr auto is(const Color given) const { return value == given; }
82 
83  constexpr operator Value() const noexcept { return value; }
84 
85  friend auto operator>>(std::istream & is, Color & color) -> std::istream &;
86 
87  friend auto operator<<(std::ostream & os, const Color & color) -> std::ostream &;
88  };
89 
90  struct Status
91  {
92  enum Value : std::uint8_t {
97  } value;
98 
99  // clang-format off
100  static_assert(static_cast<std::uint8_t>(solid_on ) == 0b0000'0000);
101  static_assert(static_cast<std::uint8_t>(solid_off) == 0b0000'0001);
102  static_assert(static_cast<std::uint8_t>(flashing ) == 0b0000'0010);
103  static_assert(static_cast<std::uint8_t>(unknown ) == 0b0000'0011);
104  // clang-format on
105 
106  constexpr Status(const Value value = solid_on) : value(value) {}
107 
108  Status(const std::string & name) : value(make(name)) {}
109 
110  static inline const std::unordered_map<std::string, Value> table{
111  std::make_pair("solidOn", solid_on),
112  std::make_pair("solidOff", solid_off),
113  std::make_pair("flashing", flashing),
114  std::make_pair("unknown", unknown),
115 
116  // BACKWARD COMPATIBILITY
117  std::make_pair("Blank", solid_off),
118  std::make_pair("none", solid_off),
119  };
120 
121  static auto make(const std::string & name) -> Status;
122 
123  constexpr auto is(const Value given) const { return value == given; }
124 
125  constexpr operator bool() const { return value == solid_on or value == flashing; }
126 
127  constexpr operator Value() const noexcept { return value; }
128 
129  friend auto operator>>(std::istream & is, Status & status) -> std::istream &;
130 
131  friend auto operator<<(std::ostream & os, const Status & status) -> std::ostream &;
132  };
133 
134  struct Shape
135  {
136  enum class Category : std::uint8_t {
137  circle,
138  cross,
139  arrow,
140  unknown,
141  };
142 
143  // clang-format off
144  static_assert(static_cast<std::uint8_t>(Category::circle ) == 0b0000'0000);
145  static_assert(static_cast<std::uint8_t>(Category::cross ) == 0b0000'0001);
146  static_assert(static_cast<std::uint8_t>(Category::arrow ) == 0b0000'0010);
147  static_assert(static_cast<std::uint8_t>(Category::unknown) == 0b0000'0011);
148  // clang-format on
149 
150  enum Value : std::uint16_t {
151  // clang-format off
152  circle = static_cast<std::uint8_t>(Category::circle ),
153  cross = static_cast<std::uint8_t>(Category::cross ),
154  left = (0b0000'1000 << 8) | static_cast<std::uint8_t>(Category::arrow ),
155  down = (0b0000'0100 << 8) | static_cast<std::uint8_t>(Category::arrow ),
156  up = (0b0000'0010 << 8) | static_cast<std::uint8_t>(Category::arrow ),
157  right = (0b0000'0001 << 8) | static_cast<std::uint8_t>(Category::arrow ),
158  lower_left = (0b0000'1100 << 8) | static_cast<std::uint8_t>(Category::arrow ),
159  upper_left = (0b0000'1010 << 8) | static_cast<std::uint8_t>(Category::arrow ),
160  lower_right = (0b0000'0101 << 8) | static_cast<std::uint8_t>(Category::arrow ),
161  upper_right = (0b0000'0011 << 8) | static_cast<std::uint8_t>(Category::arrow ),
162  unknown = static_cast<std::uint8_t>(Category::unknown),
163  // clang-format on
164  } value;
165 
166  // clang-format off
167  static_assert(static_cast<std::uint16_t>(circle ) == 0b0000'0000'0000'0000);
168  static_assert(static_cast<std::uint16_t>(cross ) == 0b0000'0000'0000'0001);
169  static_assert(static_cast<std::uint16_t>(left ) == 0b0000'1000'0000'0010);
170  static_assert(static_cast<std::uint16_t>(down ) == 0b0000'0100'0000'0010);
171  static_assert(static_cast<std::uint16_t>(up ) == 0b0000'0010'0000'0010);
172  static_assert(static_cast<std::uint16_t>(right ) == 0b0000'0001'0000'0010);
173  static_assert(static_cast<std::uint16_t>(lower_left ) == 0b0000'1100'0000'0010);
174  static_assert(static_cast<std::uint16_t>(upper_left ) == 0b0000'1010'0000'0010);
175  static_assert(static_cast<std::uint16_t>(lower_right) == 0b0000'0101'0000'0010);
176  static_assert(static_cast<std::uint16_t>(upper_right) == 0b0000'0011'0000'0010);
177  static_assert(static_cast<std::uint16_t>(unknown ) == 0b0000'0000'0000'0011);
178  // clang-format on
179 
180  constexpr Shape(const Value value = circle) : value(value) {}
181 
182  Shape(const std::string & name) : value(make(name)) {}
183 
184  static inline const std::unordered_map<std::string, Shape::Value> table{
185  std::make_pair("circle", Shape::circle),
186  std::make_pair("cross", Shape::cross),
187  std::make_pair("left", Shape::left),
188  std::make_pair("down", Shape::down),
189  std::make_pair("up", Shape::up),
190  std::make_pair("right", Shape::right),
191  std::make_pair("lowerLeft", Shape::lower_left),
192  std::make_pair("upperLeft", Shape::upper_left),
193  std::make_pair("lowerRight", Shape::lower_right),
194  std::make_pair("upperRight", Shape::upper_right),
195  std::make_pair("unknown", Shape::unknown),
196 
197  // BACKWARD COMPATIBILITY
198  std::make_pair("straight", Shape::up),
199  };
200 
201  static auto make(const std::string & name) -> Shape;
202 
203  constexpr auto category() const
204  {
205  return static_cast<Category>(static_cast<std::uint16_t>(value) & 0b1111'1111);
206  }
207 
208  constexpr auto is(const Value given) const { return value == given; }
209 
210  constexpr auto is(const Category given) const { return category() == given; }
211 
212  constexpr operator Value() const noexcept { return value; }
213 
214  friend auto operator>>(std::istream & is, Shape & shape) -> std::istream &;
215 
216  friend auto operator<<(std::ostream & os, const Shape & shape) -> std::ostream &;
217  };
218 
219  struct Bulb
220  {
221  using Value = std::tuple<Color, Status, Shape>;
222 
223  const Value value;
224 
225  using Hash = std::uint32_t; // (Color::Value << 8 + 16) | (Status::Value << 16) | Shape::Value
226 
227  constexpr Bulb(const Value value) : value(value) {}
228 
229  constexpr Bulb(const Color color = {}, const Status status = {}, const Shape shape = {})
230  : Bulb(std::forward_as_tuple(color, status, shape))
231  {
232  }
233 
234  Bulb(const std::string & name) : Bulb(make(name)) {}
235 
236  auto make(const std::string & s) -> Value;
237 
238  constexpr auto is(const Color color) const { return std::get<Color>(value).is(color); }
239 
240  constexpr auto is(const Status status) const { return std::get<Status>(value).is(status); }
241 
242  constexpr auto is(const Shape shape) const { return std::get<Shape>(value).is(shape); }
243 
244  constexpr auto is(const Shape::Category category) const
245  {
246  return std::get<Shape>(value).is(category);
247  }
248 
249  constexpr auto hash() const -> Hash
250  {
251  return (static_cast<Hash>(std::get<Color>(value).value) << 24) |
252  (static_cast<Hash>(std::get<Status>(value).value) << 16) |
253  static_cast<Hash>(std::get<Shape>(value).value);
254  }
255 
256  friend constexpr auto operator<(const Bulb & lhs, const Bulb & rhs) -> bool
257  {
258  return lhs.hash() < rhs.hash();
259  }
260 
261  friend auto operator<<(std::ostream & os, const Bulb & bulb) -> std::ostream &;
262 
263  explicit operator simulation_api_schema::TrafficLight() const
264  {
265  const auto color = [this]() {
266  auto color_message = simulation_api_schema::TrafficLight_Color_UNKNOWN_COLOR;
267  switch (std::get<Color>(value).value) {
268  case Color::green:
269  color_message = simulation_api_schema::TrafficLight_Color_GREEN;
270  break;
271  case Color::yellow:
272  color_message = simulation_api_schema::TrafficLight_Color_AMBER;
273  break;
274  case Color::red:
275  color_message = simulation_api_schema::TrafficLight_Color_RED;
276  break;
277  case Color::white:
278  color_message = simulation_api_schema::TrafficLight_Color_WHITE;
279  break;
280  case Color::unknown:
281  color_message = simulation_api_schema::TrafficLight_Color_UNKNOWN_COLOR;
282  break;
283  }
284  return color_message;
285  };
286 
287  const auto status = [this]() {
288  auto status_message = simulation_api_schema::TrafficLight_Status_UNKNOWN_STATUS;
289  switch (std::get<Status>(value).value) {
290  case Status::solid_on:
291  status_message = simulation_api_schema::TrafficLight_Status_SOLID_ON;
292  break;
293  case Status::solid_off:
294  status_message = simulation_api_schema::TrafficLight_Status_SOLID_OFF;
295  break;
296  case Status::flashing:
297  status_message = simulation_api_schema::TrafficLight_Status_FLASHING;
298  break;
299  case Status::unknown:
300  status_message = simulation_api_schema::TrafficLight_Status_UNKNOWN_STATUS;
301  break;
302  }
303  return status_message;
304  };
305 
306  const auto shape = [this]() {
307  auto shape_message = simulation_api_schema::TrafficLight_Shape_UNKNOWN_SHAPE;
308  switch (std::get<Shape>(value).value) {
309  case Shape::circle:
310  shape_message = simulation_api_schema::TrafficLight_Shape_CIRCLE;
311  break;
312  case Shape::cross:
313  shape_message = simulation_api_schema::TrafficLight_Shape_CROSS;
314  break;
315  case Shape::left:
316  shape_message = simulation_api_schema::TrafficLight_Shape_LEFT_ARROW;
317  break;
318  case Shape::down:
319  shape_message = simulation_api_schema::TrafficLight_Shape_DOWN_ARROW;
320  break;
321  case Shape::up:
322  shape_message = simulation_api_schema::TrafficLight_Shape_UP_ARROW;
323  break;
324  case Shape::right:
325  shape_message = simulation_api_schema::TrafficLight_Shape_RIGHT_ARROW;
326  break;
327  case Shape::lower_left:
328  shape_message = simulation_api_schema::TrafficLight_Shape_DOWN_LEFT_ARROW;
329  break;
330  case Shape::lower_right:
331  shape_message = simulation_api_schema::TrafficLight_Shape_DOWN_RIGHT_ARROW;
332  break;
333  case Shape::upper_left:
334  shape_message = simulation_api_schema::TrafficLight_Shape_UP_LEFT_ARROW;
335  break;
336  case Shape::upper_right:
337  shape_message = simulation_api_schema::TrafficLight_Shape_UP_RIGHT_ARROW;
338  break;
339  case Shape::unknown:
340  shape_message = simulation_api_schema::TrafficLight_Shape_UNKNOWN_SHAPE;
341  break;
342  }
343  return shape_message;
344  };
345 
346  simulation_api_schema::TrafficLight traffic_light_bulb_proto;
347  traffic_light_bulb_proto.set_status(status());
348  traffic_light_bulb_proto.set_shape(shape());
349  traffic_light_bulb_proto.set_color(color());
350  // NOTE: confidence will be overwritten in TrafficLight::operator simulation_api_schema::TrafficSignal()
351  traffic_light_bulb_proto.set_confidence(1.0);
352 
353  return traffic_light_bulb_proto;
354  }
355 
356  explicit operator traffic_simulator_msgs::msg::TrafficLightBulbV1() const
357  {
358  const auto color = [this] {
359  auto color_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::UNKNOWN;
360  switch (std::get<Color>(value).value) {
361  case Color::green:
362  color_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::GREEN;
363  break;
364  case Color::yellow:
365  color_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::AMBER;
366  break;
367  case Color::red:
368  color_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::RED;
369  break;
370  case Color::white:
371  color_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::WHITE;
372  break;
373  case Color::unknown:
374  color_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::UNKNOWN;
375  break;
376  }
377  return color_message;
378  };
379 
380  const auto status = [this] {
381  auto status_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::UNKNOWN;
382  switch (std::get<Status>(value).value) {
383  case Status::solid_on:
384  status_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::SOLID_ON;
385  break;
386  case Status::solid_off:
387  status_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::SOLID_OFF;
388  break;
389  case Status::flashing:
390  status_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::FLASHING;
391  break;
392  case Status::unknown:
393  status_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::UNKNOWN;
394  break;
395  }
396  return status_message;
397  };
398 
399  const auto shape = [this] {
400  auto shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::UNKNOWN;
401  switch (std::get<Shape>(value).value) {
402  case Shape::circle:
403  shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::CIRCLE;
404  break;
405  case Shape::cross:
406  shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::CROSS;
407  break;
408  case Shape::left:
409  shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::LEFT_ARROW;
410  break;
411  case Shape::down:
412  shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::DOWN_ARROW;
413  break;
414  case Shape::up:
415  shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::UP_ARROW;
416  break;
417  case Shape::right:
418  shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::RIGHT_ARROW;
419  break;
420  case Shape::lower_left:
421  shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::DOWN_LEFT_ARROW;
422  break;
423  case Shape::lower_right:
424  shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::DOWN_RIGHT_ARROW;
425  break;
426  case Shape::upper_left:
427  shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::UP_LEFT_ARROW;
428  break;
429  case Shape::upper_right:
430  shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::UP_RIGHT_ARROW;
431  break;
432  case Shape::unknown:
433  shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::UNKNOWN;
434  break;
435  }
436  return shape_message;
437  };
438 
439  traffic_simulator_msgs::msg::TrafficLightBulbV1 msg;
440  msg.color = color();
441  msg.status = status();
442  msg.shape = shape();
443  // NOTE: confidence will be overwritten
444  msg.confidence = 1.0;
445  // NOTE: unused data member 'enum_revision' for
446  // traffic_simulator_msgs::msg::TrafficLightBulbV1
447  return msg;
448  }
449  };
450 
451  explicit TrafficLight(const lanelet::Id, const hdmap_utils::HdMapUtils &);
452 
453  const lanelet::Id way_id;
454 
455  const lanelet::Ids regulatory_elements_ids;
456 
457  double confidence = 1.0;
458 
459  std::set<Bulb> bulbs;
460 
461  const std::map<Color, std::optional<geometry_msgs::msg::Point>> positions;
462 
463  auto clear() { bulbs.clear(); }
464 
465  auto contains(const Bulb & bulb) const { return bulbs.find(bulb) != std::end(bulbs); }
466 
467  auto contains(const Color & color, const Status & status, const Shape & shape) const
468  {
469  return contains(Bulb(color, status, shape));
470  }
471 
472  auto contains(const std::string & name) const { return contains(Bulb(name)); }
473 
474  template <typename Markers, typename Now>
475  auto draw(Markers & markers, const Now & now, const std::string & frame_id) const
476  {
477  auto create_bulb_marker = [&](const Color & color, const bool is_on) {
478  visualization_msgs::msg::Marker marker;
479  marker.header.stamp = now;
480  marker.header.frame_id = frame_id;
481  marker.action = visualization_msgs::msg::Marker::ADD;
482  marker.ns = "bulb";
483  marker.id = way_id << 2 | static_cast<int>(color.value);
484  marker.type = visualization_msgs::msg::Marker::SPHERE;
485  marker.pose.position = positions.at(color).value();
486  marker.pose.orientation = geometry_msgs::msg::Quaternion();
487  marker.scale.x = 0.3;
488  marker.scale.y = 0.3;
489  marker.scale.z = 0.3;
490  marker.color = color_names::makeColorMsg(boost::lexical_cast<std::string>(color));
491  marker.color.a = is_on ? 1.0 : 0.3;
492  return marker;
493  };
494 
495  std::set<Color> added_colors;
496 
497  // Place on markers for actual bulbs
498  for (const auto & bulb : bulbs) {
499  // NOTE: Status is ignored intentionally
500  if (bulb.is(Shape::Category::circle)) {
501  const auto color = std::get<Color>(bulb.value);
502  const auto position = positions.find(color);
503  if (position == positions.end() or not position->second.has_value()) {
504  continue;
505  }
506 
507  markers.push_back(create_bulb_marker(color, true));
508  added_colors.insert(color);
509  }
510  }
511 
512  // Place solidOff markers for other positions
513  for (const auto & [color, position] : positions) {
514  if (position.has_value() and added_colors.find(color) == added_colors.end()) {
515  markers.push_back(create_bulb_marker(color, false));
516  }
517  }
518  }
519 
520  template <typename... Ts>
521  auto emplace(Ts &&... xs)
522  {
523  bulbs.emplace(std::forward<decltype(xs)>(xs)...);
524  }
525 
526  auto empty() const { return bulbs.empty(); }
527 
528  auto set(const std::string & states) -> void;
529 
530  friend auto operator<<(std::ostream & os, const TrafficLight & traffic_light) -> std::ostream &;
531 
532  explicit operator simulation_api_schema::TrafficSignal() const
533  {
534  simulation_api_schema::TrafficSignal traffic_signal_proto;
535 
536  traffic_signal_proto.set_id(way_id);
537  for (const auto & bulb : bulbs) {
538  auto traffic_light_bulb_proto = static_cast<simulation_api_schema::TrafficLight>(bulb);
539  traffic_light_bulb_proto.set_confidence(confidence);
540  *traffic_signal_proto.add_traffic_light_status() = traffic_light_bulb_proto;
541  }
542  return traffic_signal_proto;
543  }
544 
545  explicit operator traffic_simulator_msgs::msg::TrafficLightV1() const
546  {
547  traffic_simulator_msgs::msg::TrafficLightV1 traffic_signal;
548  traffic_signal.lanelet_way_id = way_id;
549  for (const auto & bulb : bulbs) {
550  auto traffic_light_bulb = static_cast<traffic_simulator_msgs::msg::TrafficLightBulbV1>(bulb);
551  traffic_light_bulb.confidence = confidence;
552  traffic_signal.traffic_light_bulbs.push_back(traffic_light_bulb);
553  }
554  return traffic_signal;
555  }
556 };
557 } // namespace traffic_simulator
558 
559 #endif // TRAFFIC_SIMULATOR__TRAFFIC_LIGHTS__TRAFFIC_LIGHT_HPP_
Definition: hdmap_utils.hpp:64
Definition: api.hpp:32
Definition: junit5.hpp:25
std::string string
Definition: junit5.hpp:26
Definition: traffic_light.hpp:220
constexpr auto is(const Shape shape) const
Definition: traffic_light.hpp:242
std::tuple< Color, Status, Shape > Value
Definition: traffic_light.hpp:221
constexpr auto hash() const -> Hash
Definition: traffic_light.hpp:249
constexpr Bulb(const Value value)
Definition: traffic_light.hpp:227
constexpr Bulb(const Color color={}, const Status status={}, const Shape shape={})
Definition: traffic_light.hpp:229
Bulb(const std::string &name)
Definition: traffic_light.hpp:234
constexpr friend auto operator<(const Bulb &lhs, const Bulb &rhs) -> bool
Definition: traffic_light.hpp:256
constexpr auto is(const Color color) const
Definition: traffic_light.hpp:238
friend auto operator<<(std::ostream &os, const Bulb &bulb) -> std::ostream &
Definition: traffic_light.cpp:160
auto make(const std::string &s) -> Value
Definition: traffic_light.cpp:134
constexpr auto is(const Shape::Category category) const
Definition: traffic_light.hpp:244
const Value value
Definition: traffic_light.hpp:223
std::uint32_t Hash
Definition: traffic_light.hpp:225
constexpr auto is(const Status status) const
Definition: traffic_light.hpp:240
Definition: traffic_light.hpp:44
Value
Definition: traffic_light.hpp:45
@ white
Definition: traffic_light.hpp:49
@ green
Definition: traffic_light.hpp:46
@ red
Definition: traffic_light.hpp:48
@ unknown
Definition: traffic_light.hpp:50
@ yellow
Definition: traffic_light.hpp:47
friend auto operator<<(std::ostream &os, const Color &color) -> std::ostream &
Definition: traffic_light.cpp:37
constexpr Color(const Value value=green)
Definition: traffic_light.hpp:61
Color(const std::string &name)
Definition: traffic_light.hpp:63
static const std::unordered_map< std::string, Value > table
Definition: traffic_light.hpp:65
enum traffic_simulator::TrafficLight::Color::Value value
friend auto operator>>(std::istream &is, Color &color) -> std::istream &
Definition: traffic_light.cpp:29
static auto make(const std::string &name) -> Color
Definition: traffic_light.cpp:20
constexpr auto is(const Color given) const
Definition: traffic_light.hpp:81
Definition: traffic_light.hpp:135
Value
Definition: traffic_light.hpp:150
@ up
Definition: traffic_light.hpp:156
@ upper_right
Definition: traffic_light.hpp:161
@ left
Definition: traffic_light.hpp:154
@ cross
Definition: traffic_light.hpp:153
@ lower_right
Definition: traffic_light.hpp:160
@ upper_left
Definition: traffic_light.hpp:159
@ lower_left
Definition: traffic_light.hpp:158
@ down
Definition: traffic_light.hpp:155
@ unknown
Definition: traffic_light.hpp:162
@ circle
Definition: traffic_light.hpp:152
@ right
Definition: traffic_light.hpp:157
constexpr auto category() const
Definition: traffic_light.hpp:203
enum traffic_simulator::TrafficLight::Shape::Value value
static auto make(const std::string &name) -> Shape
Definition: traffic_light.cpp:87
constexpr auto is(const Category given) const
Definition: traffic_light.hpp:210
friend auto operator>>(std::istream &is, Shape &shape) -> std::istream &
Definition: traffic_light.cpp:96
Category
Definition: traffic_light.hpp:136
friend auto operator<<(std::ostream &os, const Shape &shape) -> std::ostream &
Definition: traffic_light.cpp:104
constexpr auto is(const Value given) const
Definition: traffic_light.hpp:208
constexpr Shape(const Value value=circle)
Definition: traffic_light.hpp:180
static const std::unordered_map< std::string, Shape::Value > table
Definition: traffic_light.hpp:184
Shape(const std::string &name)
Definition: traffic_light.hpp:182
Definition: traffic_light.hpp:91
constexpr auto is(const Value given) const
Definition: traffic_light.hpp:123
constexpr Status(const Value value=solid_on)
Definition: traffic_light.hpp:106
static const std::unordered_map< std::string, Value > table
Definition: traffic_light.hpp:110
Status(const std::string &name)
Definition: traffic_light.hpp:108
Value
Definition: traffic_light.hpp:92
@ solid_off
Definition: traffic_light.hpp:94
@ unknown
Definition: traffic_light.hpp:96
@ solid_on
Definition: traffic_light.hpp:93
@ flashing
Definition: traffic_light.hpp:95
friend auto operator<<(std::ostream &os, const Status &status) -> std::ostream &
Definition: traffic_light.cpp:72
enum traffic_simulator::TrafficLight::Status::Value value
static auto make(const std::string &name) -> Status
Definition: traffic_light.cpp:55
friend auto operator>>(std::istream &is, Status &status) -> std::istream &
Definition: traffic_light.cpp:64
Definition: traffic_light.hpp:42
auto clear()
Definition: traffic_light.hpp:463
const lanelet::Ids regulatory_elements_ids
Definition: traffic_light.hpp:455
double confidence
Definition: traffic_light.hpp:457
const lanelet::Id way_id
Definition: traffic_light.hpp:453
TrafficLight(const lanelet::Id, const hdmap_utils::HdMapUtils &)
Definition: traffic_light.cpp:167
auto empty() const
Definition: traffic_light.hpp:526
const std::map< Color, std::optional< geometry_msgs::msg::Point > > positions
Definition: traffic_light.hpp:461
auto contains(const Color &color, const Status &status, const Shape &shape) const
Definition: traffic_light.hpp:467
std::set< Bulb > bulbs
Definition: traffic_light.hpp:459
auto set(const std::string &states) -> void
Definition: traffic_light.cpp:195
auto contains(const std::string &name) const
Definition: traffic_light.hpp:472
auto draw(Markers &markers, const Now &now, const std::string &frame_id) const
Definition: traffic_light.hpp:475
friend auto operator<<(std::ostream &os, const TrafficLight &traffic_light) -> std::ostream &
Definition: traffic_light.cpp:213
auto contains(const Bulb &bulb) const
Definition: traffic_light.hpp:465
auto emplace(Ts &&... xs)
Definition: traffic_light.hpp:521
traffic_simulator::TrafficLight TrafficLight
Definition: test_traffic_light.cpp:24
TrafficLight::Bulb Bulb
Definition: test_traffic_light.cpp:28