rclcpp
rclcpp copied to clipboard
Clarify rate names and introduce SteadyRate
Not sure if this is the best place to start a discussion, but this PR might result in some discussion anyway.
- So far
rclcpp::WallRatehas been based onstd::chrono::steady_clock. - In ROS1,
ros::WallRateis based onros::WallTime, which ends up usingclock_gettime(CLOCK_REALTIME, [..])to get time, which returns the wall time (including time jumps and slew).
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:
WallRateshould usesystem_clockinstead ofsteady_clock, to be consistent with the ROS1 behavior.SteadyRateis introduced forsteady_clock.- I've made Rate an alias for
WallRate, to not change it's behavior, i.e. make it usesystem_clock. Personally I see only very limited use for aRatebased onsystem_clock, so I would fine havingRatebe an alias forSteadyRateinstead. On another note: maybe it should become based on ROS time in caseuse_sime_timeis enabled?
* 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 .
* 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
rclcppAPIs, those respectuse_sim_time(otherwise, they could just usestdAPIs 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 thesteady_clockorsystem_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.
An overview of clock sources for
rclcpp::Rateand 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::SteadyRateshould switch to/clockas well in caseuse_sim_timeis 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.
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.