Skip to content

Catch the exception from rate.sleep() if the context is invalid.#2956

Merged
fujitatomoya merged 1 commit intorollingfrom
fujitatomoya/rclcpp/issues/2862
Oct 6, 2025
Merged

Catch the exception from rate.sleep() if the context is invalid.#2956
fujitatomoya merged 1 commit intorollingfrom
fujitatomoya/rclcpp/issues/2862

Conversation

@fujitatomoya
Copy link
Copy Markdown
Collaborator

Description

Fixes #2862

Is this user-facing behavior change?

Yes.

before, it throws the exception via rate.sleep() call if the context is already shutdown by other threads.
after, it does not throw the exception via rate.sleep() call, instead it just returns the false to indicate that it could not sleep for the full time.

Did you use Generative AI?

No

Additional Information

Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
Copy link
Copy Markdown

Copilot AI left a comment

Choose a reason for hiding this comment

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

Pull Request Overview

This PR fixes an exception handling issue where Rate::sleep() would throw an exception when called on an invalid/shutdown ROS context. The change catches the exception and returns false instead, providing a more graceful failure mode.

Key changes:

  • Added exception handling around clock_->sleep_for() call in Rate::sleep()
  • Added test coverage for the invalid context scenario

Reviewed Changes

Copilot reviewed 2 out of 2 changed files in this pull request and generated 1 comment.

File Description
rclcpp/src/rclcpp/rate.cpp Wraps clock_->sleep_for() in try-catch to handle invalid context exceptions
rclcpp/test/rclcpp/test_rate.cpp Adds test case to verify no exception is thrown when context is shutdown

Tip: Customize your code reviews with copilot-instructions.md. Create the file or learn how to get started.

rclcpp::Rate rate(1.0);
ASSERT_TRUE(rate.sleep());
rclcpp::shutdown();
EXPECT_NO_THROW(rate.sleep());
Copy link
Copy Markdown
Collaborator Author

Choose a reason for hiding this comment

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

this particular line is passing because of this PR fix. it did throw the exception without this PR change.

clock_->sleep_for(time_to_sleep);
try {
// If the context is invalid, an exception will be thrown.
clock_->sleep_for(time_to_sleep);
Copy link
Copy Markdown
Collaborator Author

Choose a reason for hiding this comment

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

It does not matter what kind of clock type is used by application.
During this sleep call, it checks if the context is valid in the underlying clock object. and this is required to register the shutdown callback to wake the condition variable to the clock.

@fujitatomoya
Copy link
Copy Markdown
Collaborator Author

@jmachowinski can you take a look at this?

Copy link
Copy Markdown

@MarqRazz MarqRazz left a comment

Choose a reason for hiding this comment

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

Thanks fixing this ❤️

@fujitatomoya fujitatomoya merged commit 10f0186 into rolling Oct 6, 2025
2 of 3 checks passed
@fujitatomoya
Copy link
Copy Markdown
Collaborator Author

Ah, sorry i forgot to run the CI. i will revert and retry with CI.

fujitatomoya added a commit that referenced this pull request Oct 6, 2025
…id. (#2956)"

This reverts commit 10f0186.

Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
fujitatomoya added a commit that referenced this pull request Oct 6, 2025
…id. (#2956)" (#2963)

This reverts commit 10f0186.

Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
fujitatomoya added a commit that referenced this pull request Oct 6, 2025
…lid. (#2956)" (#2963)

This reverts commit 6fbf039.

Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
fujitatomoya added a commit that referenced this pull request Oct 6, 2025
…lid. (#2956)" (#2963) (#2964)

This reverts commit 6fbf039.

Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
@ahcorde ahcorde deleted the fujitatomoya/rclcpp/issues/2862 branch October 6, 2025 08:51
iv461 pushed a commit to iv461/rclcpp that referenced this pull request Oct 7, 2025
…2#2956)

Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
iv461 pushed a commit to iv461/rclcpp that referenced this pull request Oct 7, 2025
…id. (ros2#2956)" (ros2#2963)

This reverts commit 10f0186.

Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
iv461 pushed a commit to iv461/rclcpp that referenced this pull request Oct 7, 2025
…lid. (ros2#2956)" (ros2#2963) (ros2#2964)

This reverts commit 6fbf039.

Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
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.

rclcpp::Rate crash if called when node is requested to shutdown

4 participants