scenario_simulator_v2 C++ API
traffic_lights_base.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_LIGHTS_BASE_HPP_
16 #define TRAFFIC_SIMULATOR__TRAFFIC_LIGHTS__TRAFFIC_LIGHTS_BASE_HPP_
17 
18 #include <simulation_interface/simulation_api_schema.pb.h>
19 
20 #include <functional>
22 #include <memory>
23 #include <rclcpp/rclcpp.hpp>
24 #include <string>
28 #include <unordered_map>
29 #include <vector>
30 
31 namespace traffic_simulator
32 {
33 using TrafficLightStatePredictions = std::unordered_map<
34  lanelet::Id,
35  std::vector<std::pair<rclcpp::Time, std::vector<simulation_api_schema::TrafficLight>>>>;
36 
37 /*
38  TrafficLightsBase class is designed in such a way that while trying to perform an operation
39  on a TrafficLight (add, set, etc.) that is not added to traffic_light_map_,
40  it adds the traffic light first and then performs the operation, so that the methods
41  here cannot be tagged with the "const" specifier
42 */
44 {
45 public:
46  // State change callback types
47  enum class StateChangeType {
48  SET, // setTrafficLightsState()
49  CLEAR, // clearTrafficLightsState()
50  ADD, // addTrafficLightsState()
51  };
52 
53  using StateChangeCallback = std::function<void(
54  lanelet::Id lanelet_id, const std::string & state, StateChangeType change_type)>;
55 
56  template <typename NodeTypePointer>
57  explicit TrafficLightsBase(const NodeTypePointer & node_ptr)
58  : clock_ptr_(node_ptr->get_clock()),
59  marker_publisher_ptr_(std::make_unique<TrafficLightMarkerPublisher>(node_ptr)),
60  rate_updater_(node_ptr, [this]() { update(); })
61  {
62  }
63 
64  virtual ~TrafficLightsBase() = default;
65 
66  // update
67  auto startUpdate(const double update_rate) -> void;
68 
69  auto resetUpdate(const double update_rate) -> void;
70 
71  // checks, setters, getters
72  auto isAnyTrafficLightChanged() const -> bool;
73 
74  auto isRequiredStopTrafficLightState(const lanelet::Id traffic_light_id) -> bool;
75 
76  auto compareTrafficLightsState(const lanelet::Id lanelet_id, const std::string & state) -> bool;
77 
79  const lanelet::Id lanelet_id, const traffic_simulator::TrafficLight::Color & color) -> void;
80 
81  auto setTrafficLightsState(const lanelet::Id lanelet_id, const std::string & state) -> void;
82 
83  auto clearTrafficLightsState(const lanelet::Id lanelet_id) -> void;
84 
85  auto addTrafficLightsState(const lanelet::Id lanelet_id, const std::string & state) -> void;
86 
87  auto setTrafficLightsConfidence(const lanelet::Id lanelet_id, const double confidence) -> void;
88 
89  auto getTrafficLightsComposedState(const lanelet::Id lanelet_id) -> std::string;
90 
92  const lanelet::Ids & route_lanelets, const math::geometry::CatmullRomSplineInterface & spline)
93  -> std::optional<double>;
94 
96  -> simulation_api_schema::UpdateTrafficLightsRequest;
97 
98  auto getTrafficLight(const lanelet::Id traffic_light_id) -> TrafficLight &;
99 
100  auto registerStateChangeCallback(StateChangeCallback callback) -> void;
101 
102 protected:
103  virtual auto update() const -> void = 0;
104 
105  auto notifyStateChange(
106  const lanelet::Id lanelet_id, const std::string & state, StateChangeType change_type) -> void;
107 
108  auto isTrafficLightAdded(const lanelet::Id traffic_light_id) const -> bool;
109 
110  auto addTrafficLight(const lanelet::Id traffic_light_id) -> void;
111 
112  auto getTrafficLights(const lanelet::Id lanelet_id)
113  -> std::vector<std::reference_wrapper<TrafficLight>>;
114 
115  const rclcpp::Clock::SharedPtr clock_ptr_;
116 
117  std::unordered_map<lanelet::Id, TrafficLight> traffic_lights_map_;
120 
122 };
123 } // namespace traffic_simulator
124 #endif // TRAFFIC_SIMULATOR__TRAFFIC_LIGHTS__TRAFFIC_LIGHTS_BASE_HPP_
Definition: configurable_rate_updater.hpp:24
Definition: traffic_light_marker_publisher.hpp:25
Definition: traffic_lights_base.hpp:44
auto getDistanceToActiveTrafficLightStopLine(const lanelet::Ids &route_lanelets, const math::geometry::CatmullRomSplineInterface &spline) -> std::optional< double >
Definition: traffic_lights_base.cpp:173
StateChangeType
Definition: traffic_lights_base.hpp:47
auto resetUpdate(const double update_rate) -> void
Definition: traffic_lights_base.cpp:26
auto setTrafficLightsState(const lanelet::Id lanelet_id, const std::string &state) -> void
Definition: traffic_lights_base.cpp:70
auto isAnyTrafficLightChanged() const -> bool
Definition: traffic_lights_base.cpp:32
auto generateUpdateTrafficLightsRequest() const -> simulation_api_schema::UpdateTrafficLightsRequest
Definition: traffic_lights_base.cpp:114
auto addTrafficLight(const lanelet::Id traffic_light_id) -> void
Definition: traffic_lights_base.cpp:131
ConfigurableRateUpdater rate_updater_
Definition: traffic_lights_base.hpp:119
virtual auto update() const -> void=0
auto isRequiredStopTrafficLightState(const lanelet::Id traffic_light_id) -> bool
Definition: traffic_lights_base.cpp:34
const rclcpp::Clock::SharedPtr clock_ptr_
Definition: traffic_lights_base.hpp:115
std::vector< StateChangeCallback > state_change_callbacks_
Definition: traffic_lights_base.hpp:121
auto clearTrafficLightsState(const lanelet::Id lanelet_id) -> void
Definition: traffic_lights_base.cpp:78
auto registerStateChangeCallback(StateChangeCallback callback) -> void
Definition: traffic_lights_base.cpp:147
auto setTrafficLightsConfidence(const lanelet::Id lanelet_id, const double confidence) -> void
Definition: traffic_lights_base.cpp:95
TrafficLightsBase(const NodeTypePointer &node_ptr)
Definition: traffic_lights_base.hpp:57
auto notifyStateChange(const lanelet::Id lanelet_id, const std::string &state, StateChangeType change_type) -> void
Definition: traffic_lights_base.cpp:152
auto startUpdate(const double update_rate) -> void
Definition: traffic_lights_base.cpp:21
auto addTrafficLightsState(const lanelet::Id lanelet_id, const std::string &state) -> void
Definition: traffic_lights_base.cpp:86
const std::unique_ptr< TrafficLightMarkerPublisher > marker_publisher_ptr_
Definition: traffic_lights_base.hpp:118
auto isTrafficLightAdded(const lanelet::Id traffic_light_id) const -> bool
Definition: traffic_lights_base.cpp:126
auto getTrafficLight(const lanelet::Id traffic_light_id) -> TrafficLight &
Definition: traffic_lights_base.cpp:139
auto setTrafficLightsColor(const lanelet::Id lanelet_id, const traffic_simulator::TrafficLight::Color &color) -> void
Definition: traffic_lights_base.cpp:62
auto getTrafficLightsComposedState(const lanelet::Id lanelet_id) -> std::string
Definition: traffic_lights_base.cpp:103
std::function< void(lanelet::Id lanelet_id, const std::string &state, StateChangeType change_type)> StateChangeCallback
Definition: traffic_lights_base.hpp:54
auto getTrafficLights(const lanelet::Id lanelet_id) -> std::vector< std::reference_wrapper< TrafficLight >>
Definition: traffic_lights_base.cpp:162
auto compareTrafficLightsState(const lanelet::Id lanelet_id, const std::string &state) -> bool
Definition: traffic_lights_base.cpp:45
std::unordered_map< lanelet::Id, TrafficLight > traffic_lights_map_
Definition: traffic_lights_base.hpp:117
Definition: bounding_box.hpp:32
Definition: lanelet_wrapper.hpp:43
Definition: api.hpp:33
std::unordered_map< lanelet::Id, std::vector< std::pair< rclcpp::Time, std::vector< simulation_api_schema::TrafficLight > >> > TrafficLightStatePredictions
Definition: traffic_lights_base.hpp:35
std::string string
Definition: junit5.hpp:26
Definition: traffic_light.hpp:45
Definition: traffic_light.hpp:43