rclpy.time module
- class rclpy.time.Time(*, seconds: int | float = 0, nanoseconds: int = 0, clock_type: ClockType = rpyutils.import_c_library.ClockType.SYSTEM_TIME)
Bases:
object
Represents a point in time.
A
Time
object is the combination of a duration since an epoch, and a clock type.Time
objects are only comparable with other time points from the same type of clock.- classmethod from_msg(msg: builtin_interfaces.msg.Time, clock_type: ClockType = rpyutils.import_c_library.ClockType.ROS_TIME) Time
Create a
Time
instance from a ROS message.- Parameters:
msg (builtin_interfaces.msg.Time) – the message instance to convert.
- Return type:
- property nanoseconds: int
- Returns:
the total number of nanoseconds since the clock’s epoch.
- seconds_nanoseconds() Tuple[int, int]
Get time separated into seconds and nanoseconds components.
- Returns:
2-tuple seconds and nanoseconds
- to_msg() builtin_interfaces.msg.Time
Create a ROS message instance from a
Time
object.- Return type:
builtin_interfaces.msg.Time