4242using StringMsg = test_msgs::msg::Strings;
4343using realtime_tools::RealtimePublisher;
4444
45- TEST (RealtimePublisher, construct_destruct) { RealtimePublisher<StringMsg> rt_pub; }
46-
4745struct StringCallback
4846{
4947 StringMsg msg_;
@@ -56,7 +54,12 @@ struct StringCallback
5654 }
5755};
5856
59- TEST (RealtimePublisher, rt_publish)
57+ #pragma GCC diagnostic push
58+ #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
59+
60+ TEST (RealtimePublisher, construct_destruct_legacy) { RealtimePublisher<StringMsg> rt_pub; }
61+
62+ TEST (RealtimePublisher, rt_publish_legacy)
6063{
6164 rclcpp::init (0 , nullptr );
6265 const size_t ATTEMPTS = 10 ;
@@ -92,7 +95,7 @@ TEST(RealtimePublisher, rt_publish)
9295 rclcpp::shutdown ();
9396}
9497
95- TEST (RealtimePublisher, rt_try_publish )
98+ TEST (RealtimePublisher, rt_try_publish_legacy )
9699{
97100 rclcpp::init (0 , nullptr );
98101 const size_t ATTEMPTS = 10 ;
@@ -132,6 +135,7 @@ TEST(RealtimePublisher, rt_try_publish)
132135 EXPECT_STREQ (expected_msg, str_callback.msg_ .string_value .c_str ());
133136 rclcpp::shutdown ();
134137}
138+ #pragma GCC diagnostic pop
135139
136140TEST (RealtimePublisher, rt_can_try_publish)
137141{
0 commit comments