#include <duration.hpp>
◆ Duration() [1/7]
rclcpp::Duration::Duration |
( |
int32_t |
seconds, |
|
|
uint32_t |
nanoseconds |
|
) |
| |
Duration constructor.
Initializes the time values for seconds and nanoseconds individually. Large values for nsecs are wrapped automatically with the remainder added to secs. Both inputs must be integers. Seconds can be negative.
- Parameters
-
seconds | time in seconds |
nanoseconds | time in nanoseconds |
◆ Duration() [2/7]
Construct duration from the specified nanoseconds.
◆ Duration() [3/7]
◆ Duration() [4/7]
template<class Rep , class Period >
◆ Duration() [5/7]
rclcpp::Duration::Duration |
( |
const builtin_interfaces::msg::Duration & |
duration_msg | ) |
|
◆ Duration() [6/7]
Time constructor.
- Parameters
-
◆ Duration() [7/7]
rclcpp::Duration::Duration |
( |
const Duration & |
rhs | ) |
|
◆ ~Duration()
virtual rclcpp::Duration::~Duration |
( |
| ) |
|
|
virtualdefault |
◆ operator builtin_interfaces::msg::Duration()
rclcpp::Duration::operator builtin_interfaces::msg::Duration |
( |
| ) |
const |
◆ operator=() [1/2]
◆ operator=() [2/2]
Duration& rclcpp::Duration::operator= |
( |
const builtin_interfaces::msg::Duration & |
duration_msg | ) |
|
◆ operator==()
◆ operator!=()
◆ operator<()
◆ operator<=()
◆ operator>=()
◆ operator>()
◆ operator+()
◆ operator-()
◆ max()
static Duration rclcpp::Duration::max |
( |
| ) |
|
|
static |
Get the maximum representable value.
- Returns
- the maximum representable value
◆ operator*()
Duration rclcpp::Duration::operator* |
( |
double |
scale | ) |
const |
◆ nanoseconds()
Get duration in nanosecods.
- Returns
- the duration in nanoseconds as a rcl_duration_value_t.
◆ seconds()
double rclcpp::Duration::seconds |
( |
| ) |
const |
Get duration in seconds.
- Warning
- Depending on sizeof(double) there could be significant precision loss. When an exact time is required use nanoseconds() instead.
- Returns
- the duration in seconds as a floating point number.
◆ from_seconds()
static Duration rclcpp::Duration::from_seconds |
( |
double |
seconds | ) |
|
|
static |
Create a duration object from a floating point number representing seconds.
◆ from_nanoseconds()
Create a duration object from an integer number representing nanoseconds.
◆ from_rmw_time()
◆ to_chrono()
template<class DurationT >
DurationT rclcpp::Duration::to_chrono |
( |
| ) |
const |
|
inline |
Convert Duration into a std::chrono::Duration.
◆ to_rmw_time()
rmw_time_t rclcpp::Duration::to_rmw_time |
( |
| ) |
const |
The documentation for this class was generated from the following file: