@@ -54,86 +54,6 @@ struct StringCallback
54
54
}
55
55
};
56
56
57
- #pragma GCC diagnostic push
58
- #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
59
- TEST (RealtimePublisher, rt_publish_legacy)
60
- {
61
- rclcpp::init (0 , nullptr );
62
- const size_t ATTEMPTS = 10 ;
63
- const std::chrono::milliseconds DELAY (250 );
64
-
65
- const char * expected_msg = " Hello World" ;
66
- auto node = std::make_shared<rclcpp::Node>(" construct_move_destruct" );
67
- rclcpp::QoS qos (10 );
68
- qos.reliable ().transient_local ();
69
- auto pub = node->create_publisher <StringMsg>(" ~/rt_publish" , qos);
70
- RealtimePublisher<StringMsg> rt_pub (pub);
71
- // publish a latched message
72
- bool lock_is_held = rt_pub.trylock ();
73
- for (size_t i = 0 ; i < ATTEMPTS && !lock_is_held; ++i) {
74
- lock_is_held = rt_pub.trylock ();
75
- std::this_thread::sleep_for (DELAY);
76
- }
77
- ASSERT_TRUE (lock_is_held);
78
- rt_pub.msg_ .string_value = expected_msg;
79
- rt_pub.unlockAndPublish ();
80
-
81
- // make sure subscriber gets it
82
- StringCallback str_callback;
83
-
84
- auto sub = node->create_subscription <StringMsg>(
85
- " ~/rt_publish" , qos,
86
- std::bind (&StringCallback::callback, &str_callback, std::placeholders::_1));
87
- for (size_t i = 0 ; i < ATTEMPTS && str_callback.msg_ .string_value .empty (); ++i) {
88
- rclcpp::spin_some (node);
89
- std::this_thread::sleep_for (DELAY);
90
- }
91
- EXPECT_STREQ (expected_msg, str_callback.msg_ .string_value .c_str ());
92
- rclcpp::shutdown ();
93
- }
94
-
95
- TEST (RealtimePublisher, rt_try_publish_legacy)
96
- {
97
- rclcpp::init (0 , nullptr );
98
- const size_t ATTEMPTS = 10 ;
99
- const std::chrono::milliseconds DELAY (250 );
100
-
101
- const char * expected_msg = " Hello World" ;
102
- auto node = std::make_shared<rclcpp::Node>(" construct_move_destruct" );
103
- rclcpp::QoS qos (10 );
104
- qos.reliable ().transient_local ();
105
- auto pub = node->create_publisher <StringMsg>(" ~/rt_publish" , qos);
106
- RealtimePublisher<StringMsg> rt_pub (pub);
107
-
108
- // try publish a latched message
109
- bool publish_success = false ;
110
- for (std::size_t i = 0 ; i < ATTEMPTS; ++i) {
111
- StringMsg msg;
112
- msg.string_value = expected_msg;
113
-
114
- if (rt_pub.tryPublish (msg)) {
115
- publish_success = true ;
116
- break ;
117
- }
118
- std::this_thread::sleep_for (DELAY);
119
- }
120
- ASSERT_TRUE (publish_success);
121
-
122
- // make sure subscriber gets it
123
- StringCallback str_callback;
124
-
125
- auto sub = node->create_subscription <StringMsg>(
126
- " ~/rt_publish" , qos,
127
- std::bind (&StringCallback::callback, &str_callback, std::placeholders::_1));
128
- for (size_t i = 0 ; i < ATTEMPTS && str_callback.msg_ .string_value .empty (); ++i) {
129
- rclcpp::spin_some (node);
130
- std::this_thread::sleep_for (DELAY);
131
- }
132
- EXPECT_STREQ (expected_msg, str_callback.msg_ .string_value .c_str ());
133
- rclcpp::shutdown ();
134
- }
135
- #pragma GCC diagnostic pop
136
-
137
57
TEST (RealtimePublisher, rt_can_try_publish)
138
58
{
139
59
rclcpp::init (0 , nullptr );
0 commit comments