ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
8

ROS 2 time handling

asked 2018-04-09 00:43:52 -0500

KenYN gravatar image

In ROS 1 my node has code like this in a subscribed message callback:

ros::Time now = ros::Time::now();
ros::Duration frameSkip = ros::Duration(m_frameSyncMs/1000.0);

// Proceed if time interval has elapsed or if clock has gone backwards
if (m_previousTimeStamp + frameSkip > now)
// etc...

Basically, when m_frameSyncMs is 100 ms with the topic being a camera feed at 30 fps, just pick out every third frame or so. This works quite happily.

Now, for ROS 2 there no longer is a Time::now(), and looking at various web pages there might be a node clock, or there might be an rcl_get_time_point_now() but shouldn't that also take the result of rcl_get_default_ros_time()?

What is the best way to do this? Furthermore, where is the best place to learn about the latest ROS 2 developments; GitHub and Discord, for instance seem a bit too light on information, and reading the source might work, but the next beta may very well invalidate everything. Finally is there a ros2bag or equivalent for recording and playing back runs?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
10

answered 2018-04-09 00:56:58 -0500

William gravatar image

updated 2018-04-09 00:57:22 -0500

If you want the equivalent "ROS Time" as in ROS 1, e.g. might return wall clock time or simulated time (see https://wiki.ros.org/Clock#Using_Simu... ), then you need to call now() on a Node, see:

http://docs.ros2.org/ardent/api/rclcp...

The reason you need to get "now" from a node in ROS 2 is because unlike ROS 1, there's no global node singleton and the ROS time clock requires things like parameters and topics to implement sim time. So in ROS 2 you need to have a node to use ROS time.

If you only ever care about real time (no simulated time), then I suggest either using a custom made rclcpp::Clock, which defaults to "System time":

http://docs.ros2.org/ardent/api/rclcp...

Or give it an argument of RCL_STEADY_TIME to get monotonically increasing time.

You can also just use std::chrono::system_clock or std::chrono::steady_clock if you're not using ROS time:

http://en.cppreference.com/w/cpp/chro...

http://en.cppreference.com/w/cpp/chro...

edit flag offensive delete link more

Comments

Thanks for the quick reply! That's solved my immediate problem.

KenYN gravatar image KenYN  ( 2018-04-09 01:11:29 -0500 )edit

Has any of this changed in the past two years? (I'm on Eloquent on Ubuntu 18.04.) I found Intel's ros2 realsense source code, and have been using it as a bit of an example of how I might port to ros2. see here They create a rclcpp::Clock instance, then in the initializer list set that clock instance to RCL_ROS_TIME. I am understanding what they essentially did is take your second suggestion and substituted out "System time" for "ROS time". Is my understanding correct?

I'm trying to understand what the difference would be between doing something like what Intel did, versus using the Node now() method as in your first suggestion.

Thanks!

bbus gravatar image bbus  ( 2020-02-26 14:37:22 -0500 )edit

The approach in the realsense driver linked above does not associate a Time Source with the clock (which the node does for you) and as such it will never switch to simulated time. As this is a sensor driver that's likely not a use case that has come up. Note that you can also use get_clock() from the node and call now() on the initialized clock too.

tfoote gravatar image tfoote  ( 2020-02-28 15:55:32 -0500 )edit

Ok, so calling rclcpp::init generates a link to the "time source" in the backend code? Is there a way for me to link the ros time source manually?

Problem I'm having is that I'm attempting to port a ROS1 project that creates a nodehandle inside a library, and that nodehandle is used to create a timer inside the library. But, that library isn't a node itself. Maybe I've misunderstood other code, but I don't think we can have a ros2 nodehandle spawned out of the blue, without it being tied to an actual node, which is what the project devs originally did. I don't want to have to pass a nodehandle 3 layers into this library for two timers that can be paused with simulation time. I was attempting to create my own rclcpp::GenericTimer with this clock that I thought would be ...(more)

bbus gravatar image bbus  ( 2020-02-28 17:15:15 -0500 )edit

No the init does not do anything with a TimeSource that's only done by the Node initialization. In ROS 1 there was global state going on under the hood, but we've removed that in ROS 2. So you do need a Node to get a properly initialized clock. The clock cannot listen for the simulated time without a Node instance, (which is built into the Node so you don't have to do it yourself.)

tfoote gravatar image tfoote  ( 2020-02-28 17:22:50 -0500 )edit

I understand I don't have to do it myself, but is it technically possible to do myself?

Also, from reading the "Clock and Time" design article (https://design.ros2.org/articles/cloc...) I suspected that a randomly spawned clock, using rclcpp::Clock my_clock(RCL_ROS_TIME), in a source code file that isn't a node, would search for the /clock topic and use that, hence using the simulation time if I publish sim time to /clock somewhere else. From what you are saying, it sounds like this isn't the case, but that my_clock spawned in this manner does not look for/at /clock for knowledge of time. If this is correct, then great, I'm glad to be finally understanding. And that makes me wonder now, that would mean only Nodes know of topics, not instances of object types in rclcpp. I feel like I'm being very dense ...(more)

bbus gravatar image bbus  ( 2020-02-28 18:05:38 -0500 )edit

You're correct that only Nodes know about topics. The Clock object is just an object with no communication. It cannot "search for the /clock topic".

The default clock is just a clock object that does not know about any time source. If you attach a TimeSource such as our default one which listens to /clock and reads the use_sim_time parameter it will get updated based on that TimeSource if it's set to use RCL_ROS_TIME If it's a different type the TimeSource won't affect it.

tfoote gravatar image tfoote  ( 2020-02-28 18:29:53 -0500 )edit

Jumping in. As I understand with this answer that the default clock of a node listens to the /clock topic when use_sim_time is true, when is this clock updated? It seems that it would be frozen when any callback on the node is being served ? Which is a different behavior than when use_sim_time is false (the node clock being system time, it would node be frozen inside a callback)

doisyg gravatar image doisyg  ( 2021-02-03 04:29:59 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2018-04-09 00:43:52 -0500

Seen: 25,749 times

Last updated: Apr 09 '18