Class Time

Class Documentation

class Time

Public Functions

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

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

Throws:

std::runtime_error – if seconds are negative

explicit Time(int64_t nanoseconds = 0, rcl_clock_type_t clock_type = RCL_SYSTEM_TIME)

Time constructor.

Parameters:
  • nanoseconds – since time epoch

  • clock_type – clock type

Time(const Time &rhs)

Copy constructor.

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

Time constructor.

Parameters:
  • time_msg – builtin_interfaces time message to copy

  • clock_type – clock type

Throws:

std::runtime_error – if seconds are negative

explicit Time(const rcl_time_point_t &time_point)

Time constructor.

Parameters:

time_point – rcl_time_point_t structure to copy

virtual ~Time()

Time destructor.

operator builtin_interfaces::msg::Time() const

Return a builtin_interfaces::msg::Time object based.

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

std::runtime_error – if seconds are negative

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

Throws:

std::runtime_error – if seconds are negative

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

std::runtime_error – if the time sources are different

bool operator!=(const rclcpp::Time &rhs) const
bool operator<(const rclcpp::Time &rhs) const
Throws:

std::runtime_error – if the time sources are different

bool operator<=(const rclcpp::Time &rhs) const
Throws:

std::runtime_error – if the time sources are different

bool operator>=(const rclcpp::Time &rhs) const
Throws:

std::runtime_error – if the time sources are different

bool operator>(const rclcpp::Time &rhs) const
Throws:

std::runtime_error – if the time sources are different

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

std::overflow_error – if addition leads to overflow

Duration operator-(const rclcpp::Time &rhs) const
Throws:
  • std::runtime_error – if the time sources are different

  • std::overflow_error – if addition leads to overflow

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

std::overflow_error – if addition leads to overflow

Time &operator+=(const rclcpp::Duration &rhs)
Throws:

std::overflow_error – if addition leads to overflow

Time &operator-=(const rclcpp::Duration &rhs)
Throws:

std::overflow_error – if addition leads to overflow

rcl_time_point_value_t nanoseconds() const

Get the nanoseconds since epoch.

Returns:

the nanoseconds since epoch as a rcl_time_point_value_t structure.

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

rcl_clock_type_t get_clock_type() const

Get the clock type.

Returns:

the clock type

Public Static Functions

static Time max()

Get the maximum representable value.

Returns:

the maximum representable value