15 #ifndef CONCEALER__SUBSCRIBER_WRAPPER_HPP_
16 #define CONCEALER__SUBSCRIBER_WRAPPER_HPP_
19 #include <rclcpp/rclcpp.hpp>
25 template <
typename MessageType, ThreadSafety thread_safety = ThreadSafety::unsafe>
28 typename MessageType::ConstSharedPtr current_value = std::make_shared<const MessageType>();
30 typename rclcpp::Subscription<MessageType>::SharedPtr subscription;
36 return *current_value;
38 return *std::atomic_load(¤t_value);
42 template <
typename NodeInterface>
44 const std::string & topic,
const rclcpp::QoS & quality_of_service,
45 NodeInterface & autoware_interface,
46 const std::function<
void(
const MessageType &)> & callback = {})
47 : subscription(autoware_interface.template create_subscription<MessageType>(
48 topic, quality_of_service,
49 [
this, callback](
const typename MessageType::ConstSharedPtr message) {
50 if constexpr (thread_safety == ThreadSafety::safe) {
51 std::atomic_store(¤t_value, message);
52 if (current_value and callback) {
53 callback(*std::atomic_load(¤t_value));
56 if (current_value = message; current_value and callback) {
57 callback(*current_value);
Definition: subscriber_wrapper.hpp:27
SubscriberWrapper(const std::string &topic, const rclcpp::QoS &quality_of_service, NodeInterface &autoware_interface, const std::function< void(const MessageType &)> &callback={})
Definition: subscriber_wrapper.hpp:43
auto operator()() const -> decltype(auto)
Definition: subscriber_wrapper.hpp:33
Definition: autoware.hpp:30
ThreadSafety
Definition: subscriber_wrapper.hpp:23
std::string string
Definition: junit5.hpp:26