diff --git a/rclcpp/include/rclcpp/rate.hpp b/rclcpp/include/rclcpp/rate.hpp index 381e8d7908..5b04b72b81 100644 --- a/rclcpp/include/rclcpp/rate.hpp +++ b/rclcpp/include/rclcpp/rate.hpp @@ -184,16 +184,6 @@ class WallRate : public Rate explicit WallRate(const Duration & period); }; -class ROSRate : public Rate -{ -public: - RCLCPP_PUBLIC - explicit ROSRate(const double rate); - - RCLCPP_PUBLIC - explicit ROSRate(const Duration & period); -}; - } // namespace rclcpp #endif // RCLCPP__RATE_HPP_ diff --git a/rclcpp/src/rclcpp/rate.cpp b/rclcpp/src/rclcpp/rate.cpp index 9a6e3d486b..cd071d2cb0 100644 --- a/rclcpp/src/rclcpp/rate.cpp +++ b/rclcpp/src/rclcpp/rate.cpp @@ -102,12 +102,4 @@ WallRate::WallRate(const Duration & period) : Rate(period, std::make_shared(RCL_STEADY_TIME)) {} -ROSRate::ROSRate(const double rate) -: Rate(rate, std::make_shared(RCL_ROS_TIME)) -{} - -ROSRate::ROSRate(const Duration & period) -: Rate(period, std::make_shared(RCL_ROS_TIME)) -{} - } // namespace rclcpp diff --git a/rclcpp/test/rclcpp/test_rate.cpp b/rclcpp/test/rclcpp/test_rate.cpp index 5ab64ee608..4f067b2bd8 100644 --- a/rclcpp/test/rclcpp/test_rate.cpp +++ b/rclcpp/test/rclcpp/test_rate.cpp @@ -22,7 +22,7 @@ #include "../utils/rclcpp_gtest_macros.hpp" /* - Basic tests for the Rate, WallRate and ROSRate classes. + Basic tests for the Rate and WallRate classes. */ TEST(TestRate, rate_basics) { rclcpp::init(0, nullptr); @@ -144,69 +144,6 @@ TEST(TestRate, wall_rate_basics) { rclcpp::shutdown(); } -TEST(TestRate, ros_rate_basics) { - rclcpp::init(0, nullptr); - - auto period = std::chrono::milliseconds(100); - auto offset = std::chrono::milliseconds(50); - auto epsilon = std::chrono::milliseconds(1); - double overrun_ratio = 1.5; - - rclcpp::Clock clock(RCL_ROS_TIME); - - auto start = clock.now(); - rclcpp::ROSRate r(period); - EXPECT_EQ(rclcpp::Duration(period), r.period()); -// suppress deprecated warnings -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - ASSERT_FALSE(r.is_steady()); -// suppress deprecated warnings -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - ASSERT_EQ(RCL_ROS_TIME, r.get_type()); - ASSERT_TRUE(r.sleep()); - auto one = clock.now(); - auto delta = one - start; - EXPECT_LT(rclcpp::Duration(period), delta); - EXPECT_GT(rclcpp::Duration(period * overrun_ratio), delta); - - clock.sleep_for(offset); - ASSERT_TRUE(r.sleep()); - auto two = clock.now(); - delta = two - start; - EXPECT_LT(rclcpp::Duration(2 * period), delta + epsilon); - EXPECT_GT(rclcpp::Duration(2 * period * overrun_ratio), delta); - - clock.sleep_for(offset); - auto two_offset = clock.now(); - r.reset(); - ASSERT_TRUE(r.sleep()); - auto three = clock.now(); - delta = three - two_offset; - EXPECT_LT(rclcpp::Duration(period), delta); - EXPECT_GT(rclcpp::Duration(period * overrun_ratio), delta); - - clock.sleep_for(offset + period); - auto four = clock.now(); - ASSERT_FALSE(r.sleep()); - auto five = clock.now(); - delta = five - four; - EXPECT_GT(rclcpp::Duration(epsilon), delta); - - rclcpp::shutdown(); -} - /* Basic test for the deprecated GenericRate class. */ @@ -331,7 +268,7 @@ TEST(TestRate, from_double) { EXPECT_EQ(rclcpp::Duration(std::chrono::seconds(1)), rate.period()); } { - rclcpp::WallRate rate(2.0); + rclcpp::Rate rate(2.0); EXPECT_EQ(rclcpp::Duration(std::chrono::milliseconds(500)), rate.period()); } { @@ -339,7 +276,7 @@ TEST(TestRate, from_double) { EXPECT_EQ(rclcpp::Duration(std::chrono::seconds(2)), rate.period()); } { - rclcpp::ROSRate rate(4.0); + rclcpp::WallRate rate(4.0); EXPECT_EQ(rclcpp::Duration(std::chrono::milliseconds(250)), rate.period()); } }