#include <time.hpp>
◆ Time() [1/5]
Time constructor.
Initializes the time values for seconds and nanoseconds individually. Large values for nanoseconds are wrapped automatically with the remainder added to seconds. Both inputs must be integers.
- Parameters
-
seconds | part of the time in seconds since time epoch |
nanoseconds | part of the time in nanoseconds since time epoch |
clock_type | clock type |
- Exceptions
-
◆ Time() [2/5]
Time constructor.
- Parameters
-
nanoseconds | since time epoch |
clock_type | clock type |
◆ Time() [3/5]
rclcpp::Time::Time |
( |
const Time & |
rhs | ) |
|
◆ Time() [4/5]
Time constructor.
- Parameters
-
time_msg | builtin_interfaces time message to copy |
clock_type | clock type |
- Exceptions
-
◆ Time() [5/5]
Time constructor.
- Parameters
-
◆ ~Time()
virtual rclcpp::Time::~Time |
( |
| ) |
|
|
virtual |
◆ operator builtin_interfaces::msg::Time()
rclcpp::Time::operator builtin_interfaces::msg::Time |
( |
| ) |
const |
Return a builtin_interfaces::msg::Time object based.
◆ operator=() [1/2]
Time& rclcpp::Time::operator= |
( |
const Time & |
rhs | ) |
|
◆ operator=() [2/2]
Time& rclcpp::Time::operator= |
( |
const builtin_interfaces::msg::Time & |
time_msg | ) |
|
Assign Time from a builtin_interfaces::msg::Time instance. The clock_type will be reset to RCL_ROS_TIME. Equivalent to *this = Time(time_msg, RCL_ROS_TIME).
- Exceptions
-
◆ operator==()
bool rclcpp::Time::operator== |
( |
const rclcpp::Time & |
rhs | ) |
const |
◆ operator!=()
bool rclcpp::Time::operator!= |
( |
const rclcpp::Time & |
rhs | ) |
const |
◆ operator<()
bool rclcpp::Time::operator< |
( |
const rclcpp::Time & |
rhs | ) |
const |
◆ operator<=()
bool rclcpp::Time::operator<= |
( |
const rclcpp::Time & |
rhs | ) |
const |
◆ operator>=()
bool rclcpp::Time::operator>= |
( |
const rclcpp::Time & |
rhs | ) |
const |
◆ operator>()
bool rclcpp::Time::operator> |
( |
const rclcpp::Time & |
rhs | ) |
const |
◆ operator+()
◆ operator-() [1/2]
◆ operator-() [2/2]
◆ operator+=()
◆ operator-=()
◆ nanoseconds()
Get the nanoseconds since epoch.
- Returns
- the nanoseconds since epoch as a rcl_time_point_value_t structure.
◆ max()
static Time rclcpp::Time::max |
( |
| ) |
|
|
static |
Get the maximum representable value.
- Returns
- the maximum representable value
◆ seconds()
double rclcpp::Time::seconds |
( |
| ) |
const |
Get the seconds since epoch.
- Warning
- Depending on sizeof(double) there could be significant precision loss. When an exact time is required use nanoseconds() instead.
- Returns
- the seconds since epoch as a floating point number.
◆ get_clock_type()
Get the clock type.
- Returns
- the clock type
The documentation for this class was generated from the following file: