15 #ifndef CONCEALER__SUBSCRIBER_HPP_
16 #define CONCEALER__SUBSCRIBER_HPP_
19 #include <rclcpp/rclcpp.hpp>
23 template <
typename Message>
26 typename Message::ConstSharedPtr
current_value = std::make_shared<const Message>();
32 template <
typename Autoware,
typename Callback>
34 const std::string & topic,
const rclcpp::QoS & quality_of_service, Autoware & autoware,
35 const Callback & callback)
36 :
subscription(autoware.template create_subscription<Message>(
37 topic, quality_of_service,
38 [this, callback](const typename Message::ConstSharedPtr & message) {
46 template <
typename Autoware>
48 const std::string & topic,
const rclcpp::QoS & quality_of_service, Autoware & autoware)
49 :
subscription(autoware.template create_subscription<Message>(
50 topic, quality_of_service, [this](const typename Message::ConstSharedPtr & message) {
Definition: autoware_universe.hpp:40
std::string string
Definition: junit5.hpp:26
Definition: subscriber.hpp:25
Subscriber(const std::string &topic, const rclcpp::QoS &quality_of_service, Autoware &autoware, const Callback &callback)
Definition: subscriber.hpp:33
auto operator()() const -> const auto &
Definition: subscriber.hpp:30
rclcpp::Subscription< Message >::SharedPtr subscription
Definition: subscriber.hpp:28
Message::ConstSharedPtr current_value
Definition: subscriber.hpp:26
Subscriber(const std::string &topic, const rclcpp::QoS &quality_of_service, Autoware &autoware)
Definition: subscriber.hpp:47