Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Clarify rate names and introduce SteadyRate #1373

Draft
wants to merge 3 commits into
base: rolling
Choose a base branch
from

Conversation

mbuijs
Copy link
Contributor

@mbuijs mbuijs commented Oct 5, 2020

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 mbuijs changed the title Clarify rate names and introducing SteadyRate Clarify rate names and introduce SteadyRate Oct 5, 2020
@clalancette
Copy link
Contributor

* 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 .

@mbuijs
Copy link
Contributor Author

mbuijs commented Oct 7, 2020

* 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.

@clalancette
Copy link
Contributor

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.

- WallRate now is based on system_clock instead of steady_clock
- SteadyRate is introduced for steady_clock
- Rate becomes an alias for WallRate for now (maybe should become based
on ROS time in case `use_sime_time` is enabled?)

WallRate in ROS1 was based on WallTime, which was based wall time
(including time jumps and slew), so this would be changing back to that.

Signed-off-by: Martijn Buijs <martijn.buijs@gmail.com>
Signed-off-by: Martijn Buijs <martijn.buijs@gmail.com>
Signed-off-by: Martijn Buijs <martijn.buijs@gmail.com>
@mbuijs
Copy link
Contributor Author

mbuijs commented Jan 7, 2021

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 mbuijs marked this pull request as draft January 7, 2021 10:14
@audrow audrow changed the base branch from master to rolling June 28, 2022 14:21
@clalancette clalancette mentioned this pull request Jan 18, 2023
}

virtual bool
sleep()
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I have a fundamental concern/worry is that we're conflating two concepts here. 

The rate object is a data storage which has an interval period and the last start time. 

The clock on the other hand is the thing that has a concept of time passing and keeps track of that. 

If you call XXXX.sleep() it has to be the thing that has a concept of time passing. Now we've gotten used to the ROS 1 Rate object being able to reach under the hood and grab the Node singleton and from that get the clock status and disambiguate sim time vs wall time and then give you an answer.  This implementation uses the original temporary rclcpp::sleep_for which was added before we had sim time and will not use that. 

However we've separated out these many layers so we now actually have a separate clock concept. And we could require that you construct a Rate object with the clock as proposed above. But that's tying together a much heaver concept which requires a time source and a lot more initialization. Whereas the Rate object is basically a little bit of data that doesn't need extra infrastructure. 

This can also be seen in Duration where we have not ported forward the sleep method that was previously defined in roscpp. And this parallels how chrono implements it. There's no Sleep defined on the "duration" object. https://en.cppreference.com/w/cpp/chrono/duration You call sleep_for on the duration because the Duration doesn't have a concept of time passing

Similarly for the Rate concept. You're going to call sleep_for(x) where x = start + period - now The Rate object doesn't need to know or handle time in the background etc.
You can have and store Rate objects in messages and they stay valid without them additionally forcing association and maintenance of the clock object. Similarly different clocks could service a specific Rate object. 

To keep things isolated I would rather propose a Rate.sleep(Clock::ptr clock) Which will do the sleep and you pass it the appropriate clock when you want to sleep using it. This would be a shorthand for users to if clock.sleep(Rate.get_remainder()) { Rate.reset() } Maybe sleep_remainder or sleep_cycle

It would be valuable to enable the Rates to be templated on the Clock type to check that Rate is compatible with Clock so you don't end up sleeping from different timelines (Steady, Wall, ROS) 

Copy link
Contributor

@AlexeyMerzlyakov AlexeyMerzlyakov Feb 27, 2023

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@tfoote, we also have the same need in Nav2 to use rclcpp::Rate respectful to ROS-time. If I undestood correctly, the main reason of the above - is to not overcomplicate the rclcpp::Rate by adding the references (and objects???) of rclcpp::Clock there?

We could template the rclcpp::GenericRate by <rcl_clock_type_t Type> instead of <class Clock = std::chrono::clock>. Depending on it, templates' instantiations will be as follows:

using Rate = GenericRate<RCL_SYSTEM_TIME>;
using WallRate = GenericRate<RCL_STEADY_TIME>;
using ROSRate = GenericRate<RCL_ROS_TIME>;

Here I see 2 options of API solutions:

O1. Update GenericRate::sleep(Clock::SharedPtr clock) call to accept the pointer to RCLCPP Clock as input argument. Then inside sleep() implementation it will check whether the given clock corresponds to a class template <Type> and use clock->sleep_for(time_to_sleep) API call to sleep.

O2. In the GenericRate constrictor, create an internal rclcpp::Clock(Type) object of the templated type and then store it in GenericRate privates: clock_ = rclcpp::Clock::make_shared(Type);. Then using clock_->sleep_for() inside the sleep(). This will free sleep() call from extra checks and developers from one more pointer to the clock in API. But it also will make a new rclcpp::Clock object inside rclcpp::GenericRate. Which as I understand, is not the intention, if we want to rclcpp::GenericRate to be a lightweight structure. However, from my perspective, this option is pretty straight-forward to end-developers who will use this API.

Which way is better to prefer?
I may not see the whole picture, so please correct it if something missed or we could go another way.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants