@@ -139,14 +139,6 @@ TYPED_TEST_SUITE(TestExecutorsStable, StandardExecutors, ExecutorTypeNames);
139139TYPED_TEST (TestExecutors, detachOnDestruction)
140140{
141141 using ExecutorType = TypeParam;
142- // rmw_connextdds doesn't support events-executor
143- if (
144- std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>() &&
145- std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 )
146- {
147- GTEST_SKIP ();
148- }
149-
150142 {
151143 ExecutorType executor;
152144 executor.add_node (this ->node );
@@ -163,14 +155,6 @@ TYPED_TEST(TestExecutors, detachOnDestruction)
163155TYPED_TEST (TestExecutorsStable, addTemporaryNode)
164156{
165157 using ExecutorType = TypeParam;
166- // rmw_connextdds doesn't support events-executor
167- if (
168- std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>() &&
169- std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 )
170- {
171- GTEST_SKIP ();
172- }
173-
174158 ExecutorType executor;
175159
176160 {
@@ -191,14 +175,6 @@ TYPED_TEST(TestExecutorsStable, addTemporaryNode)
191175TYPED_TEST (TestExecutors, emptyExecutor)
192176{
193177 using ExecutorType = TypeParam;
194- // rmw_connextdds doesn't support events-executor
195- if (
196- std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>() &&
197- std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 )
198- {
199- GTEST_SKIP ();
200- }
201-
202178 ExecutorType executor;
203179 std::thread spinner ([&]() {EXPECT_NO_THROW (executor.spin ());});
204180 std::this_thread::sleep_for (50ms);
@@ -210,14 +186,6 @@ TYPED_TEST(TestExecutors, emptyExecutor)
210186TYPED_TEST (TestExecutors, addNodeTwoExecutors)
211187{
212188 using ExecutorType = TypeParam;
213- // rmw_connextdds doesn't support events-executor
214- if (
215- std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>() &&
216- std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 )
217- {
218- GTEST_SKIP ();
219- }
220-
221189 ExecutorType executor1;
222190 ExecutorType executor2;
223191 EXPECT_NO_THROW (executor1.add_node (this ->node ));
@@ -229,14 +197,6 @@ TYPED_TEST(TestExecutors, addNodeTwoExecutors)
229197TYPED_TEST (TestExecutors, spinWithTimer)
230198{
231199 using ExecutorType = TypeParam;
232- // rmw_connextdds doesn't support events-executor
233- if (
234- std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>() &&
235- std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 )
236- {
237- GTEST_SKIP ();
238- }
239-
240200 ExecutorType executor;
241201
242202 bool timer_completed = false ;
@@ -260,14 +220,6 @@ TYPED_TEST(TestExecutors, spinWithTimer)
260220TYPED_TEST (TestExecutors, spinWhileAlreadySpinning)
261221{
262222 using ExecutorType = TypeParam;
263- // rmw_connextdds doesn't support events-executor
264- if (
265- std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>() &&
266- std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 )
267- {
268- GTEST_SKIP ();
269- }
270-
271223 ExecutorType executor;
272224 executor.add_node (this ->node );
273225
@@ -295,14 +247,6 @@ TYPED_TEST(TestExecutors, spinWhileAlreadySpinning)
295247TYPED_TEST (TestExecutors, testSpinUntilFutureComplete)
296248{
297249 using ExecutorType = TypeParam;
298- // rmw_connextdds doesn't support events-executor
299- if (
300- std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>() &&
301- std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 )
302- {
303- GTEST_SKIP ();
304- }
305-
306250 ExecutorType executor;
307251 executor.add_node (this ->node );
308252
@@ -326,14 +270,6 @@ TYPED_TEST(TestExecutors, testSpinUntilFutureComplete)
326270TYPED_TEST (TestExecutors, testSpinUntilSharedFutureComplete)
327271{
328272 using ExecutorType = TypeParam;
329- // rmw_connextdds doesn't support events-executor
330- if (
331- std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>() &&
332- std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 )
333- {
334- GTEST_SKIP ();
335- }
336-
337273 ExecutorType executor;
338274 executor.add_node (this ->node );
339275
@@ -358,14 +294,6 @@ TYPED_TEST(TestExecutors, testSpinUntilSharedFutureComplete)
358294TYPED_TEST (TestExecutors, testSpinUntilFutureCompleteNoTimeout)
359295{
360296 using ExecutorType = TypeParam;
361- // rmw_connextdds doesn't support events-executor
362- if (
363- std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>() &&
364- std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 )
365- {
366- GTEST_SKIP ();
367- }
368-
369297 ExecutorType executor;
370298 executor.add_node (this ->node );
371299
@@ -413,14 +341,6 @@ TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteNoTimeout)
413341TYPED_TEST (TestExecutors, testSpinUntilFutureCompleteWithTimeout)
414342{
415343 using ExecutorType = TypeParam;
416- // rmw_connextdds doesn't support events-executor
417- if (
418- std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>() &&
419- std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 )
420- {
421- GTEST_SKIP ();
422- }
423-
424344 ExecutorType executor;
425345 executor.add_node (this ->node );
426346
@@ -533,14 +453,6 @@ class TestWaitable : public rclcpp::Waitable
533453TYPED_TEST (TestExecutors, spinAll)
534454{
535455 using ExecutorType = TypeParam;
536- // rmw_connextdds doesn't support events-executor
537- if (
538- std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>() &&
539- std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 )
540- {
541- GTEST_SKIP ();
542- }
543-
544456 ExecutorType executor;
545457 auto waitable_interfaces = this ->node ->get_node_waitables_interface ();
546458 auto my_waitable = std::make_shared<TestWaitable>();
@@ -583,14 +495,6 @@ TYPED_TEST(TestExecutors, spinAll)
583495TYPED_TEST (TestExecutors, spinSome)
584496{
585497 using ExecutorType = TypeParam;
586- // rmw_connextdds doesn't support events-executor
587- if (
588- std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>() &&
589- std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 )
590- {
591- GTEST_SKIP ();
592- }
593-
594498 ExecutorType executor;
595499 auto waitable_interfaces = this ->node ->get_node_waitables_interface ();
596500 auto my_waitable = std::make_shared<TestWaitable>();
@@ -633,14 +537,6 @@ TYPED_TEST(TestExecutors, spinSome)
633537TYPED_TEST (TestExecutors, testSpinNodeUntilFutureCompleteNodeBasePtr)
634538{
635539 using ExecutorType = TypeParam;
636- // rmw_connextdds doesn't support events-executor
637- if (
638- std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>() &&
639- std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 )
640- {
641- GTEST_SKIP ();
642- }
643-
644540 ExecutorType executor;
645541
646542 std::promise<bool > promise;
@@ -657,14 +553,6 @@ TYPED_TEST(TestExecutors, testSpinNodeUntilFutureCompleteNodeBasePtr)
657553TYPED_TEST (TestExecutors, testSpinNodeUntilFutureCompleteNodePtr)
658554{
659555 using ExecutorType = TypeParam;
660- // rmw_connextdds doesn't support events-executor
661- if (
662- std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>() &&
663- std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 )
664- {
665- GTEST_SKIP ();
666- }
667-
668556 ExecutorType executor;
669557
670558 std::promise<bool > promise;
@@ -681,14 +569,6 @@ TYPED_TEST(TestExecutors, testSpinNodeUntilFutureCompleteNodePtr)
681569TYPED_TEST (TestExecutors, testSpinUntilFutureCompleteInterrupted)
682570{
683571 using ExecutorType = TypeParam;
684- // rmw_connextdds doesn't support events-executor
685- if (
686- std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>() &&
687- std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 )
688- {
689- GTEST_SKIP ();
690- }
691-
692572 ExecutorType executor;
693573 executor.add_node (this ->node );
694574
0 commit comments