File tree Expand file tree Collapse file tree 2 files changed +16
-1
lines changed Expand file tree Collapse file tree 2 files changed +16
-1
lines changed Original file line number Diff line number Diff line change @@ -67,7 +67,13 @@ Rate::sleep()
6767 // Calculate the time to sleep
6868 auto time_to_sleep = next_interval - now;
6969 // Sleep (will get interrupted by ctrl-c, may not sleep full time)
70- clock_->sleep_for (time_to_sleep);
70+ try {
71+ // If the context is invalid, an exception will be thrown.
72+ clock_->sleep_for (time_to_sleep);
73+ } catch (const std::runtime_error & e) {
74+ // If it didn't sleep the full time, return false
75+ return false ;
76+ }
7177 return true ;
7278}
7379
Original file line number Diff line number Diff line change @@ -173,3 +173,12 @@ TEST_F(TestRate, incorrect_constuctor) {
173173 rclcpp::Rate rate (rclcpp::Duration (-1 , 0 )),
174174 std::invalid_argument (" period must be greater than 0" ));
175175}
176+
177+ TEST (TestRateBasic, invalid_context) {
178+ rclcpp::init (0 , nullptr );
179+ rclcpp::Rate rate (1.0 );
180+ ASSERT_TRUE (rate.sleep ());
181+ rclcpp::shutdown ();
182+ EXPECT_NO_THROW (rate.sleep ());
183+ ASSERT_FALSE (rate.sleep ());
184+ }
You can’t perform that action at this time.
0 commit comments