forked from ros2/rclcpp
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathtime.hpp
More file actions
130 lines (97 loc) · 2.79 KB
/
time.hpp
File metadata and controls
130 lines (97 loc) · 2.79 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
// Copyright 2017 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP__TIME_HPP_
#define RCLCPP__TIME_HPP_
#include "builtin_interfaces/msg/time.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rcl/time.h"
#include "rclcpp/duration.hpp"
namespace rclcpp
{
class Clock;
class Time
{
public:
RCLCPP_PUBLIC
Time(int32_t seconds, uint32_t nanoseconds, rcl_clock_type_t clock_type = RCL_SYSTEM_TIME);
RCLCPP_PUBLIC
explicit Time(int64_t nanoseconds = 0, rcl_clock_type_t clock = RCL_SYSTEM_TIME);
RCLCPP_PUBLIC
Time(const Time & rhs);
RCLCPP_PUBLIC
Time(
const builtin_interfaces::msg::Time & time_msg,
rcl_clock_type_t ros_time = RCL_ROS_TIME);
RCLCPP_PUBLIC
explicit Time(const rcl_time_point_t & time_point);
RCLCPP_PUBLIC
virtual ~Time();
RCLCPP_PUBLIC
operator builtin_interfaces::msg::Time() const;
RCLCPP_PUBLIC
Time &
operator=(const Time & rhs);
RCLCPP_PUBLIC
Time &
operator=(const builtin_interfaces::msg::Time & time_msg);
RCLCPP_PUBLIC
bool
operator==(const rclcpp::Time & rhs) const;
RCLCPP_PUBLIC
bool
operator!=(const rclcpp::Time & rhs) const;
RCLCPP_PUBLIC
bool
operator<(const rclcpp::Time & rhs) const;
RCLCPP_PUBLIC
bool
operator<=(const rclcpp::Time & rhs) const;
RCLCPP_PUBLIC
bool
operator>=(const rclcpp::Time & rhs) const;
RCLCPP_PUBLIC
bool
operator>(const rclcpp::Time & rhs) const;
RCLCPP_PUBLIC
Time
operator+(const rclcpp::Duration & rhs) const;
RCLCPP_PUBLIC
Duration
operator-(const rclcpp::Time & rhs) const;
RCLCPP_PUBLIC
Time
operator-(const rclcpp::Duration & rhs) const;
RCLCPP_PUBLIC
rcl_time_point_value_t
nanoseconds() const;
RCLCPP_PUBLIC
static Time
max();
/// \return the seconds since epoch as a floating point number.
/// \warning Depending on sizeof(double) there could be significant precision loss.
/// When an exact time is required use nanoseconds() instead.
RCLCPP_PUBLIC
double
seconds() const;
RCLCPP_PUBLIC
rcl_clock_type_t
get_clock_type() const;
private:
rcl_time_point_t rcl_time_;
friend Clock; // Allow clock to manipulate internal data
};
Time
operator+(const rclcpp::Duration & lhs, const rclcpp::Time & rhs);
} // namespace rclcpp
#endif // RCLCPP__TIME_HPP_