rclcpp  master
C++ ROS Client Library API
clock.hpp
Go to the documentation of this file.
1 // Copyright 2017 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef RCLCPP__CLOCK_HPP_
16 #define RCLCPP__CLOCK_HPP_
17 
18 #include <functional>
19 #include <memory>
20 #include <mutex>
21 #include <vector>
22 
23 #include "rclcpp/macros.hpp"
24 #include "rclcpp/time.hpp"
26 
27 #include "rcl/time.h"
28 
29 namespace rclcpp
30 {
31 
32 class TimeSource;
33 
35 
38 struct TimeJump
39 {
40  typedef enum ClockChange_t
41  {
46  } ClockChange_t;
47 
50 };
51 
53 
57 {
58 public:
59  uint64_t min_forward_;
60  uint64_t min_backward_;
62 
63  // Test if the threshold is exceeded by a TimeJump
65  bool
66  is_exceeded(const TimeJump & jump);
67 };
68 
70 {
71 public:
76  JumpThreshold & threshold);
77 
81 };
82 
83 class Clock
84 {
85 public:
87 
89  explicit Clock(rcl_clock_type_t clock_type = RCL_SYSTEM_TIME);
90 
92  ~Clock();
93 
95  Time
96  now();
97 
99  bool
101 
104  get_clock_type();
105 
106  // Add a callback to invoke if the jump threshold is exceeded.
112  JumpHandler::SharedPtr
114  std::function<void()> pre_callback,
115  std::function<void(const TimeJump &)> post_callback,
116  JumpThreshold & threshold);
117 
118 private:
119  // A method for TimeSource to get a list of callbacks to invoke while updating
122  get_triggered_callback_handlers(const TimeJump & jump);
123 
124  // Invoke callbacks that are valid and outside threshold.
126  static void invoke_prejump_callbacks(
127  const std::vector<JumpHandler::SharedPtr> & callbacks);
128 
130  static void invoke_postjump_callbacks(
131  const std::vector<JumpHandler::SharedPtr> & callbacks,
132  const TimeJump & jump);
133 
135  rcl_clock_t rcl_clock_;
136  friend TimeSource;
137  rcl_allocator_t allocator_;
138 
139  std::mutex callback_list_mutex_;
140  std::vector<std::weak_ptr<JumpHandler>> active_jump_handlers_;
141 };
142 
143 } // namespace rclcpp
144 
145 #endif // RCLCPP__CLOCK_HPP_
Definition: time_source.hpp:36
std::function< void()> pre_callback
Definition: clock.hpp:78
The time type switched to SYSTEM_TIME from ROS_TIME.
Definition: clock.hpp:44
Clock(rcl_clock_type_t clock_type=RCL_SYSTEM_TIME)
Definition: clock.hpp:83
rcl_clock_type_t
Definition: allocator_common.hpp:24
ClockChange_t
Definition: clock.hpp:40
ClockChange_t jump_type_
The change in clock_type if there is one.
Definition: clock.hpp:48
bool is_exceeded(const TimeJump &jump)
JumpThreshold notice_threshold
Definition: clock.hpp:80
RCL_SYSTEM_TIME
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
uint64_t min_backward_
The minimum backwards jump to be considered exceeded.
Definition: clock.hpp:60
rcl_clock_type_t get_clock_type()
JumpHandler(std::function< void()> pre_callback, std::function< void(TimeJump)> post_callback, JumpThreshold &threshold)
bool ros_time_is_active()
std::function< void(const TimeJump &)> post_callback
Definition: clock.hpp:79
The time type before and after the jump is ROS_TIME.
Definition: clock.hpp:42
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
The time type switched to ROS_TIME from SYSTEM_TIME.
Definition: clock.hpp:43
bool on_clock_change_
Whether to trigger on any clock type change.
Definition: clock.hpp:61
Definition: clock.hpp:69
The time type before and after the jump is SYSTEM_TIME.
Definition: clock.hpp:45
uint64_t min_forward_
The minimum jump forward to be considered exceeded..
Definition: clock.hpp:59
rcl_duration_t delta_
The change in time value.
Definition: clock.hpp:49
Definition: time.hpp:31
A struct to represent a timejump.
Definition: clock.hpp:38
JumpHandler::SharedPtr create_jump_callback(std::function< void()> pre_callback, std::function< void(const TimeJump &)> post_callback, JumpThreshold &threshold)
A class to store a threshold for a TimeJump.
Definition: clock.hpp:56