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
75 explicit RealtimePublisher(PublisherSharedPtr publisher)
76 : publisher_(publisher), is_running_(false), keep_running_(true), turn_(State::LOOP_NOT_STARTED)
77 {
78 thread_ = std::thread(&RealtimePublisher::publishingLoop, this);
79
80 // Wait for the thread to be ready before proceeding
81 // This is important to ensure that the thread is properly initialized and ready to handle
82 // messages before any other operations are performed on the RealtimePublisher instance.
83 while (!thread_.joinable() ||
84 turn_.load(std::memory_order_acquire) == State::LOOP_NOT_STARTED) {
85 std::this_thread::sleep_for(std::chrono::microseconds(100));
86 }
87 }
88
91 {
92 RCLCPP_DEBUG(rclcpp::get_logger("realtime_tools"), "Waiting for publishing thread to stop....");
93 stop();
94 while (is_running()) {
95 std::this_thread::sleep_for(std::chrono::microseconds(100));
96 }
97 RCLCPP_DEBUG(
98 rclcpp::get_logger("realtime_tools"), "Publishing thread stopped, joining thread....");
99 if (thread_.joinable()) {
100 thread_.join();
101 }
102 }
103
111 void stop()
112 {
113 {
114 std::unique_lock<std::mutex> lock(msg_mutex_);
115 keep_running_ = false;
116 }
117 updated_cond_.notify_one(); // So the publishing loop can exit
118 }
119
124 bool can_publish() const
125 {
126 std::unique_lock<std::mutex> lock(msg_mutex_, std::try_to_lock);
127 return can_publish(lock);
128 }
129
139 bool try_publish(const MessageT & msg)
140 {
141 std::unique_lock<std::mutex> lock(msg_mutex_, std::try_to_lock);
142 if (can_publish(lock)) {
143 {
144 std::unique_lock<std::mutex> scoped_lock(std::move(lock));
145 msg_ = msg;
146 turn_.store(State::NON_REALTIME, std::memory_order_release);
147 }
148 updated_cond_.notify_one(); // Notify the publishing thread
149 return true;
150 }
151 return false;
152 }
153
159 std::thread & get_thread() { return thread_; }
160
166 const std::thread & get_thread() const { return thread_; }
167
171 std::mutex & get_mutex() { return msg_mutex_; }
172
176 const std::mutex & get_mutex() const { return msg_mutex_; }
177
178private:
184 bool can_publish(std::unique_lock<std::mutex> & lock) const
185 {
186 return turn_.load(std::memory_order_acquire) == State::REALTIME && lock.owns_lock();
187 }
188
189 // non-copyable
190 RealtimePublisher(const RealtimePublisher &) = delete;
191 RealtimePublisher & operator=(const RealtimePublisher &) = delete;
192
193 bool is_running() const { return is_running_; }
194
206 void publishingLoop()
207 {
208 is_running_ = true;
209
210 while (keep_running_) {
211 MessageT outgoing;
212
213 {
214 turn_.store(State::REALTIME, std::memory_order_release);
215 // Locks msg_ and copies it to outgoing
216 std::unique_lock<std::mutex> lock_(msg_mutex_);
217 updated_cond_.wait(lock_, [&] { return turn_ == State::NON_REALTIME || !keep_running_; });
218 outgoing = msg_;
219 }
220
221 // Sends the outgoing message
222 if (keep_running_) {
223 publisher_->publish(outgoing);
224 }
225 }
226 is_running_ = false;
227 }
228
229 PublisherSharedPtr publisher_;
230 std::atomic<bool> is_running_;
231 std::atomic<bool> keep_running_;
232
233 std::thread thread_;
234
235 MessageT msg_;
236
237 mutable std::mutex msg_mutex_; // Protects msg_
238 std::condition_variable updated_cond_;
239
240 enum class State : int { REALTIME, NON_REALTIME, LOOP_NOT_STARTED };
241 std::atomic<State> turn_; // Who's turn is it to use msg_?
242};
243
244template <class MessageT>
245using RealtimePublisherSharedPtr = std::shared_ptr<RealtimePublisher<MessageT>>;
246
247} // namespace realtime_tools
248#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:171
void stop()
Stop the realtime publisher.
Definition realtime_publisher.hpp:111
bool try_publish(const MessageT &msg)
Try to publish the given message.
Definition realtime_publisher.hpp:139
std::thread & get_thread()
Get the thread object for the publishing thread.
Definition realtime_publisher.hpp:159
~RealtimePublisher()
Destructor.
Definition realtime_publisher.hpp:90
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:124
const std::mutex & get_mutex() const
Get the mutex protecting the stored message.
Definition realtime_publisher.hpp:176
const std::thread & get_thread() const
Get the thread object for the publishing thread.
Definition realtime_publisher.hpp:166
A pthread mutex wrapper that provides a mutex with the priority inheritance protocol and a priority c...
Definition async_function_handler.hpp:40