ROS 2 rclcpp + rcl - rolling  rolling-a919a6e5
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 
54  RCLCPP_PUBLIC
55  explicit Time(int64_t nanoseconds = 0, rcl_clock_type_t clock_type = RCL_SYSTEM_TIME);
56 
58  RCLCPP_PUBLIC
59  Time(const Time & rhs);
60 
62  RCLCPP_PUBLIC
63  Time(Time && rhs) noexcept;
64 
66 
71  RCLCPP_PUBLIC
72  Time(
73  const builtin_interfaces::msg::Time & time_msg,
74  rcl_clock_type_t clock_type = RCL_ROS_TIME);
75 
77 
80  RCLCPP_PUBLIC
81  explicit Time(const rcl_time_point_t & time_point);
82 
84  RCLCPP_PUBLIC
85  virtual ~Time();
86 
88  RCLCPP_PUBLIC
89  operator builtin_interfaces::msg::Time() const;
90 
95  RCLCPP_PUBLIC
96  Time &
97  operator=(const Time & rhs);
98 
105  RCLCPP_PUBLIC
106  Time &
107  operator=(const builtin_interfaces::msg::Time & time_msg);
108 
112  RCLCPP_PUBLIC
113  Time &
114  operator=(Time && rhs) noexcept;
115 
119  RCLCPP_PUBLIC
120  bool
121  operator==(const rclcpp::Time & rhs) const;
122 
123  RCLCPP_PUBLIC
124  bool
125  operator!=(const rclcpp::Time & rhs) const;
126 
130  RCLCPP_PUBLIC
131  bool
132  operator<(const rclcpp::Time & rhs) const;
133 
137  RCLCPP_PUBLIC
138  bool
139  operator<=(const rclcpp::Time & rhs) const;
140 
144  RCLCPP_PUBLIC
145  bool
146  operator>=(const rclcpp::Time & rhs) const;
147 
151  RCLCPP_PUBLIC
152  bool
153  operator>(const rclcpp::Time & rhs) const;
154 
158  RCLCPP_PUBLIC
159  Time
160  operator+(const rclcpp::Duration & rhs) const;
161 
166  RCLCPP_PUBLIC
167  Duration
168  operator-(const rclcpp::Time & rhs) const;
169 
173  RCLCPP_PUBLIC
174  Time
175  operator-(const rclcpp::Duration & rhs) const;
176 
180  RCLCPP_PUBLIC
181  Time &
182  operator+=(const rclcpp::Duration & rhs);
183 
187  RCLCPP_PUBLIC
188  Time &
189  operator-=(const rclcpp::Duration & rhs);
190 
192 
195  RCLCPP_PUBLIC
197  nanoseconds() const;
198 
200 
203  RCLCPP_PUBLIC
204  static Time
205  max(rcl_clock_type_t clock_type = RCL_SYSTEM_TIME); // NOLINT
206 
208 
214  RCLCPP_PUBLIC
215  double
216  seconds() const;
217 
219 
222  RCLCPP_PUBLIC
224  get_clock_type() const;
225 
226 private:
227  rcl_time_point_t rcl_time_;
228  friend Clock; // Allow clock to manipulate internal data
229 };
230 
234 RCLCPP_PUBLIC
235 Time
236 operator+(const rclcpp::Duration & lhs, const rclcpp::Time & rhs);
237 
239 
243 RCLCPP_PUBLIC
244 builtin_interfaces::msg::Time
246 
247 } // namespace rclcpp
248 
249 #endif // RCLCPP__TIME_HPP_
RCLCPP_PUBLIC Time & operator-=(const rclcpp::Duration &rhs)
Definition: time.cpp:264
RCLCPP_PUBLIC Time(const Time &rhs)
Copy constructor.
RCLCPP_PUBLIC Time & operator+=(const rclcpp::Duration &rhs)
Definition: time.cpp:246
RCLCPP_PUBLIC Time(Time &&rhs) noexcept
Move constructor.
RCLCPP_PUBLIC bool operator>=(const rclcpp::Time &rhs) const
Definition: time.cpp:150
RCLCPP_PUBLIC double seconds() const
Get the seconds since epoch.
Definition: time.cpp:222
virtual RCLCPP_PUBLIC ~Time()
Time destructor.
RCLCPP_PUBLIC Duration operator-(const rclcpp::Time &rhs) const
Definition: time.cpp:182
RCLCPP_PUBLIC rcl_time_point_value_t nanoseconds() const
Get the nanoseconds since epoch.
Definition: time.cpp:216
RCLCPP_PUBLIC Time & operator=(Time &&rhs) noexcept
RCLCPP_PUBLIC bool operator<(const rclcpp::Time &rhs) const
Definition: time.cpp:130
RCLCPP_PUBLIC Time & operator=(const Time &rhs)
RCLCPP_PUBLIC rcl_clock_type_t get_clock_type() const
Get the clock type.
Definition: time.cpp:228
RCLCPP_PUBLIC bool operator<=(const rclcpp::Time &rhs) const
Definition: time.cpp:140
static RCLCPP_PUBLIC Time max(rcl_clock_type_t clock_type=RCL_SYSTEM_TIME)
Get the maximum representable value.
Definition: time.cpp:282
RCLCPP_PUBLIC bool operator==(const rclcpp::Time &rhs) const
Definition: time.cpp:114
RCLCPP_PUBLIC Time operator+(const rclcpp::Duration &rhs) const
Definition: time.cpp:170
RCLCPP_PUBLIC bool operator>(const rclcpp::Time &rhs) const
Definition: time.cpp:160
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:288
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