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
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 updated_cond_.notify_one(); // So the publishing loop can exit
103 }
104
111 bool trylock()
112 {
113 if (turn_.load(std::memory_order_acquire) == State::NON_REALTIME && msg_mutex_.try_lock()) {
114 return true;
115 } else {
116 return false;
117 }
118 }
119
126 bool tryPublish(const MessageT & msg)
127 {
128 if (!trylock()) {
129 return false;
130 }
131
132 msg_ = msg;
134 return true;
135 }
136
144 {
145 turn_.store(State::REALTIME, std::memory_order_release);
146 unlock();
147 }
148
155 void lock() { msg_mutex_.lock(); }
156
160 void unlock()
161 {
162 msg_mutex_.unlock();
163 updated_cond_.notify_one();
164 }
165
166 std::thread & get_thread() { return thread_; }
167
168 const std::thread & get_thread() const { return thread_; }
169
170private:
171 // non-copyable
172 RealtimePublisher(const RealtimePublisher &) = delete;
173 RealtimePublisher & operator=(const RealtimePublisher &) = delete;
174
175 bool is_running() const { return is_running_; }
176
177 void publishingLoop()
178 {
179 is_running_ = true;
180 turn_.store(State::NON_REALTIME, std::memory_order_release);
181
182 while (keep_running_) {
183 MessageT outgoing;
184
185 {
186 // Locks msg_ and copies it to outgoing
187 std::unique_lock<std::mutex> lock_(msg_mutex_);
188 updated_cond_.wait(lock_, [&] { return turn_ == State::REALTIME || !keep_running_; });
189 outgoing = msg_;
190 }
191
192 // Sends the outgoing message
193 if (keep_running_) {
194 publisher_->publish(outgoing);
195 }
196 turn_.store(State::NON_REALTIME, std::memory_order_release);
197 }
198 is_running_ = false;
199 }
200
201 PublisherSharedPtr publisher_;
202 std::atomic<bool> is_running_;
203 std::atomic<bool> keep_running_;
204
205 std::thread thread_;
206
207 std::mutex msg_mutex_; // Protects msg_
208 std::condition_variable updated_cond_;
209
210 enum class State : int { REALTIME, NON_REALTIME, LOOP_NOT_STARTED };
211 std::atomic<State> turn_; // Who's turn is it to use msg_?
212};
213
214template <class MessageT>
215using RealtimePublisherSharedPtr = std::shared_ptr<RealtimePublisher<MessageT>>;
216
217} // namespace realtime_tools
218#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:126
bool trylock()
Try to get the data lock from realtime.
Definition realtime_publisher.hpp:111
~RealtimePublisher()
Destructor.
Definition realtime_publisher.hpp:87
void unlock()
Unlocks the data without publishing anything.
Definition realtime_publisher.hpp:160
void unlockAndPublish()
Unlock the msg_ variable.
Definition realtime_publisher.hpp:143
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:155
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