ros2_control - rolling
realtime_clock.h
1 // Copyright (c) 2013, hiDOF, 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 hiDOF, 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: Wim Meeussen
36  */
37 
38 #ifndef REALTIME_TOOLS__REALTIME_CLOCK_H_
39 #define REALTIME_TOOLS__REALTIME_CLOCK_H_
40 
41 #include <mutex>
42 #include <thread>
43 
44 #include "rclcpp/clock.hpp"
45 #include "rclcpp/duration.hpp"
46 #include "rclcpp/logger.hpp"
47 #include "rclcpp/time.hpp"
48 
49 namespace realtime_tools
50 {
52 {
53 public:
57  RealtimeClock();
58 
62  explicit RealtimeClock(rclcpp::Clock::SharedPtr clock);
63 
67  RealtimeClock(rclcpp::Clock::SharedPtr clock, rclcpp::Logger logger);
68 
69  ~RealtimeClock();
70 
75  [[deprecated]] rclcpp::Time getSystemTime(const rclcpp::Time & realtime_time = rclcpp::Time());
76 
82  rclcpp::Time now(const rclcpp::Time & realtime_time = rclcpp::Time());
83 
84 private:
85  void loop();
86 
87  rclcpp::Clock::SharedPtr clock_;
88  rclcpp::Logger logger_;
89  unsigned int lock_misses_ = 0;
90  rclcpp::Time system_time_;
91  rclcpp::Duration clock_offset_{0, 0u};
92 
93  rclcpp::Time last_realtime_time_;
94  bool running_ = false;
95  bool initialized_ = false;
96  std::mutex mutex_;
97  std::thread thread_;
98 }; // class
99 
100 } // namespace realtime_tools
101 #endif // REALTIME_TOOLS__REALTIME_CLOCK_H_
Definition: realtime_clock.h:52
RealtimeClock()
Definition: realtime_clock.cpp:47
rclcpp::Time getSystemTime(const rclcpp::Time &realtime_time=rclcpp::Time())
rclcpp::Time now(const rclcpp::Time &realtime_time=rclcpp::Time())
Definition: realtime_clock.cpp:67
Definition: async_function_handler.hpp:38