15 #ifndef TRAFFIC_SIMULATOR__TRAFFIC_LIGHTS__TRAFFIC_LIGHT_PUBLISHER_HPP_
16 #define TRAFFIC_SIMULATOR__TRAFFIC_LIGHTS__TRAFFIC_LIGHT_PUBLISHER_HPP_
19 #include <rclcpp/rclcpp.hpp>
30 const rclcpp::Time & current_ros_time,
31 const simulation_api_schema::UpdateTrafficLightsRequest & request) ->
void = 0;
34 template <
typename Message>
37 const typename rclcpp::Publisher<Message>::SharedPtr traffic_light_state_array_publisher_;
39 const std::shared_ptr<hdmap_utils::HdMapUtils> hdmap_utils_;
42 template <
typename NodePo
inter>
44 const std::string & topic_name,
const NodePointer & node,
45 const std::shared_ptr<hdmap_utils::HdMapUtils> &
hdmap_utils =
nullptr)
47 traffic_light_state_array_publisher_(
48 rclcpp::create_publisher<Message>(node, topic_name, rclcpp::QoS(10).transient_local())),
54 const rclcpp::Time & current_ros_time,
55 const simulation_api_schema::UpdateTrafficLightsRequest & request) ->
void override;
Definition: traffic_light_publisher.hpp:27
virtual auto publish(const rclcpp::Time ¤t_ros_time, const simulation_api_schema::UpdateTrafficLightsRequest &request) -> void=0
Definition: traffic_light_publisher.hpp:36
auto publish(const rclcpp::Time ¤t_ros_time, const simulation_api_schema::UpdateTrafficLightsRequest &request) -> void override
TrafficLightPublisher(const std::string &topic_name, const NodePointer &node, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils=nullptr)
Definition: traffic_light_publisher.hpp:43
std::string string
Definition: junit5.hpp:26