|
| 1 | +// Copyright 2024 TIER IV, Inc. |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#ifndef TIER4_AUTOWARE_UTILS__ROS__POLLING_SUBSCRIBER_HPP_ |
| 16 | +#define TIER4_AUTOWARE_UTILS__ROS__POLLING_SUBSCRIBER_HPP_ |
| 17 | + |
| 18 | +#include <rclcpp/rclcpp.hpp> |
| 19 | + |
| 20 | +#include <string> |
| 21 | + |
| 22 | +namespace tier4_autoware_utils |
| 23 | +{ |
| 24 | + |
| 25 | +template <typename T> |
| 26 | +class InterProcessPollingSubscriber |
| 27 | +{ |
| 28 | +private: |
| 29 | + typename rclcpp::Subscription<T>::SharedPtr subscriber_; |
| 30 | + std::optional<T> data_; |
| 31 | + |
| 32 | +public: |
| 33 | + explicit InterProcessPollingSubscriber(rclcpp::Node * node, const std::string & topic_name) |
| 34 | + { |
| 35 | + auto noexec_callback_group = |
| 36 | + node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive, false); |
| 37 | + auto noexec_subscription_options = rclcpp::SubscriptionOptions(); |
| 38 | + noexec_subscription_options.callback_group = noexec_callback_group; |
| 39 | + |
| 40 | + subscriber_ = node->create_subscription<T>( |
| 41 | + topic_name, rclcpp::QoS{1}, |
| 42 | + [node]([[maybe_unused]] const typename T::ConstSharedPtr msg) { assert(false); }, |
| 43 | + noexec_subscription_options); |
| 44 | + }; |
| 45 | + bool updateLatestData() |
| 46 | + { |
| 47 | + rclcpp::MessageInfo message_info; |
| 48 | + T tmp; |
| 49 | + // The queue size (QoS) must be 1 to get the last message data. |
| 50 | + if (subscriber_->take(tmp, message_info)) { |
| 51 | + data_ = tmp; |
| 52 | + } |
| 53 | + return data_.has_value(); |
| 54 | + }; |
| 55 | + const T & getData() const |
| 56 | + { |
| 57 | + if (!data_.has_value()) { |
| 58 | + throw std::runtime_error("Bad_optional_access in class InterProcessPollingSubscriber"); |
| 59 | + } |
| 60 | + return data_.value(); |
| 61 | + }; |
| 62 | +}; |
| 63 | + |
| 64 | +} // namespace tier4_autoware_utils |
| 65 | + |
| 66 | +#endif // TIER4_AUTOWARE_UTILS__ROS__POLLING_SUBSCRIBER_HPP_ |
0 commit comments