ros2_control - rolling
Loading...
Searching...
No Matches
realtime_publisher.hpp
1// Copyright (c) 2008, Willow Garage, Inc.
2//
3// Redistribution and use in source and binary forms, with or without
4// modification, are permitted provided that the following conditions are met:
5//
6// * Redistributions of source code must retain the above copyright
7// notice, this list of conditions and the following disclaimer.
8//
9// * Redistributions in binary form must reproduce the above copyright
10// notice, this list of conditions and the following disclaimer in the
11// documentation and/or other materials provided with the distribution.
12//
13// * Neither the name of the Willow Garage, Inc. nor the names of its
14// contributors may be used to endorse or promote products derived from
15// this software without specific prior written permission.
16//
17// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27// POSSIBILITY OF SUCH DAMAGE.
28
29/*
30 * Publishing ROS messages is difficult, as the publish function is
31 * not realtime safe. This class provides the proper locking so that
32 * you can call publish in realtime and a separate (non-realtime)
33 * thread will ensure that the message gets published over ROS.
34 *
35 * Author: Stuart Glaser
36 */
37#ifndef REALTIME_TOOLS__REALTIME_PUBLISHER_HPP_
38#define REALTIME_TOOLS__REALTIME_PUBLISHER_HPP_
39
40#include <atomic>
41#include <chrono>
42#include <condition_variable>
43#include <memory>
44#include <mutex>
45#include <string>
46#include <thread>
47#include <utility>
48
49#include "rclcpp/publisher.hpp"
50
51namespace realtime_tools
52{
53template <class MessageT>
55{
56public:
58 using PublisherType = rclcpp::Publisher<MessageT>;
59 using PublisherSharedPtr = typename rclcpp::Publisher<MessageT>::SharedPtr;
60
61 using PublishedType = typename rclcpp::TypeAdapter<MessageT>::custom_type;
62 using ROSMessageType = typename rclcpp::TypeAdapter<MessageT>::ros_message_type;
63
64 RCLCPP_SMART_PTR_DEFINITIONS(RealtimePublisher<MessageT>)
65
66 [[deprecated(
67 "This variable is deprecated, it is recommended to use the try_publish() method instead.")]]
68 MessageT msg_;
69
79#ifdef _MSC_VER
80#pragma warning(push)
81#pragma warning(disable : 4996)
82#else
83#pragma GCC diagnostic push
84#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
85#endif
86 explicit RealtimePublisher(PublisherSharedPtr publisher)
87 : publisher_(publisher), is_running_(false), keep_running_(true), turn_(State::LOOP_NOT_STARTED)
88 {
89 thread_ = std::thread(&RealtimePublisher::publishingLoop, this);
90
91 // Wait for the thread to be ready before proceeding
92 // This is important to ensure that the thread is properly initialized and ready to handle
93 // messages before any other operations are performed on the RealtimePublisher instance.
94 while (!thread_.joinable() ||
95 turn_.load(std::memory_order_acquire) == State::LOOP_NOT_STARTED) {
96 std::this_thread::sleep_for(std::chrono::microseconds(100));
97 }
98 }
99
102 {
103 RCLCPP_DEBUG(rclcpp::get_logger("realtime_tools"), "Waiting for publishing thread to stop....");
104 stop();
105 while (is_running()) {
106 std::this_thread::sleep_for(std::chrono::microseconds(100));
107 }
108 RCLCPP_DEBUG(
109 rclcpp::get_logger("realtime_tools"), "Publishing thread stopped, joining thread....");
110 if (thread_.joinable()) {
111 thread_.join();
112 }
113 }
114#ifdef _MSC_VER
115#pragma warning(pop)
116#else
117#pragma GCC diagnostic pop
118#endif
119
127 void stop()
128 {
129 {
130 std::unique_lock<std::mutex> lock(msg_mutex_);
131 keep_running_ = false;
132 }
133 updated_cond_.notify_one(); // So the publishing loop can exit
134 }
135
140 bool can_publish() const
141 {
142 std::unique_lock<std::mutex> lock(msg_mutex_, std::try_to_lock);
143 return can_publish(lock);
144 }
145
155 bool try_publish(const MessageT & msg)
156 {
157 std::unique_lock<std::mutex> lock(msg_mutex_, std::try_to_lock);
158 if (can_publish(lock)) {
159 {
160 std::unique_lock<std::mutex> scoped_lock(std::move(lock));
161#ifdef _MSC_VER
162#pragma warning(push)
163#pragma warning(disable : 4996)
164#else
165#pragma GCC diagnostic push
166#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
167#endif
168 msg_ = msg;
169#ifdef _MSC_VER
170#pragma warning(pop)
171#else
172#pragma GCC diagnostic pop
173#endif
174 turn_.store(State::NON_REALTIME, std::memory_order_release);
175 }
176 updated_cond_.notify_one(); // Notify the publishing thread
177 return true;
178 }
179 return false;
180 }
181
187 std::thread & get_thread() { return thread_; }
188
194 const std::thread & get_thread() const { return thread_; }
195
196 [[deprecated(
197 "This getter method will be removed. It is recommended to use the try_publish() instead of "
198 "accessing the msg_ variable.")]]
199 const MessageT & get_msg() const
200 {
201#ifdef _MSC_VER
202#pragma warning(push)
203#pragma warning(disable : 4996)
204#else
205#pragma GCC diagnostic push
206#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
207#endif
208 return msg_;
209#ifdef _MSC_VER
210#pragma warning(pop)
211#else
212#pragma GCC diagnostic pop
213#endif
214 }
215
219 std::mutex & get_mutex() { return msg_mutex_; }
220
224 const std::mutex & get_mutex() const { return msg_mutex_; }
225
226private:
232 bool can_publish(std::unique_lock<std::mutex> & lock) const
233 {
234 return turn_.load(std::memory_order_acquire) == State::REALTIME && lock.owns_lock();
235 }
236
237 // non-copyable
238 RealtimePublisher(const RealtimePublisher &) = delete;
239 RealtimePublisher & operator=(const RealtimePublisher &) = delete;
240
241 bool is_running() const { return is_running_; }
242
254 void publishingLoop()
255 {
256 is_running_ = true;
257
258 while (keep_running_) {
259 MessageT outgoing;
260
261 {
262 turn_.store(State::REALTIME, std::memory_order_release);
263 // Locks msg_ and copies it to outgoing
264 std::unique_lock<std::mutex> lock_(msg_mutex_);
265 updated_cond_.wait(lock_, [&] { return turn_ == State::NON_REALTIME || !keep_running_; });
266#ifdef _MSC_VER
267#pragma warning(push)
268#pragma warning(disable : 4996)
269#else
270#pragma GCC diagnostic push
271#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
272#endif
273 outgoing = msg_;
274#ifdef _MSC_VER
275#pragma warning(pop)
276#else
277#pragma GCC diagnostic pop
278#endif
279 }
280
281 // Sends the outgoing message
282 if (keep_running_) {
283 publisher_->publish(outgoing);
284 }
285 }
286 is_running_ = false;
287 }
288
289 PublisherSharedPtr publisher_;
290 std::atomic<bool> is_running_;
291 std::atomic<bool> keep_running_;
292
293 std::thread thread_;
294
295 mutable std::mutex msg_mutex_; // Protects msg_
296 std::condition_variable updated_cond_;
297
298 enum class State : int { REALTIME, NON_REALTIME, LOOP_NOT_STARTED };
299 std::atomic<State> turn_; // Who's turn is it to use msg_?
300};
301
302template <class MessageT>
303using RealtimePublisherSharedPtr = std::shared_ptr<RealtimePublisher<MessageT>>;
304
305} // namespace realtime_tools
306#endif // REALTIME_TOOLS__REALTIME_PUBLISHER_HPP_
Definition realtime_publisher.hpp:55
std::mutex & get_mutex()
Get the mutex protecting the stored message.
Definition realtime_publisher.hpp:219
void stop()
Stop the realtime publisher.
Definition realtime_publisher.hpp:127
bool try_publish(const MessageT &msg)
Try to publish the given message.
Definition realtime_publisher.hpp:155
RealtimePublisher(PublisherSharedPtr publisher)
Constructor for the realtime publisher.
Definition realtime_publisher.hpp:86
std::thread & get_thread()
Get the thread object for the publishing thread.
Definition realtime_publisher.hpp:187
~RealtimePublisher()
Destructor.
Definition realtime_publisher.hpp:101
rclcpp::Publisher< MessageT > PublisherType
Provide various typedefs to resemble the rclcpp::Publisher type.
Definition realtime_publisher.hpp:58
bool can_publish() const
Check if the realtime publisher is in a state to publish messages.
Definition realtime_publisher.hpp:140
const std::mutex & get_mutex() const
Get the mutex protecting the stored message.
Definition realtime_publisher.hpp:224
const std::thread & get_thread() const
Get the thread object for the publishing thread.
Definition realtime_publisher.hpp:194
A pthread mutex wrapper that provides a mutex with the priority inheritance protocol and a priority c...
Definition async_function_handler.hpp:40