[ros-users] [Discourse.ros.org] [Next Generation ROS] ROS 2 Time vs std::chrono

William Woodall ros.discourse at gmail.com
Wed Oct 10 01:54:54 UTC 2018



So this is where my expectation for ROS Time and what is actually implemented right now has diverged.

My expectation is that ROS Time would not be able to store or provide Steady time, and instead that would be a separate type or just be `std::chrono::steady_clock` instead.

I did bring up this issue at the time, but I think the refactor to address my concerns was tabled for later, but unfortunately I don't see an issue on `ros2/rclcpp` tracking the problem either. @tfoote do you know if this is tracked somewhere? Perhaps on a meta issue or something?

Either way it is stated this way in the design document:

> `SteadyTime`  will be typed differently than the interchangable  `SystemTime`  and  `ROSTime` . This is because SystemTime and ROSTime have a common base class with runtime checks that they are valid to compare against each other. However SteadyTime is never comparable to SystemTime or ROSTime so it would actually have a separate implementation of the same API. Thus you could get protection from misusing them at compile time (in compiled languages) instead of only catching it at runtime.

-- from: https://design.ros2.org/articles/clock_and_time.html#implementation

----

If you assume that this change is made, then ROS Time (i.e. `rclcpp::Time`) can only either be from the system time or from a custom time source. However, the custom time source must provide a time that is "compatible" with system time. For me that means it uses the same epoch (i.e. unix epoch) and it follows the same behaviors like handling leap seconds. Put another way a time stamp from system time and the same timestamp from a custom time source should match when converted to a date time (yyyy-mm-dd-...).

So with that assumption, the conversion function would look like this:

```c++
std::chrono::system_clock::time_point
to_time_point(const rclcpp::Time & time)
{
  return std::chrono::system_clock::time_point(std::chrono::nanoseconds(time.nanoseconds()));
}
```





---
[Visit Topic](https://discourse.ros.org/t/ros-2-time-vs-std-chrono/6293/10) or reply to this email to respond.




More information about the ros-users mailing list