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 MessageT msg_;
67
77 explicit RealtimePublisher(PublisherSharedPtr publisher)
78 : publisher_(publisher), is_running_(false), keep_running_(true), turn_(State::LOOP_NOT_STARTED)
79 {
80 thread_ = std::thread(&RealtimePublisher::publishingLoop, this);
81
82 // Wait for the thread to be ready before proceeding
83 // This is important to ensure that the thread is properly initialized and ready to handle
84 // messages before any other operations are performed on the RealtimePublisher instance.
85 while (!thread_.joinable() ||
86 turn_.load(std::memory_order_acquire) == State::LOOP_NOT_STARTED) {
87 std::this_thread::sleep_for(std::chrono::microseconds(100));
88 }
89 }
90
93 {
94 RCLCPP_DEBUG(rclcpp::get_logger("realtime_tools"), "Waiting for publishing thread to stop....");
95 stop();
96 while (is_running()) {
97 std::this_thread::sleep_for(std::chrono::microseconds(100));
98 }
99 RCLCPP_DEBUG(
100 rclcpp::get_logger("realtime_tools"), "Publishing thread stopped, joining thread....");
101 if (thread_.joinable()) {
102 thread_.join();
103 }
104 }
105
113 void stop()
114 {
115 {
116 std::unique_lock<std::mutex> lock(msg_mutex_);
117 keep_running_ = false;
118 }
119 updated_cond_.notify_one(); // So the publishing loop can exit
120 }
121
130 [[deprecated(
131 "Use try_publish() method instead of this method. This method may be removed in future "
132 "versions.")]]
133 bool trylock()
134 {
135 return turn_.load(std::memory_order_acquire) == State::REALTIME && msg_mutex_.try_lock();
136 }
137
143 bool can_publish() const
144 {
145 std::unique_lock<std::mutex> lock(msg_mutex_, std::try_to_lock);
146 return can_publish(lock);
147 }
148
158 bool try_publish(const MessageT & msg)
159 {
160 std::unique_lock<std::mutex> lock(msg_mutex_, std::try_to_lock);
161 if (can_publish(lock)) {
162 {
163 std::unique_lock<std::mutex> scoped_lock(std::move(lock));
164 msg_ = msg;
165 turn_.store(State::NON_REALTIME, std::memory_order_release);
166 }
167 updated_cond_.notify_one(); // Notify the publishing thread
168 return true;
169 }
170 return false;
171 }
172
184 [[deprecated(
185 "Use try_publish() method instead of this method. This method may be removed in future "
186 "versions.")]]
187 bool tryPublish(const MessageT & msg)
188 {
189 return try_publish(msg);
190 }
191
199 [[deprecated(
200 "Use the try_publish() method to publish the message instead of using this method. This method "
201 "may be removed in future versions.")]]
203 {
204 turn_.store(State::NON_REALTIME, std::memory_order_release);
205#pragma GCC diagnostic push
206#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
207 unlock();
208#pragma GCC diagnostic pop
209 }
210
217 [[deprecated(
218 "Use the try_publish() method to publish the message instead of using this method. This method "
219 "may be removed in future versions.")]]
220 void lock()
221 {
222 msg_mutex_.lock();
223 }
224
229 [[deprecated(
230 "Use the try_publish() method to publish the message instead of using this method. This method "
231 "may be removed in future versions.")]]
232 void unlock()
233 {
234 msg_mutex_.unlock();
235 updated_cond_.notify_one();
236 }
237
238 std::thread & get_thread() { return thread_; }
239
240 const std::thread & get_thread() const { return thread_; }
241
242 const MessageT & get_msg() const { return msg_; }
243
244 std::mutex & get_mutex() { return msg_mutex_; }
245
246 const std::mutex & get_mutex() const { return msg_mutex_; }
247
248private:
255 bool can_publish(std::unique_lock<std::mutex> & lock) const
256 {
257 return turn_.load(std::memory_order_acquire) == State::REALTIME && lock.owns_lock();
258 }
259
260 // non-copyable
261 RealtimePublisher(const RealtimePublisher &) = delete;
262 RealtimePublisher & operator=(const RealtimePublisher &) = delete;
263
264 bool is_running() const { return is_running_; }
265
277 void publishingLoop()
278 {
279 is_running_ = true;
280
281 while (keep_running_) {
282 MessageT outgoing;
283
284 {
285 turn_.store(State::REALTIME, std::memory_order_release);
286 // Locks msg_ and copies it to outgoing
287 std::unique_lock<std::mutex> lock_(msg_mutex_);
288 updated_cond_.wait(lock_, [&] { return turn_ == State::NON_REALTIME || !keep_running_; });
289 outgoing = msg_;
290 }
291
292 // Sends the outgoing message
293 if (keep_running_) {
294 publisher_->publish(outgoing);
295 }
296 }
297 is_running_ = false;
298 }
299
300 PublisherSharedPtr publisher_;
301 std::atomic<bool> is_running_;
302 std::atomic<bool> keep_running_;
303
304 std::thread thread_;
305
306 mutable std::mutex msg_mutex_; // Protects msg_
307 std::condition_variable updated_cond_;
308
309 enum class State : int { REALTIME, NON_REALTIME, LOOP_NOT_STARTED };
310 std::atomic<State> turn_; // Who's turn is it to use msg_?
311};
312
313template <class MessageT>
314using RealtimePublisherSharedPtr = std::shared_ptr<RealtimePublisher<MessageT>>;
315
316} // namespace realtime_tools
317#endif // REALTIME_TOOLS__REALTIME_PUBLISHER_HPP_
Definition realtime_publisher.hpp:55
void stop()
Stop the realtime publisher.
Definition realtime_publisher.hpp:113
bool try_publish(const MessageT &msg)
Try to publish the given message.
Definition realtime_publisher.hpp:158
RealtimePublisher(PublisherSharedPtr publisher)
Constructor for the realtime publisher.
Definition realtime_publisher.hpp:77
bool tryPublish(const MessageT &msg)
Try to publish the given message (deprecated)
Definition realtime_publisher.hpp:187
bool trylock()
Try to acquire the data lock for non-realtime message publishing.
Definition realtime_publisher.hpp:133
~RealtimePublisher()
Destructor.
Definition realtime_publisher.hpp:92
void unlock()
Unlocks the data without publishing anything.
Definition realtime_publisher.hpp:232
void unlockAndPublish()
Unlock the msg_ variable for the non-realtime thread to start publishing.
Definition realtime_publisher.hpp:202
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:143
void lock()
Acquire the data lock.
Definition realtime_publisher.hpp:220
A pthread mutex wrapper that provides a mutex with the priority inheritance protocol and a priority c...
Definition async_function_handler.hpp:38