rclcpp  master
C++ ROS Client Library API
Public Member Functions | Static Public Member Functions | List of all members
rclcpp::Duration Class Reference

#include <duration.hpp>

Public Member Functions

 Duration (int32_t seconds, uint32_t nanoseconds)
 Duration constructor. More...
 
 Duration (rcl_duration_value_t nanoseconds)
 
 Duration (std::chrono::nanoseconds nanoseconds)
 
template<class Rep , class Period >
 Duration (const std::chrono::duration< Rep, Period > &duration)
 
 Duration (const builtin_interfaces::msg::Duration &duration_msg)
 
 Duration (const rcl_duration_t &duration)
 Time constructor. More...
 
 Duration (const Duration &rhs)
 
virtual ~Duration ()=default
 
 operator builtin_interfaces::msg::Duration () const
 
Durationoperator= (const Duration &rhs)
 
Durationoperator= (const builtin_interfaces::msg::Duration &duration_msg)
 
bool operator== (const rclcpp::Duration &rhs) const
 
bool operator!= (const rclcpp::Duration &rhs) const
 
bool operator< (const rclcpp::Duration &rhs) const
 
bool operator<= (const rclcpp::Duration &rhs) const
 
bool operator>= (const rclcpp::Duration &rhs) const
 
bool operator> (const rclcpp::Duration &rhs) const
 
Duration operator+ (const rclcpp::Duration &rhs) const
 
Duration operator- (const rclcpp::Duration &rhs) const
 
Duration operator* (double scale) const
 
rcl_duration_value_t nanoseconds () const
 Get duration in nanosecods. More...
 
double seconds () const
 Get duration in seconds. More...
 
template<class DurationT >
DurationT to_chrono () const
 Convert Duration into a std::chrono::Duration. More...
 
rmw_time_t to_rmw_time () const
 Convert Duration into rmw_time_t. More...
 

Static Public Member Functions

static Duration max ()
 Get the maximum representable value. More...
 
static Duration from_seconds (double seconds)
 Create a duration object from a floating point number representing seconds. More...
 

Constructor & Destructor Documentation

◆ 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
secondstime in seconds
nanosecondstime in nanoseconds

◆ Duration() [2/7]

rclcpp::Duration::Duration ( rcl_duration_value_t  nanoseconds)
explicit

◆ Duration() [3/7]

rclcpp::Duration::Duration ( std::chrono::nanoseconds  nanoseconds)
explicit

◆ Duration() [4/7]

template<class Rep , class Period >
rclcpp::Duration::Duration ( const std::chrono::duration< Rep, Period > &  duration)
inline

◆ Duration() [5/7]

rclcpp::Duration::Duration ( const builtin_interfaces::msg::Duration &  duration_msg)

◆ Duration() [6/7]

rclcpp::Duration::Duration ( const rcl_duration_t duration)
explicit

Time constructor.

Parameters
durationrcl_duration_t structure to copy.

◆ Duration() [7/7]

rclcpp::Duration::Duration ( const Duration rhs)

◆ ~Duration()

virtual rclcpp::Duration::~Duration ( )
virtualdefault

Member Function Documentation

◆ operator builtin_interfaces::msg::Duration()

rclcpp::Duration::operator builtin_interfaces::msg::Duration ( ) const

◆ operator=() [1/2]

Duration& rclcpp::Duration::operator= ( const Duration rhs)

◆ operator=() [2/2]

Duration& rclcpp::Duration::operator= ( const builtin_interfaces::msg::Duration &  duration_msg)

◆ operator==()

bool rclcpp::Duration::operator== ( const rclcpp::Duration rhs) const

◆ operator!=()

bool rclcpp::Duration::operator!= ( const rclcpp::Duration rhs) const

◆ operator<()

bool rclcpp::Duration::operator< ( const rclcpp::Duration rhs) const

◆ operator<=()

bool rclcpp::Duration::operator<= ( const rclcpp::Duration rhs) const

◆ operator>=()

bool rclcpp::Duration::operator>= ( const rclcpp::Duration rhs) const

◆ operator>()

bool rclcpp::Duration::operator> ( const rclcpp::Duration rhs) const

◆ operator+()

Duration rclcpp::Duration::operator+ ( const rclcpp::Duration rhs) const

◆ operator-()

Duration rclcpp::Duration::operator- ( const rclcpp::Duration rhs) const

◆ 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()

rcl_duration_value_t rclcpp::Duration::nanoseconds ( ) const

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.

◆ 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

Convert Duration into rmw_time_t.


The documentation for this class was generated from the following file: