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

#include <time.hpp>

Public Member Functions

 Time (int32_t seconds, uint32_t nanoseconds, rcl_clock_type_t clock_type=RCL_SYSTEM_TIME)
 
 Time (int64_t nanoseconds=0, rcl_clock_type_t clock=RCL_SYSTEM_TIME)
 
 Time (const Time &rhs)
 
 Time (const builtin_interfaces::msg::Time &time_msg, rcl_clock_type_t ros_time=RCL_ROS_TIME)
 
 Time (const rcl_time_point_t &time_point)
 
virtual ~Time ()
 
 operator builtin_interfaces::msg::Time () const
 
Timeoperator= (const Time &rhs)
 
Timeoperator= (const builtin_interfaces::msg::Time &time_msg)
 
bool operator== (const rclcpp::Time &rhs) const
 
bool operator!= (const rclcpp::Time &rhs) const
 
bool operator< (const rclcpp::Time &rhs) const
 
bool operator<= (const rclcpp::Time &rhs) const
 
bool operator>= (const rclcpp::Time &rhs) const
 
bool operator> (const rclcpp::Time &rhs) const
 
Time operator+ (const rclcpp::Duration &rhs) const
 
Duration operator- (const rclcpp::Time &rhs) const
 
Time operator- (const rclcpp::Duration &rhs) const
 
rcl_time_point_value_t nanoseconds () const
 
double seconds () const
 
rcl_clock_type_t get_clock_type () const
 

Static Public Member Functions

static Time max ()
 

Constructor & Destructor Documentation

◆ Time() [1/5]

rclcpp::Time::Time ( int32_t  seconds,
uint32_t  nanoseconds,
rcl_clock_type_t  clock_type = RCL_SYSTEM_TIME 
)

◆ Time() [2/5]

rclcpp::Time::Time ( int64_t  nanoseconds = 0,
rcl_clock_type_t  clock = RCL_SYSTEM_TIME 
)
explicit

◆ Time() [3/5]

rclcpp::Time::Time ( const Time rhs)

◆ Time() [4/5]

rclcpp::Time::Time ( const builtin_interfaces::msg::Time &  time_msg,
rcl_clock_type_t  ros_time = RCL_ROS_TIME 
)

◆ Time() [5/5]

rclcpp::Time::Time ( const rcl_time_point_t time_point)
explicit

◆ ~Time()

virtual rclcpp::Time::~Time ( )
virtual

Member Function Documentation

◆ operator builtin_interfaces::msg::Time()

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

◆ operator=() [1/2]

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

◆ operator=() [2/2]

Time& rclcpp::Time::operator= ( const builtin_interfaces::msg::Time &  time_msg)

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

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

◆ operator-() [1/2]

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

◆ operator-() [2/2]

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

◆ nanoseconds()

rcl_time_point_value_t rclcpp::Time::nanoseconds ( ) const

◆ max()

static Time rclcpp::Time::max ( )
static

◆ seconds()

double rclcpp::Time::seconds ( ) const
Returns
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.

◆ get_clock_type()

rcl_clock_type_t rclcpp::Time::get_clock_type ( ) const

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