ros2_control - rolling
realtime_publisher.h
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_H_
38 #define REALTIME_TOOLS__REALTIME_PUBLISHER_H_
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 
50 namespace realtime_tools
51 {
52 template <class Msg>
54 {
55 private:
56  using PublisherSharedPtr = typename rclcpp::Publisher<Msg>::SharedPtr;
57 
58 public:
60  Msg msg_;
61 
66  explicit RealtimePublisher(PublisherSharedPtr publisher)
67  : publisher_(publisher), is_running_(false), keep_running_(true), turn_(LOOP_NOT_STARTED)
68  {
69  thread_ = std::thread(&RealtimePublisher::publishingLoop, this);
70  }
71 
72  RealtimePublisher() : is_running_(false), keep_running_(false), turn_(LOOP_NOT_STARTED) {}
73 
76  {
77  stop();
78  while (is_running()) {
79  std::this_thread::sleep_for(std::chrono::microseconds(100));
80  }
81  if (thread_.joinable()) {
82  thread_.join();
83  }
84  }
85 
87  void stop()
88  {
89  keep_running_ = false;
90 #ifdef NON_POLLING
91  updated_cond_.notify_one(); // So the publishing loop can exit
92 #endif
93  }
94 
101  bool trylock()
102  {
103  if (msg_mutex_.try_lock()) {
104  if (turn_ == REALTIME) {
105  return true;
106  } else {
107  msg_mutex_.unlock();
108  return false;
109  }
110  } else {
111  return false;
112  }
113  }
114 
122  {
123  turn_ = NON_REALTIME;
124  unlock();
125  }
126 
133  void lock()
134  {
135 #ifdef NON_POLLING
136  msg_mutex_.lock();
137 #else
138  // never actually block on the lock
139  while (!msg_mutex_.try_lock()) {
140  std::this_thread::sleep_for(std::chrono::microseconds(200));
141  }
142 #endif
143  }
144 
148  void unlock()
149  {
150  msg_mutex_.unlock();
151 #ifdef NON_POLLING
152  updated_cond_.notify_one();
153 #endif
154  }
155 
156 private:
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 
173 #ifdef NON_POLLING
174  std::unique_lock<std::mutex> lock_(msg_mutex_);
175 #else
176  lock();
177 #endif
178 
179  while (turn_ != NON_REALTIME && keep_running_) {
180 #ifdef NON_POLLING
181  updated_cond_.wait(lock_);
182 #else
183  unlock();
184  std::this_thread::sleep_for(std::chrono::microseconds(500));
185  lock();
186 #endif
187  }
188  outgoing = msg_;
189  turn_ = REALTIME;
190 
191  unlock();
192 
193  // Sends the outgoing message
194  if (keep_running_) {
195  publisher_->publish(outgoing);
196  }
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 
209 #ifdef NON_POLLING
210  std::condition_variable updated_cond_;
211 #endif
212 
213  enum { REALTIME, NON_REALTIME, LOOP_NOT_STARTED };
214  std::atomic<int> turn_; // Who's turn is it to use msg_?
215 };
216 
217 template <class Msg>
218 using RealtimePublisherSharedPtr = std::shared_ptr<RealtimePublisher<Msg>>;
219 
220 } // namespace realtime_tools
221 #endif // REALTIME_TOOLS__REALTIME_PUBLISHER_H_
Definition: realtime_publisher.h:54
void stop()
Stop the realtime publisher from sending out more ROS messages.
Definition: realtime_publisher.h:87
bool trylock()
Try to get the data lock from realtime.
Definition: realtime_publisher.h:101
Msg msg_
The msg_ variable contains the data that will get published on the ROS topic.
Definition: realtime_publisher.h:60
void unlockAndPublish()
Unlock the msg_ variable.
Definition: realtime_publisher.h:121
~RealtimePublisher()
Destructor.
Definition: realtime_publisher.h:75
void unlock()
Unlocks the data without publishing anything.
Definition: realtime_publisher.h:148
void lock()
Get the data lock form non-realtime.
Definition: realtime_publisher.h:133
RealtimePublisher(PublisherSharedPtr publisher)
Constructor for the realtime publisher.
Definition: realtime_publisher.h:66
Definition: async_function_handler.hpp:38