ros2_control - galactic
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
48#include "rclcpp/publisher.hpp"
49
50namespace realtime_tools
51{
52template <class MessageT>
54{
55public:
57 using PublisherType = rclcpp::Publisher<MessageT>;
58 using PublisherSharedPtr = typename rclcpp::Publisher<MessageT>::SharedPtr;
59
60 using PublishedType = typename rclcpp::TypeAdapter<MessageT>::custom_type;
61 using ROSMessageType = typename rclcpp::TypeAdapter<MessageT>::ros_message_type;
62
63 RCLCPP_SMART_PTR_DEFINITIONS(RealtimePublisher<MessageT>)
64
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 if (turn_.load(std::memory_order_acquire) == State::REALTIME && msg_mutex_.try_lock()) {
141 return true;
142 } else {
143 return false;
144 }
145 }
146
156 bool tryPublish(const MessageT & msg)
157 {
158 if (!trylock()) {
159 return false;
160 }
161
162 msg_ = msg;
164 return true;
165 }
166
175 {
176 turn_.store(State::NON_REALTIME, std::memory_order_release);
177 unlock();
178 }
179
186 void lock() { msg_mutex_.lock(); }
187
192 void unlock()
193 {
194 msg_mutex_.unlock();
195 updated_cond_.notify_one();
196 }
197
198private:
199 // non-copyable
200 RealtimePublisher(const RealtimePublisher &) = delete;
201 RealtimePublisher & operator=(const RealtimePublisher &) = delete;
202
203 bool is_running() const { return is_running_; }
204
216 void publishingLoop()
217 {
218 is_running_ = true;
219
220 while (keep_running_) {
221 MessageT outgoing;
222
223 {
224 turn_.store(State::REALTIME, std::memory_order_release);
225 // Locks msg_ and copies it to outgoing
226 std::unique_lock<std::mutex> lock_(msg_mutex_);
227 updated_cond_.wait(lock_, [&] { return turn_ == State::NON_REALTIME || !keep_running_; });
228 outgoing = msg_;
229 }
230
231 // Sends the outgoing message
232 if (keep_running_) {
233 publisher_->publish(outgoing);
234 }
235 }
236 is_running_ = false;
237 }
238
239 PublisherSharedPtr publisher_;
240 std::atomic<bool> is_running_;
241 std::atomic<bool> keep_running_;
242
243 std::thread thread_;
244
245 std::mutex msg_mutex_; // Protects msg_
246 std::condition_variable updated_cond_;
247
248 enum class State : int { REALTIME, NON_REALTIME, LOOP_NOT_STARTED };
249 std::atomic<State> turn_; // Who's turn is it to use msg_?
250};
251
252template <class MessageT>
253using RealtimePublisherSharedPtr = std::shared_ptr<RealtimePublisher<MessageT>>;
254
255} // namespace realtime_tools
256#endif // REALTIME_TOOLS__REALTIME_PUBLISHER_HPP_
Definition realtime_publisher.hpp:54
void stop()
Stop the realtime publisher.
Definition realtime_publisher.hpp:121
bool tryPublish(const MessageT &msg)
Try to get the data lock from realtime and publish the given message.
Definition realtime_publisher.hpp:156
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:192
void unlockAndPublish()
Unlock the msg_ variable for the non-realtime thread to start publishing.
Definition realtime_publisher.hpp:174
rclcpp::Publisher< MessageT > PublisherType
Provide various typedefs to resemble the rclcpp::Publisher type.
Definition realtime_publisher.hpp:57
void lock()
Acquire the data lock.
Definition realtime_publisher.hpp:186
MessageT msg_
The msg_ variable contains the data that will get published on the ROS topic.
Definition realtime_publisher.hpp:66
A pthread mutex wrapper that provides a mutex with the priority inheritance protocol and a priority c...
Definition async_function_handler.hpp:38