ROS 2 rclcpp + rcl - jazzy  jazzy
ROS 2 C++ Client Library with ROS Client Library
Public Member Functions | Static Public Member Functions | List of all members
rclcpp::Duration Class Reference

Public Member Functions

 Duration (int32_t seconds, uint32_t nanoseconds)
 Duration constructor. More...
 
 Duration (std::chrono::nanoseconds nanoseconds)
 Construct duration from the specified std::chrono::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)
 
 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
 
Durationoperator+= (const rclcpp::Duration &rhs)
 
Duration operator- (const rclcpp::Duration &rhs) const
 
Durationoperator-= (const rclcpp::Duration &rhs)
 
Duration operator* (double scale) const
 
Durationoperator*= (double scale)
 
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.
 
rmw_time_t to_rmw_time () const
 Convert Duration into rmw_time_t.
 

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.
 
static Duration from_nanoseconds (rcl_duration_value_t nanoseconds)
 Create a duration object from an integer number representing nanoseconds.
 
static Duration from_rmw_time (rmw_time_t duration)
 

Detailed Description

Definition at line 27 of file duration.hpp.

Constructor & Destructor Documentation

◆ Duration() [1/2]

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

Definition at line 36 of file duration.cpp.

References rcl_duration_s::nanoseconds, nanoseconds(), RCL_S_TO_NS, and seconds().

Here is the call graph for this function:

◆ Duration() [2/2]

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

Time constructor.

Parameters
durationrcl_duration_t structure to copy.

Definition at line 57 of file duration.cpp.

Member Function Documentation

◆ max()

Duration rclcpp::Duration::max ( )
static

Get the maximum representable value.

Returns
the maximum representable value

Definition at line 255 of file duration.cpp.

◆ nanoseconds()

rcl_duration_value_t rclcpp::Duration::nanoseconds ( ) const

Get duration in nanosecods.

Returns
the duration in nanoseconds as a rcl_duration_value_t.

Definition at line 249 of file duration.cpp.

References rcl_duration_s::nanoseconds.

Referenced by Duration(), from_nanoseconds(), rclcpp::operator+(), rclcpp::Time::operator+(), rclcpp::Time::operator+=(), rclcpp::Time::operator-(), rclcpp::Time::operator-=(), and rclcpp::Clock::sleep_until().

Here is the caller graph for this function:

◆ 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.

Definition at line 261 of file duration.cpp.

References rcl_duration_s::nanoseconds.

Referenced by Duration(), and from_seconds().

Here is the caller graph for this function:

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