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>
31 const rclcpp::Time & current_ros_time,
32 const simulation_api_schema::UpdateTrafficLightsRequest & request)
const ->
void = 0;
36 template <
typename MessageType>
40 template <
typename NodeTypePo
inter>
42 const NodeTypePointer & node_ptr,
const std::string & topic_name,
46 traffic_light_state_array_publisher_(rclcpp::create_publisher<MessageType>(
47 node_ptr, topic_name, rclcpp::QoS(10).transient_local()))
54 const rclcpp::Time & current_ros_time,
55 const simulation_api_schema::UpdateTrafficLightsRequest & request)
const ->
void override;
60 const typename rclcpp::Publisher<MessageType>::SharedPtr traffic_light_state_array_publisher_;
Definition: traffic_light_publisher.hpp:28
virtual ~TrafficLightPublisherBase()=default
virtual auto publish(const rclcpp::Time ¤t_ros_time, const simulation_api_schema::UpdateTrafficLightsRequest &request) const -> void=0
Definition: traffic_light_publisher.hpp:38
auto publish(const rclcpp::Time ¤t_ros_time, const simulation_api_schema::UpdateTrafficLightsRequest &request) const -> void override
~TrafficLightPublisher() override=default
TrafficLightPublisher(const NodeTypePointer &node_ptr, const std::string &topic_name, const std::string &frame="camera_link")
Definition: traffic_light_publisher.hpp:41
std::string string
Definition: junit5.hpp:26