15 #ifndef CONCEALER__SUBSCRIBER_WRAPPER_HPP_
16 #define CONCEALER__SUBSCRIBER_WRAPPER_HPP_
19 #include <rclcpp/rclcpp.hpp>
23 template <
typename Message>
26 typename Message::ConstSharedPtr current_value = std::make_shared<const Message>();
28 typename rclcpp::Subscription<Message>::SharedPtr subscription;
31 auto operator()() const -> const auto & {
return *std::atomic_load(¤t_value); }
33 template <
typename Autoware,
typename Callback>
35 const std::string & topic,
const rclcpp::QoS & quality_of_service, Autoware & autoware,
36 const Callback & callback)
37 : subscription(autoware.template create_subscription<Message>(
38 topic, quality_of_service,
39 [this, callback](const typename Message::ConstSharedPtr & message) {
40 if (std::atomic_store(¤t_value, message); current_value) {
41 callback(*std::atomic_load(¤t_value));
47 template <
typename Autoware>
49 const std::string & topic,
const rclcpp::QoS & quality_of_service, Autoware & autoware)
50 : subscription(autoware.template create_subscription<Message>(
51 topic, quality_of_service, [this](const typename Message::ConstSharedPtr & message) {
52 std::atomic_store(¤t_value, message);
Definition: subscriber_wrapper.hpp:25
auto operator()() const -> const auto &
Definition: subscriber_wrapper.hpp:31
SubscriberWrapper(const std::string &topic, const rclcpp::QoS &quality_of_service, Autoware &autoware, const Callback &callback)
Definition: subscriber_wrapper.hpp:34
SubscriberWrapper(const std::string &topic, const rclcpp::QoS &quality_of_service, Autoware &autoware)
Definition: subscriber_wrapper.hpp:48
Definition: autoware_universe.hpp:40
std::string string
Definition: junit5.hpp:26