15 #ifndef TRAFFIC_SIMULATOR__TRAFFIC_LIGHTS__TRAFFIC_LIGHT_HPP_
16 #define TRAFFIC_SIMULATOR__TRAFFIC_LIGHTS__TRAFFIC_LIGHT_HPP_
18 #include <simulation_interface/simulation_api_schema.pb.h>
20 #include <color_names/color_names.hpp>
22 #include <geometry_msgs/msg/point.hpp>
32 #include <traffic_simulator_msgs/msg/traffic_light_array_v1.hpp>
34 #include <type_traits>
35 #include <unordered_map>
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);
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),
74 std::make_pair(
"Green",
green),
75 std::make_pair(
"Red",
red),
76 std::make_pair(
"Yellow",
yellow),
81 constexpr
auto is(
const Color given)
const {
return value == given; }
83 constexpr
operator Value() const noexcept {
return value; }
87 friend auto operator<<(std::ostream & os,
const Color & color) -> std::ostream &;
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);
110 static inline const std::unordered_map<std::string, Value>
table{
111 std::make_pair(
"solidOn",
solid_on),
113 std::make_pair(
"flashing",
flashing),
114 std::make_pair(
"unknown",
unknown),
131 friend auto operator<<(std::ostream & os,
const Status & status) -> std::ostream &;
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);
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),
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);
184 static inline const std::unordered_map<std::string, Shape::Value>
table{
205 return static_cast<Category>(
static_cast<std::uint16_t
>(
value) & 0b1111'1111);
216 friend auto operator<<(std::ostream & os,
const Shape & shape) -> std::ostream &;
221 using Value = std::tuple<Color, Status, Shape>;
230 :
Bulb(std::forward_as_tuple(color, status, shape))
238 constexpr
auto is(
const Color color)
const {
return std::get<Color>(
value).is(color); }
240 constexpr
auto is(
const Status status)
const {
return std::get<Status>(
value).is(status); }
242 constexpr
auto is(
const Shape shape)
const {
return std::get<Shape>(
value).is(shape); }
246 return std::get<Shape>(
value).is(category);
252 (
static_cast<Hash>(std::get<Status>(
value).value) << 16) |
253 static_cast<Hash>(std::get<Shape>(
value).value);
258 return lhs.hash() < rhs.hash();
261 friend auto operator<<(std::ostream & os,
const Bulb & bulb) -> std::ostream &;
265 const auto color = [
this]() {
266 auto color_message = simulation_api_schema::TrafficLight_Color_UNKNOWN_COLOR;
267 switch (std::get<Color>(
value).value) {
269 color_message = simulation_api_schema::TrafficLight_Color_GREEN;
272 color_message = simulation_api_schema::TrafficLight_Color_AMBER;
275 color_message = simulation_api_schema::TrafficLight_Color_RED;
278 color_message = simulation_api_schema::TrafficLight_Color_WHITE;
281 color_message = simulation_api_schema::TrafficLight_Color_UNKNOWN_COLOR;
284 return color_message;
287 const auto status = [
this]() {
288 auto status_message = simulation_api_schema::TrafficLight_Status_UNKNOWN_STATUS;
289 switch (std::get<Status>(
value).value) {
291 status_message = simulation_api_schema::TrafficLight_Status_SOLID_ON;
294 status_message = simulation_api_schema::TrafficLight_Status_SOLID_OFF;
297 status_message = simulation_api_schema::TrafficLight_Status_FLASHING;
300 status_message = simulation_api_schema::TrafficLight_Status_UNKNOWN_STATUS;
303 return status_message;
306 const auto shape = [
this]() {
307 auto shape_message = simulation_api_schema::TrafficLight_Shape_UNKNOWN_SHAPE;
308 switch (std::get<Shape>(
value).value) {
310 shape_message = simulation_api_schema::TrafficLight_Shape_CIRCLE;
313 shape_message = simulation_api_schema::TrafficLight_Shape_CROSS;
316 shape_message = simulation_api_schema::TrafficLight_Shape_LEFT_ARROW;
319 shape_message = simulation_api_schema::TrafficLight_Shape_DOWN_ARROW;
322 shape_message = simulation_api_schema::TrafficLight_Shape_UP_ARROW;
325 shape_message = simulation_api_schema::TrafficLight_Shape_RIGHT_ARROW;
328 shape_message = simulation_api_schema::TrafficLight_Shape_DOWN_LEFT_ARROW;
331 shape_message = simulation_api_schema::TrafficLight_Shape_DOWN_RIGHT_ARROW;
334 shape_message = simulation_api_schema::TrafficLight_Shape_UP_LEFT_ARROW;
337 shape_message = simulation_api_schema::TrafficLight_Shape_UP_RIGHT_ARROW;
340 shape_message = simulation_api_schema::TrafficLight_Shape_UNKNOWN_SHAPE;
343 return shape_message;
347 traffic_light_bulb_proto.set_status(status());
348 traffic_light_bulb_proto.set_shape(shape());
349 traffic_light_bulb_proto.set_color(color());
351 traffic_light_bulb_proto.set_confidence(1.0);
353 return traffic_light_bulb_proto;
356 explicit operator traffic_simulator_msgs::msg::TrafficLightBulbV1()
const
358 const auto color = [
this] {
359 auto color_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::UNKNOWN;
362 color_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::GREEN;
365 color_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::AMBER;
368 color_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::RED;
371 color_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::WHITE;
374 color_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::UNKNOWN;
377 return color_message;
380 const auto status = [
this] {
381 auto status_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::UNKNOWN;
384 status_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::SOLID_ON;
387 status_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::SOLID_OFF;
390 status_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::FLASHING;
393 status_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::UNKNOWN;
396 return status_message;
399 const auto shape = [
this] {
400 auto shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::UNKNOWN;
403 shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::CIRCLE;
406 shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::CROSS;
409 shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::LEFT_ARROW;
412 shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::DOWN_ARROW;
415 shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::UP_ARROW;
418 shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::RIGHT_ARROW;
421 shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::DOWN_LEFT_ARROW;
424 shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::DOWN_RIGHT_ARROW;
427 shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::UP_LEFT_ARROW;
430 shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::UP_RIGHT_ARROW;
433 shape_message = traffic_simulator_msgs::msg::TrafficLightBulbV1::UNKNOWN;
436 return shape_message;
439 traffic_simulator_msgs::msg::TrafficLightBulbV1 msg;
441 msg.status = status();
444 msg.confidence = 1.0;
461 const std::map<Color, std::optional<geometry_msgs::msg::Point>>
positions;
474 template <
typename Markers,
typename Now>
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;
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;
495 std::set<Color> added_colors;
498 for (
const auto & bulb :
bulbs) {
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()) {
507 markers.push_back(create_bulb_marker(color,
true));
508 added_colors.insert(color);
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));
520 template <
typename... Ts>
523 bulbs.emplace(std::forward<decltype(
xs)>(
xs)...);
532 explicit operator simulation_api_schema::TrafficSignal()
const
534 simulation_api_schema::TrafficSignal traffic_signal_proto;
536 traffic_signal_proto.set_id(
way_id);
537 for (
const auto & bulb :
bulbs) {
539 traffic_light_bulb_proto.set_confidence(
confidence);
540 *traffic_signal_proto.add_traffic_light_status() = traffic_light_bulb_proto;
542 return traffic_signal_proto;
545 explicit operator traffic_simulator_msgs::msg::TrafficLightV1()
const
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);
552 traffic_signal.traffic_light_bulbs.push_back(traffic_light_bulb);
554 return traffic_signal;
Definition: hdmap_utils.hpp:64
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