rclcpp icon indicating copy to clipboard operation
rclcpp copied to clipboard

Clarify rate names and introduce SteadyRate

Open mbuijs opened this issue 4 years ago • 4 comments

Not sure if this is the best place to start a discussion, but this PR might result in some discussion anyway.

To me the name WallRate is misleading, since it's not actually using the wall time, but a clock that is typically not related to wall time at all. On top of that, it has different semantics than what it used to be in ROS1.

My suggestion is to change the names of the specific Rate like this:

  • WallRate should use system_clock instead of steady_clock, to be consistent with the ROS1 behavior.
  • SteadyRate is introduced for steady_clock.
  • I've made Rate an alias for WallRate, to not change it's behavior, i.e. make it use system_clock. Personally I see only very limited use for a Rate based on system_clock, so I would fine having Rate be an alias for SteadyRate instead. On another note: maybe it should become based on ROS time in case use_sime_time is enabled?

mbuijs avatar Oct 05 '20 11:10 mbuijs

* On another note: maybe it should become based on ROS time in case `use_sime_time` is enabled?

Yeah, this is exactly what I think. For the most part, I think people's expectation is that when they use the rclcpp APIs, those respect use_sim_time (otherwise, they could just use std APIs instead). So I really think the default here should be to use ROS time, and then have some other way (parameter, another API) to request time based on the steady_clock or system_clock.

We did have a bit of a discussion about this in another ticket: https://github.com/ros2/rclcpp/issues/1248 .

clalancette avatar Oct 05 '20 12:10 clalancette

* On another note: maybe it should become based on ROS time in case `use_sime_time` is enabled?

Yeah, this is exactly what I think. For the most part, I think people's expectation is that when they use the rclcpp APIs, those respect use_sim_time (otherwise, they could just use std APIs instead). So I really think the default here should be to use ROS time, and then have some other way (parameter, another API) to request time based on the steady_clock or system_clock.

We did have a bit of a discussion about this in another ticket: #1248 .

I agree on that the default for rclcpp::Rate should be ROS time. Currently I can't really see the amount of work required to make that happen, let me see if I can find some time to get an overview of that in within the coming week.

An overview of clock sources for rclcpp::Rate and it's specializations:

Type !use_sime_time use_sime_time
rclcpp::Rate std::chrono::system_clock /clock
rclcpp::WallRate std::chrono::system_clock std::chrono::system_clock
rclcpp::SteadyRate std::chrono::steady_clock std::chrono::steady_clock

If wonder if rclcpp::SteadyRate should switch to /clock as well in case use_sim_time is enabled.

mbuijs avatar Oct 07 '20 06:10 mbuijs

An overview of clock sources for rclcpp::Rate and it's specializations:

Honestly, I might rename rclcpp::Rate to rclcpp::ROSRate just to be totally clear that it is using the ROSClock underneath (this would need a deprecation cycle as well).

If wonder if rclcpp::SteadyRate should switch to /clock as well in case use_sim_time is enabled.

I personally wouldn't do this, especially if we rename Rate -> ROSRate. That is, by default users would be directed to using ROSRate, and in special cases where they really want to use WallRate or SteadyTime, the functionality exists as expected.

clalancette avatar Oct 07 '20 14:10 clalancette

As far as I see, the easiest way to make ROSRate use the ROSClock is to use rclcpp::Clock. I extended the pull request with a ROSRate class that does that. As a consequence this class now requires a rclcpp::Clock::SharedPtr to be constructed.

Compared to GenericRate based classes the dependency on rclcpp::Clock makes the use of ROSRate a bit harder since a (spinning) rclcpp::Node is required to make it work.

I have not created unit tests for this class yet, as I'm not sure on what is the best approach on updating the rclcpp::Clock when using the ROSClock in the test. Before looking into that, I would appreciate feedback on the direction this is going.

mbuijs avatar Jan 07 '21 10:01 mbuijs