ROS 2 rclcpp + rcl - jazzy  jazzy
ROS 2 C++ Client Library with ROS Client Library
time.hpp
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__TIME_HPP_
16 #define RCLCPP__TIME_HPP_
17 
18 #include "builtin_interfaces/msg/time.hpp"
19 
20 #include "rclcpp/visibility_control.hpp"
21 
22 #include "rcl/time.h"
23 
24 #include "rclcpp/duration.hpp"
25 
26 namespace rclcpp
27 {
28 
29 class Clock;
30 
31 class Time
32 {
33 public:
35 
45  RCLCPP_PUBLIC
46  Time(int32_t seconds, uint32_t nanoseconds, rcl_clock_type_t clock_type = RCL_SYSTEM_TIME);
47 
49 
53  RCLCPP_PUBLIC
54  explicit Time(int64_t nanoseconds = 0, rcl_clock_type_t clock_type = RCL_SYSTEM_TIME);
55 
57  RCLCPP_PUBLIC
58  Time(const Time & rhs);
59 
61  RCLCPP_PUBLIC
62  Time(Time && rhs) noexcept;
63 
65 
70  RCLCPP_PUBLIC
71  Time(
72  const builtin_interfaces::msg::Time & time_msg,
73  rcl_clock_type_t clock_type = RCL_ROS_TIME);
74 
76 
79  RCLCPP_PUBLIC
80  explicit Time(const rcl_time_point_t & time_point);
81 
83  RCLCPP_PUBLIC
84  virtual ~Time();
85 
87  RCLCPP_PUBLIC
88  operator builtin_interfaces::msg::Time() const;
89 
94  RCLCPP_PUBLIC
95  Time &
96  operator=(const Time & rhs);
97 
104  RCLCPP_PUBLIC
105  Time &
106  operator=(const builtin_interfaces::msg::Time & time_msg);
107 
111  RCLCPP_PUBLIC
112  Time &
113  operator=(Time && rhs) noexcept;
114 
118  RCLCPP_PUBLIC
119  bool
120  operator==(const rclcpp::Time & rhs) const;
121 
122  RCLCPP_PUBLIC
123  bool
124  operator!=(const rclcpp::Time & rhs) const;
125 
129  RCLCPP_PUBLIC
130  bool
131  operator<(const rclcpp::Time & rhs) const;
132 
136  RCLCPP_PUBLIC
137  bool
138  operator<=(const rclcpp::Time & rhs) const;
139 
143  RCLCPP_PUBLIC
144  bool
145  operator>=(const rclcpp::Time & rhs) const;
146 
150  RCLCPP_PUBLIC
151  bool
152  operator>(const rclcpp::Time & rhs) const;
153 
157  RCLCPP_PUBLIC
158  Time
159  operator+(const rclcpp::Duration & rhs) const;
160 
165  RCLCPP_PUBLIC
166  Duration
167  operator-(const rclcpp::Time & rhs) const;
168 
172  RCLCPP_PUBLIC
173  Time
174  operator-(const rclcpp::Duration & rhs) const;
175 
179  RCLCPP_PUBLIC
180  Time &
181  operator+=(const rclcpp::Duration & rhs);
182 
186  RCLCPP_PUBLIC
187  Time &
188  operator-=(const rclcpp::Duration & rhs);
189 
191 
194  RCLCPP_PUBLIC
196  nanoseconds() const;
197 
199 
202  RCLCPP_PUBLIC
203  static Time
204  max(rcl_clock_type_t clock_type = RCL_SYSTEM_TIME); // NOLINT
205 
207 
213  RCLCPP_PUBLIC
214  double
215  seconds() const;
216 
218 
221  RCLCPP_PUBLIC
223  get_clock_type() const;
224 
225 private:
226  rcl_time_point_t rcl_time_;
227  friend Clock; // Allow clock to manipulate internal data
228 };
229 
233 RCLCPP_PUBLIC
234 Time
235 operator+(const rclcpp::Duration & lhs, const rclcpp::Time & rhs);
236 
238 
242 RCLCPP_PUBLIC
243 builtin_interfaces::msg::Time
245 
246 } // namespace rclcpp
247 
248 #endif // RCLCPP__TIME_HPP_
RCLCPP_PUBLIC Time & operator-=(const rclcpp::Duration &rhs)
Definition: time.cpp:257
RCLCPP_PUBLIC Time(const Time &rhs)
Copy constructor.
RCLCPP_PUBLIC Time & operator+=(const rclcpp::Duration &rhs)
Definition: time.cpp:242
RCLCPP_PUBLIC Time(Time &&rhs) noexcept
Move constructor.
RCLCPP_PUBLIC bool operator>=(const rclcpp::Time &rhs) const
Definition: time.cpp:146
RCLCPP_PUBLIC double seconds() const
Get the seconds since epoch.
Definition: time.cpp:218
virtual RCLCPP_PUBLIC ~Time()
Time destructor.
RCLCPP_PUBLIC Duration operator-(const rclcpp::Time &rhs) const
Definition: time.cpp:178
RCLCPP_PUBLIC rcl_time_point_value_t nanoseconds() const
Get the nanoseconds since epoch.
Definition: time.cpp:212
RCLCPP_PUBLIC Time & operator=(Time &&rhs) noexcept
RCLCPP_PUBLIC bool operator<(const rclcpp::Time &rhs) const
Definition: time.cpp:126
RCLCPP_PUBLIC Time & operator=(const Time &rhs)
RCLCPP_PUBLIC rcl_clock_type_t get_clock_type() const
Get the clock type.
Definition: time.cpp:224
RCLCPP_PUBLIC bool operator<=(const rclcpp::Time &rhs) const
Definition: time.cpp:136
static RCLCPP_PUBLIC Time max(rcl_clock_type_t clock_type=RCL_SYSTEM_TIME)
Get the maximum representable value.
Definition: time.cpp:272
RCLCPP_PUBLIC bool operator==(const rclcpp::Time &rhs) const
Definition: time.cpp:110
RCLCPP_PUBLIC Time operator+(const rclcpp::Duration &rhs) const
Definition: time.cpp:166
RCLCPP_PUBLIC bool operator>(const rclcpp::Time &rhs) const
Definition: time.cpp:156
RCLCPP_PUBLIC Time(int32_t seconds, uint32_t nanoseconds, rcl_clock_type_t clock_type=RCL_SYSTEM_TIME)
Time constructor.
Definition: time.cpp:49
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
RCLCPP_PUBLIC builtin_interfaces::msg::Time convert_rcl_time_to_sec_nanos(const rcl_time_point_value_t &time_point)
Convert rcl_time_point_value_t to builtin_interfaces::msg::Time.
Definition: time.cpp:278
A single point in time, measured in nanoseconds, the reference point is based on the source.
Definition: time.h:156
enum rcl_clock_type_e rcl_clock_type_t
Time source type, used to indicate the source of a time measurement.
rcutils_time_point_value_t rcl_time_point_value_t
A single point in time, measured in nanoseconds since the Unix epoch.
Definition: time.h:46
@ RCL_ROS_TIME
Use ROS time.
Definition: time.h:66
@ RCL_SYSTEM_TIME
Use system time.
Definition: time.h:68