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

feat: Add ClockWaiter and ClockConditionalVariable #2691

Open
wants to merge 2 commits into
base: rolling
Choose a base branch
from

Conversation

jmachowinski
Copy link
Contributor

This replaces the Clock::cancel_sleep_or_wait with two new synchronization primitives, that can be instantiated separate from the Clock object.

The old API turned out the be a bad design, as one can not simply copy or create new clock objects.

If one copys a clock object, the same internal pimpl is copied, which is undesirable in combination with this API,
as they then all share the same conditional. Therefore one can't do sleeps with multiple threads without waking up
other threads.

If one tries to create a new clock, then there is no clockprovider registered to it. Leading to an unexpected
behavior in simulation mode. We should perhaps add a BIG warning to the constructor to not do this.

This merge request is a first step in reworking the clock code, and I want to get some feedback on the API / class names, before refactoring further.

@arneboe Can you have a look the documentation and API ?

@ros-discourse
Copy link

This pull request has been mentioned on ROS Discourse. There might be relevant details there:

https://discourse.ros.org/t/next-client-library-wg-meeting-friday-6th-december-2024-8am-pt/40954/2

@sloretz
Copy link
Contributor

sloretz commented Dec 20, 2024

Assigned @wjwwood, and recommend Client Library Working group review 🧇

Comment on lines +274 to +276
* Note, this class does not handle shutdowns, if you want to
* haven them handles as well, use ClockConditionalVariable.
*/
Copy link

Choose a reason for hiding this comment

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

Is there a use-case for a conditional variable that does not wake up when ros shuts down?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Yes, if you need to handle the shutdown and wakeup explicit. Executors are an example of this.

* Note, this class does not handle shutdowns, if you want to
* haven them handles as well, use ClockConditionalVariable.
*/
class ClockWaiter
Copy link

Choose a reason for hiding this comment

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

The naming is a bit strange. This one is called ClockWaiter, ther other one is called ClockConditionalVariable.
According to your comments they are both conditional variables and their function is nearly identical. Why such different names?

rclcpp/include/rclcpp/clock.hpp Outdated Show resolved Hide resolved
const rclcpp::Time& abs_time, const std::function<bool ()> &pred )
{
// Install jump handler for any amount of time change, for two purposes:
// - if ROS time is active, check if time reached on each new clock sample
Copy link

Choose a reason for hiding this comment

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

What do you mean by "if ROS time is active". How can the ROS time not be active?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

"ROS time is active" means the node runs on the external time input from /clock. Also know as sim_time. If it is not active, this means the system just runs on system time.

Comment on lines +413 to +420
rcl_jump_threshold_t threshold;
threshold.on_clock_change = true;
// 0 is disable, so -1 and 1 are smallest possible time changes
threshold.min_backward.nanoseconds = -1;
threshold.min_forward.nanoseconds = 1;
Copy link

Choose a reason for hiding this comment

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

Use named struct initializer to ensure that all members of the struct are initialized.
That way the compiler will tell you if anyone changes rcl_jump_threshold_t

Copy link
Contributor Author

Choose a reason for hiding this comment

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

sadly, rclcpp is using c++17 and this is a c++20 feature.

rclcpp/src/rclcpp/clock.cpp Show resolved Hide resolved


bool
wait_until_ros_time(std::unique_lock<std::mutex>& lock,
Copy link

Choose a reason for hiding this comment

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

Add documentation.
Especially document that system time will be used if ros time is not active

Janosch Machowinski added 2 commits February 7, 2025 20:34
Added two new synchronization primitives to perform waits
using an rclcpp::Clock.

Signed-off-by: Janosch Machowinski <[email protected]>
Signed-off-by: Janosch Machowinski <[email protected]>
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