ros2_control - iron
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
72 explicit RealtimePublisher(PublisherSharedPtr publisher)
73 : publisher_(publisher), is_running_(false), keep_running_(true), turn_(State::LOOP_NOT_STARTED)
74 {
75 thread_ = std::thread(&RealtimePublisher::publishingLoop, this);
76 }
77
78 [[deprecated(
79 "Use constructor with rclcpp::Publisher<T>::SharedPtr instead - this class does not make sense "
80 "without a real publisher")]]
82 : is_running_(false), keep_running_(false), turn_(State::LOOP_NOT_STARTED)
83 {
84 }
85
88 {
89 stop();
90 while (is_running()) {
91 std::this_thread::sleep_for(std::chrono::microseconds(100));
92 }
93 if (thread_.joinable()) {
94 thread_.join();
95 }
96 }
97
99 void stop()
100 {
101 keep_running_ = false;
102#ifdef NON_POLLING
103 updated_cond_.notify_one(); // So the publishing loop can exit
104#endif
105 }
106
113 bool trylock()
114 {
115 if (msg_mutex_.try_lock()) {
116 if (turn_ == State::REALTIME) {
117 return true;
118 } else {
119 msg_mutex_.unlock();
120 return false;
121 }
122 } else {
123 return false;
124 }
125 }
126
133 bool tryPublish(const MessageT & msg)
134 {
135 if (!trylock()) {
136 return false;
137 }
138
139 msg_ = msg;
141 return true;
142 }
143
151 {
152 turn_ = State::NON_REALTIME;
153 unlock();
154 }
155
162 void lock()
163 {
164#ifdef NON_POLLING
165 msg_mutex_.lock();
166#else
167 // never actually block on the lock
168 while (!msg_mutex_.try_lock()) {
169 std::this_thread::sleep_for(std::chrono::microseconds(200));
170 }
171#endif
172 }
173
177 void unlock()
178 {
179 msg_mutex_.unlock();
180#ifdef NON_POLLING
181 updated_cond_.notify_one();
182#endif
183 }
184
185 std::thread & get_thread() { return thread_; }
186
187 const std::thread & get_thread() const { return thread_; }
188
189private:
190 // non-copyable
191 RealtimePublisher(const RealtimePublisher &) = delete;
192 RealtimePublisher & operator=(const RealtimePublisher &) = delete;
193
194 bool is_running() const { return is_running_; }
195
196 void publishingLoop()
197 {
198 is_running_ = true;
199 turn_ = State::REALTIME;
200
201 while (keep_running_) {
202 MessageT outgoing;
203
204 // Locks msg_ and copies it
205
206#ifdef NON_POLLING
207 std::unique_lock<std::mutex> lock_(msg_mutex_);
208#else
209 lock();
210#endif
211
212 while (turn_ != State::NON_REALTIME && keep_running_) {
213#ifdef NON_POLLING
214 updated_cond_.wait(lock_);
215#else
216 unlock();
217 std::this_thread::sleep_for(std::chrono::microseconds(500));
218 lock();
219#endif
220 }
221 outgoing = msg_;
222 turn_ = State::REALTIME;
223
224 unlock();
225
226 // Sends the outgoing message
227 if (keep_running_) {
228 publisher_->publish(outgoing);
229 }
230 }
231 is_running_ = false;
232 }
233
234 PublisherSharedPtr publisher_;
235 std::atomic<bool> is_running_;
236 std::atomic<bool> keep_running_;
237
238 std::thread thread_;
239
240 std::mutex msg_mutex_; // Protects msg_
241
242#ifdef NON_POLLING
243 std::condition_variable updated_cond_;
244#endif
245
246 enum class State : int { REALTIME, NON_REALTIME, LOOP_NOT_STARTED };
247 std::atomic<State> turn_; // Who's turn is it to use msg_?
248};
249
250template <class MessageT>
251using RealtimePublisherSharedPtr = std::shared_ptr<RealtimePublisher<MessageT>>;
252
253} // namespace realtime_tools
254#endif // REALTIME_TOOLS__REALTIME_PUBLISHER_HPP_
Definition realtime_publisher.hpp:54
void stop()
Stop the realtime publisher from sending out more ROS messages.
Definition realtime_publisher.hpp:99
RealtimePublisher(PublisherSharedPtr publisher)
Constructor for the realtime publisher.
Definition realtime_publisher.hpp:72
bool tryPublish(const MessageT &msg)
Try to get the data lock from realtime and publish the given message.
Definition realtime_publisher.hpp:133
bool trylock()
Try to get the data lock from realtime.
Definition realtime_publisher.hpp:113
~RealtimePublisher()
Destructor.
Definition realtime_publisher.hpp:87
void unlock()
Unlocks the data without publishing anything.
Definition realtime_publisher.hpp:177
void unlockAndPublish()
Unlock the msg_ variable.
Definition realtime_publisher.hpp:150
rclcpp::Publisher< MessageT > PublisherType
Provide various typedefs to resemble the rclcpp::Publisher type.
Definition realtime_publisher.hpp:57
void lock()
Get the data lock form non-realtime.
Definition realtime_publisher.hpp:162
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