ros2_control - foxy
Loading...
Searching...
No Matches
realtime_publisher.h
1/*
2 * Copyright (c) 2008, Willow Garage, Inc.
3 * All rights reserved.
4 *
5 * Redistribution and use in source and binary forms, with or without
6 * modification, are permitted provided that the following conditions are met:
7 *
8 * * Redistributions of source code must retain the above copyright
9 * notice, this list of conditions and the following disclaimer.
10 * * Redistributions in binary form must reproduce the above copyright
11 * notice, this list of conditions and the following disclaimer in the
12 * documentation and/or other materials provided with the distribution.
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 OWNER 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/*
31 * Publishing ROS messages is difficult, as the publish function is
32 * not realtime safe. This class provides the proper locking so that
33 * you can call publish in realtime and a separate (non-realtime)
34 * thread will ensure that the message gets published over ROS.
35 *
36 * Author: Stuart Glaser
37 */
38#ifndef REALTIME_TOOLS__REALTIME_PUBLISHER_H_
39#define REALTIME_TOOLS__REALTIME_PUBLISHER_H_
40
41#include <atomic>
42#include <chrono>
43#include <condition_variable>
44#include <memory>
45#include <mutex>
46#include <string>
47#include <thread>
48
49#include "rclcpp/publisher.hpp"
50
51namespace realtime_tools
52{
53
54template<class Msg>
56{
57private:
58 using PublisherSharedPtr = typename rclcpp::Publisher<Msg>::SharedPtr;
59
60public:
62 Msg msg_;
63
68 explicit RealtimePublisher(PublisherSharedPtr publisher)
69 : publisher_(publisher), is_running_(false), keep_running_(true), turn_(LOOP_NOT_STARTED)
70 {
71 thread_ = std::thread(&RealtimePublisher::publishingLoop, this);
72 }
73
75 : is_running_(false), keep_running_(false), turn_(LOOP_NOT_STARTED) {}
76
79 {
80 stop();
81 while (is_running()) {
82 std::this_thread::sleep_for(std::chrono::microseconds(100));
83 }
84 if (thread_.joinable()) {
85 thread_.join();
86 }
87 }
88
90 void stop()
91 {
92 keep_running_ = false;
93#ifdef NON_POLLING
94 updated_cond_.notify_one(); // So the publishing loop can exit
95#endif
96 }
97
104 bool trylock()
105 {
106 if (msg_mutex_.try_lock()) {
107 if (turn_ == REALTIME) {
108 return true;
109 } else {
110 msg_mutex_.unlock();
111 return false;
112 }
113 } else {
114 return false;
115 }
116 }
117
125 {
126 turn_ = NON_REALTIME;
127 msg_mutex_.unlock();
128#ifdef NON_POLLING
129 updated_cond_.notify_one();
130#endif
131 }
132
139 void lock()
140 {
141#ifdef NON_POLLING
142 msg_mutex_.lock();
143#else
144 // never actually block on the lock
145 while (!msg_mutex_.try_lock()) {
146 std::this_thread::sleep_for(std::chrono::microseconds(200));
147 }
148#endif
149 }
150
154 void unlock() {msg_mutex_.unlock();}
155
156private:
157 // non-copyable
158 RealtimePublisher(const RealtimePublisher &) = delete;
159 RealtimePublisher & operator=(const RealtimePublisher &) = delete;
160
161 bool is_running() const {return is_running_;}
162
163 void publishingLoop()
164 {
165 is_running_ = true;
166 turn_ = REALTIME;
167
168 while (keep_running_) {
169 Msg outgoing;
170
171 // Locks msg_ and copies it
172 lock();
173 while (turn_ != NON_REALTIME && keep_running_) {
174#ifdef NON_POLLING
175 updated_cond_.wait(lock);
176#else
177 unlock();
178 std::this_thread::sleep_for(std::chrono::microseconds(500));
179 lock();
180#endif
181 }
182 outgoing = msg_;
183 turn_ = REALTIME;
184
185 unlock();
186
187 // Sends the outgoing message
188 if (keep_running_) {publisher_->publish(outgoing);}
189 }
190 is_running_ = false;
191 }
192
193 PublisherSharedPtr publisher_;
194 std::atomic<bool> is_running_;
195 std::atomic<bool> keep_running_;
196
197 std::thread thread_;
198
199 std::mutex msg_mutex_; // Protects msg_
200
201#ifdef NON_POLLING
202 std::condition_variable updated_cond_;
203#endif
204
205 enum { REALTIME, NON_REALTIME, LOOP_NOT_STARTED };
206 std::atomic<int> turn_; // Who's turn is it to use msg_?
207};
208
209template<class Msg>
210using RealtimePublisherSharedPtr = std::shared_ptr<RealtimePublisher<Msg>>;
211
212} // namespace realtime_tools
213#endif // REALTIME_TOOLS__REALTIME_PUBLISHER_H_
Definition realtime_publisher.h:56
void stop()
Stop the realtime publisher from sending out more ROS messages.
Definition realtime_publisher.h:90
bool trylock()
Try to get the data lock from realtime.
Definition realtime_publisher.h:104
Msg msg_
The msg_ variable contains the data that will get published on the ROS topic.
Definition realtime_publisher.h:62
void unlockAndPublish()
Unlock the msg_ variable.
Definition realtime_publisher.h:124
~RealtimePublisher()
Destructor.
Definition realtime_publisher.h:78
void unlock()
Unlocks the data without publishing anything.
Definition realtime_publisher.h:154
void lock()
Get the data lock form non-realtime.
Definition realtime_publisher.h:139
RealtimePublisher(PublisherSharedPtr publisher)
Constructor for the realtime publisher.
Definition realtime_publisher.h:68
Definition realtime_box.h:39