ros2_control - jazzy
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
91 [[deprecated(
92 "Use constructor with rclcpp::Publisher<T>::SharedPtr instead - this class does not make sense "
93 "without a real publisher")]]
95 : is_running_(false), keep_running_(false), turn_(State::LOOP_NOT_STARTED)
96 {
97 }
98
101 {
102 RCLCPP_DEBUG(rclcpp::get_logger("realtime_tools"), "Waiting for publishing thread to stop....");
103 stop();
104 while (is_running()) {
105 std::this_thread::sleep_for(std::chrono::microseconds(100));
106 }
107 RCLCPP_DEBUG(
108 rclcpp::get_logger("realtime_tools"), "Publishing thread stopped, joining thread....");
109 if (thread_.joinable()) {
110 thread_.join();
111 }
112 }
113
121 void stop()
122 {
123 {
124 std::unique_lock<std::mutex> lock(msg_mutex_);
125 keep_running_ = false;
126 }
127 updated_cond_.notify_one(); // So the publishing loop can exit
128 }
129
138 bool trylock()
139 {
140 return turn_.load(std::memory_order_acquire) == State::REALTIME && msg_mutex_.try_lock();
141 }
142
148 bool can_publish() const
149 {
150 std::unique_lock<std::mutex> lock(msg_mutex_, std::try_to_lock);
151 return can_publish(lock);
152 }
153
163 bool try_publish(const MessageT & msg)
164 {
165 std::unique_lock<std::mutex> lock(msg_mutex_, std::try_to_lock);
166 if (can_publish(lock)) {
167 {
168 std::unique_lock<std::mutex> scoped_lock(std::move(lock));
169 msg_ = msg;
170 turn_.store(State::NON_REALTIME, std::memory_order_release);
171 }
172 updated_cond_.notify_one(); // Notify the publishing thread
173 return true;
174 }
175 return false;
176 }
177
189 [[deprecated(
190 "Use try_publish() method instead of this method. This method may be removed in future "
191 "versions.")]]
192 bool tryPublish(const MessageT & msg)
193 {
194 return try_publish(msg);
195 }
196
205 {
206 turn_.store(State::NON_REALTIME, std::memory_order_release);
207 unlock();
208 }
209
216 void lock() { msg_mutex_.lock(); }
217
222 void unlock()
223 {
224 msg_mutex_.unlock();
225 updated_cond_.notify_one();
226 }
227
228 std::thread & get_thread() { return thread_; }
229
230 const std::thread & get_thread() const { return thread_; }
231
232 const MessageT & get_msg() const { return msg_; }
233
234 std::mutex & get_mutex() { return msg_mutex_; }
235
236 const std::mutex & get_mutex() const { return msg_mutex_; }
237
238private:
245 bool can_publish(std::unique_lock<std::mutex> & lock) const
246 {
247 return turn_.load(std::memory_order_acquire) == State::REALTIME && lock.owns_lock();
248 }
249
250 // non-copyable
251 RealtimePublisher(const RealtimePublisher &) = delete;
252 RealtimePublisher & operator=(const RealtimePublisher &) = delete;
253
254 bool is_running() const { return is_running_; }
255
267 void publishingLoop()
268 {
269 is_running_ = true;
270
271 while (keep_running_) {
272 MessageT outgoing;
273
274 {
275 turn_.store(State::REALTIME, std::memory_order_release);
276 // Locks msg_ and copies it to outgoing
277 std::unique_lock<std::mutex> lock_(msg_mutex_);
278 updated_cond_.wait(lock_, [&] { return turn_ == State::NON_REALTIME || !keep_running_; });
279 outgoing = msg_;
280 }
281
282 // Sends the outgoing message
283 if (keep_running_) {
284 publisher_->publish(outgoing);
285 }
286 }
287 is_running_ = false;
288 }
289
290 PublisherSharedPtr publisher_;
291 std::atomic<bool> is_running_;
292 std::atomic<bool> keep_running_;
293
294 std::thread thread_;
295
296 mutable std::mutex msg_mutex_; // Protects msg_
297 std::condition_variable updated_cond_;
298
299 enum class State : int { REALTIME, NON_REALTIME, LOOP_NOT_STARTED };
300 std::atomic<State> turn_; // Who's turn is it to use msg_?
301};
302
303template <class MessageT>
304using RealtimePublisherSharedPtr = std::shared_ptr<RealtimePublisher<MessageT>>;
305
306} // namespace realtime_tools
307#endif // REALTIME_TOOLS__REALTIME_PUBLISHER_HPP_
Definition realtime_publisher.hpp:55
void stop()
Stop the realtime publisher.
Definition realtime_publisher.hpp:121
bool try_publish(const MessageT &msg)
Try to publish the given message.
Definition realtime_publisher.hpp:163
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:192
bool trylock()
Try to acquire the data lock for non-realtime message publishing.
Definition realtime_publisher.hpp:138
~RealtimePublisher()
Destructor.
Definition realtime_publisher.hpp:100
void unlock()
Unlocks the data without publishing anything.
Definition realtime_publisher.hpp:222
void unlockAndPublish()
Unlock the msg_ variable for the non-realtime thread to start publishing.
Definition realtime_publisher.hpp:204
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:148
void lock()
Acquire the data lock.
Definition realtime_publisher.hpp:216
A pthread mutex wrapper that provides a mutex with the priority inheritance protocol and a priority c...
Definition async_function_handler.hpp:38