15 #ifndef TRAFFIC_SIMULATOR__TRAFFIC_LIGHTS__TRAFFIC_LIGHTS_BASE_HPP_
16 #define TRAFFIC_SIMULATOR__TRAFFIC_LIGHTS__TRAFFIC_LIGHTS_BASE_HPP_
18 #include <simulation_api_schema.pb.h>
21 #include <rclcpp/rclcpp.hpp>
27 #include <unordered_map>
41 template <
typename NodeTypePo
inter>
43 const NodeTypePointer & node_ptr,
const std::shared_ptr<hdmap_utils::HdMapUtils> &
hdmap_utils)
75 -> simulation_api_schema::UpdateTrafficLightsRequest;
78 virtual auto
update() const ->
void = 0;
Definition: configurable_rate_updater.hpp:24
Definition: traffic_light_marker_publisher.hpp:24
Definition: traffic_lights_base.hpp:39
TrafficLightsBase(const NodeTypePointer &node_ptr, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils)
Definition: traffic_lights_base.hpp:42
auto resetUpdate(const double update_rate) -> void
Definition: traffic_lights_base.cpp:24
auto setTrafficLightsState(const lanelet::Id lanelet_id, const std::string &state) -> void
Definition: traffic_lights_base.cpp:68
auto isAnyTrafficLightChanged() const -> bool
Definition: traffic_lights_base.cpp:30
auto generateUpdateTrafficLightsRequest() const -> simulation_api_schema::UpdateTrafficLightsRequest
Definition: traffic_lights_base.cpp:96
auto addTrafficLight(const lanelet::Id traffic_light_id) -> void
Definition: traffic_lights_base.cpp:116
ConfigurableRateUpdater rate_updater_
Definition: traffic_lights_base.hpp:94
virtual auto update() const -> void=0
auto isRequiredStopTrafficLightState(const lanelet::Id traffic_light_id) -> bool
Definition: traffic_lights_base.cpp:32
const rclcpp::Clock::SharedPtr clock_ptr_
Definition: traffic_lights_base.hpp:90
auto setTrafficLightsConfidence(const lanelet::Id lanelet_id, const double confidence) -> void
Definition: traffic_lights_base.cpp:77
auto startUpdate(const double update_rate) -> void
Definition: traffic_lights_base.cpp:19
const std::unique_ptr< TrafficLightMarkerPublisher > marker_publisher_ptr_
Definition: traffic_lights_base.hpp:93
const std::shared_ptr< hdmap_utils::HdMapUtils > hdmap_utils_
Definition: traffic_lights_base.hpp:89
auto isTrafficLightAdded(const lanelet::Id traffic_light_id) const -> bool
Definition: traffic_lights_base.cpp:111
auto getTrafficLight(const lanelet::Id traffic_light_id) -> TrafficLight &
Definition: traffic_lights_base.cpp:124
auto setTrafficLightsColor(const lanelet::Id lanelet_id, const traffic_simulator::TrafficLight::Color &color) -> void
Definition: traffic_lights_base.cpp:60
virtual ~TrafficLightsBase()=default
auto getTrafficLightsComposedState(const lanelet::Id lanelet_id) -> std::string
Definition: traffic_lights_base.cpp:85
auto getTrafficLights(const lanelet::Id lanelet_id) -> std::vector< std::reference_wrapper< TrafficLight >>
Definition: traffic_lights_base.cpp:130
auto compareTrafficLightsState(const lanelet::Id lanelet_id, const std::string &state) -> bool
Definition: traffic_lights_base.cpp:43
std::unordered_map< lanelet::Id, TrafficLight > traffic_lights_map_
Definition: traffic_lights_base.hpp:92
Definition: traffic_light.hpp:44
Definition: traffic_light.hpp:42