Skip to content

Clarify rate names and introduce SteadyRate #1373

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

Draft
wants to merge 3 commits into
base: rolling
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
84 changes: 82 additions & 2 deletions rclcpp/include/rclcpp/rate.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@
#include <memory>
#include <thread>

#include "rclcpp/clock.hpp"
#include "rclcpp/duration.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/utilities.hpp"
#include "rclcpp/visibility_control.hpp"
Expand Down Expand Up @@ -112,8 +114,86 @@ class GenericRate : public RateBase
std::chrono::time_point<Clock, ClockDurationNano> last_interval_;
};

using Rate = GenericRate<std::chrono::system_clock>;
using WallRate = GenericRate<std::chrono::steady_clock>;
using WallRate = GenericRate<std::chrono::system_clock>;
using SteadyRate = GenericRate<std::chrono::steady_clock>;
using Rate [[deprecated("Use rclcpp::WallRate explicitly instead.")]] = WallRate;

class ROSRate : public RateBase
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(ROSRate)

explicit ROSRate(rclcpp::Clock::SharedPtr clock, double rate)
: ROSRate(clock, rclcpp::Duration::from_seconds(1.0 / rate))
{
}
explicit ROSRate(rclcpp::Clock::SharedPtr clock, rclcpp::Duration period)
: clock_(clock), period_(period), last_interval_(clock->now())
{
}

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.

{
const auto now = clock_->now();
// Time of next interval
auto next_interval = last_interval_ + period_;
// Detect backwards time flow
if (now < last_interval_) {
// Best thing to do is to set the next_interval to now + period
next_interval = now + period_;
}
// Update the interval
last_interval_ += period_;

// If the time_to_sleep is negative or zero, don't sleep
auto time_to_sleep = next_interval - now;
if (time_to_sleep <= rclcpp::Duration(0, 0)) {
// If an entire cycle was missed then reset next interval.
// This might happen if the loop took more than a cycle.
// Or if time jumps forward.
if (now > next_interval + period_) {
last_interval_ = now + period_;
}
// Either way do not sleep and return false
return false;
}

// loop for handling the case that clock is slower than a chrono clock
// e.g. in case of use_sim_time
while (time_to_sleep > rclcpp::Duration(0, 0)) {
// Sleep (will get interrupted by ctrl-c, may not sleep full time)
rclcpp::sleep_for(time_to_sleep.to_chrono<std::chrono::nanoseconds>());
time_to_sleep = next_interval - clock_->now();
}
return true;
}

virtual bool
is_steady() const
{
return false;
}

virtual void
reset()
{
last_interval_ = clock_->now();
}

rclcpp::Duration
period() const
{
return period_;
}

private:
RCLCPP_DISABLE_COPY(ROSRate)

rclcpp::Clock::SharedPtr clock_;
rclcpp::Duration period_;
rclcpp::Time last_interval_;
};

} // namespace rclcpp

Expand Down
8 changes: 4 additions & 4 deletions rclcpp/test/rclcpp/test_rate.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,14 +21,14 @@
/*
Basic tests for the Rate and WallRate classes.
*/
TEST(TestRate, rate_basics) {
TEST(TestRate, wall_rate_basics) {
auto period = std::chrono::milliseconds(1000);
auto offset = std::chrono::milliseconds(500);
auto epsilon = std::chrono::milliseconds(100);
double overrun_ratio = 1.5;

auto start = std::chrono::system_clock::now();
rclcpp::Rate r(period);
rclcpp::WallRate r(period);
EXPECT_EQ(period, r.period());
ASSERT_FALSE(r.is_steady());
ASSERT_TRUE(r.sleep());
Expand Down Expand Up @@ -61,14 +61,14 @@ TEST(TestRate, rate_basics) {
ASSERT_TRUE(epsilon > delta);
}

TEST(TestRate, wall_rate_basics) {
TEST(TestRate, steady_rate_basics) {
auto period = std::chrono::milliseconds(100);
auto offset = std::chrono::milliseconds(50);
auto epsilon = std::chrono::milliseconds(1);
double overrun_ratio = 1.5;

auto start = std::chrono::steady_clock::now();
rclcpp::WallRate r(period);
rclcpp::SteadyRate r(period);
EXPECT_EQ(period, r.period());
ASSERT_TRUE(r.is_steady());
ASSERT_TRUE(r.sleep());
Expand Down