diff --git a/rclcpp/test/rclcpp/executors/executor_types.hpp b/rclcpp/test/rclcpp/executors/executor_types.hpp index 02462faf5f..baa13be9d5 100644 --- a/rclcpp/test/rclcpp/executors/executor_types.hpp +++ b/rclcpp/test/rclcpp/executors/executor_types.hpp @@ -43,12 +43,19 @@ using DeprecatedStaticSingleThreadedExecutor = rclcpp::executors::StaticSingleTh # pragma warning(pop) #endif +#ifdef __clang__ +# pragma clang diagnostic push +# pragma clang diagnostic ignored "-Wdeprecated-declarations" +#endif using ExecutorTypes = ::testing::Types< rclcpp::executors::SingleThreadedExecutor, rclcpp::executors::MultiThreadedExecutor, DeprecatedStaticSingleThreadedExecutor, rclcpp::experimental::executors::EventsExecutor>; +#ifdef __clang__ +# pragma clang diagnostic pop +#endif class ExecutorTypeNames { @@ -64,10 +71,16 @@ class ExecutorTypeNames if (std::is_same()) { return "MultiThreadedExecutor"; } - +#ifdef __clang__ +# pragma clang diagnostic push +# pragma clang diagnostic ignored "-Wdeprecated-declarations" +#endif if (std::is_same()) { return "StaticSingleThreadedExecutor"; } +#ifdef __clang__ +# pragma clang diagnostic pop +#endif if (std::is_same()) { return "EventsExecutor"; diff --git a/rclcpp/test/rclcpp/executors/test_executors.cpp b/rclcpp/test/rclcpp/executors/test_executors.cpp index b79de72971..8e0b0c875f 100644 --- a/rclcpp/test/rclcpp/executors/test_executors.cpp +++ b/rclcpp/test/rclcpp/executors/test_executors.cpp @@ -488,11 +488,19 @@ TYPED_TEST(TestExecutors, spin_some_max_duration) // do not properly implement max_duration (it seems), so disable this test // for them in the meantime. // see: https://github.com/ros2/rclcpp/issues/2462 +#ifdef __clang__ +# pragma clang diagnostic push +# pragma clang diagnostic ignored "-Wdeprecated-declarations" +#endif + if ( std::is_same()) { GTEST_SKIP(); } +#ifdef __clang__ +# pragma clang diagnostic pop +#endif // Use an isolated callback group to avoid interference from any housekeeping // items that may be in the default callback group of the node. diff --git a/rclcpp/test/rclcpp/executors/test_executors_timer_cancel_behavior.cpp b/rclcpp/test/rclcpp/executors/test_executors_timer_cancel_behavior.cpp index 72bbceecb2..fbf38146fb 100644 --- a/rclcpp/test/rclcpp/executors/test_executors_timer_cancel_behavior.cpp +++ b/rclcpp/test/rclcpp/executors/test_executors_timer_cancel_behavior.cpp @@ -282,12 +282,20 @@ class TestTimerCancelBehavior : public ::testing::Test T executor; }; +#if !defined(_WIN32) +# ifdef __clang__ +# pragma clang diagnostic push +# pragma clang diagnostic ignored "-Wdeprecated-declarations" +# endif +#endif using MainExecutorTypes = ::testing::Types< rclcpp::executors::SingleThreadedExecutor, rclcpp::executors::MultiThreadedExecutor, DeprecatedStaticSingleThreadedExecutor>; - +#ifdef __clang__ +# pragma clang diagnostic pop +#endif // TODO(@fujitatomoya): this test excludes EventExecutor because it does not // support simulation time used for this test to relax the racy condition. // See more details for https://github.com/ros2/rclcpp/issues/2457. diff --git a/rclcpp/test/rclcpp/executors/test_reinitialized_timers.cpp b/rclcpp/test/rclcpp/executors/test_reinitialized_timers.cpp index d1ac90b95b..99725cb95e 100644 --- a/rclcpp/test/rclcpp/executors/test_reinitialized_timers.cpp +++ b/rclcpp/test/rclcpp/executors/test_reinitialized_timers.cpp @@ -32,7 +32,7 @@ class TestTimersLifecycle : public testing::Test void TearDown() override {rclcpp::shutdown();} }; -TYPED_TEST_SUITE(TestTimersLifecycle, ExecutorTypes); +TYPED_TEST_SUITE(TestTimersLifecycle, ExecutorTypes, ExecutorTypeNames); TYPED_TEST(TestTimersLifecycle, timers_lifecycle_reinitialized_object) { diff --git a/rclcpp/test/rclcpp/executors/test_static_single_threaded_executor.cpp b/rclcpp/test/rclcpp/executors/test_static_single_threaded_executor.cpp index a834c7b2be..8e330cbebc 100644 --- a/rclcpp/test/rclcpp/executors/test_static_single_threaded_executor.cpp +++ b/rclcpp/test/rclcpp/executors/test_static_single_threaded_executor.cpp @@ -47,7 +47,15 @@ class TestStaticSingleThreadedExecutor : public ::testing::Test }; TEST_F(TestStaticSingleThreadedExecutor, add_callback_group_trigger_guard_failed) { +#ifdef __clang__ +# pragma clang diagnostic push +# pragma clang diagnostic ignored "-Wdeprecated-declarations" +#endif + DeprecatedStaticSingleThreadedExecutor executor; +#ifdef __clang__ +# pragma clang diagnostic pop +#endif auto node = std::make_shared("node", "ns"); rclcpp::CallbackGroup::SharedPtr cb_group = node->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive); @@ -62,7 +70,15 @@ TEST_F(TestStaticSingleThreadedExecutor, add_callback_group_trigger_guard_failed } TEST_F(TestStaticSingleThreadedExecutor, add_node_trigger_guard_failed) { +#ifdef __clang__ +# pragma clang diagnostic push +# pragma clang diagnostic ignored "-Wdeprecated-declarations" +#endif + DeprecatedStaticSingleThreadedExecutor executor; +#ifdef __clang__ +# pragma clang diagnostic pop +#endif auto node = std::make_shared("node", "ns"); { @@ -75,7 +91,15 @@ TEST_F(TestStaticSingleThreadedExecutor, add_node_trigger_guard_failed) { } TEST_F(TestStaticSingleThreadedExecutor, remove_callback_group_trigger_guard_failed) { +#ifdef __clang__ +# pragma clang diagnostic push +# pragma clang diagnostic ignored "-Wdeprecated-declarations" +#endif + DeprecatedStaticSingleThreadedExecutor executor; +#ifdef __clang__ +# pragma clang diagnostic pop +#endif auto node = std::make_shared("node", "ns"); rclcpp::CallbackGroup::SharedPtr cb_group = node->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive); @@ -93,7 +117,15 @@ TEST_F(TestStaticSingleThreadedExecutor, remove_callback_group_trigger_guard_fai } TEST_F(TestStaticSingleThreadedExecutor, remove_node_failed) { +#ifdef __clang__ +# pragma clang diagnostic push +# pragma clang diagnostic ignored "-Wdeprecated-declarations" +#endif + DeprecatedStaticSingleThreadedExecutor executor; +#ifdef __clang__ +# pragma clang diagnostic pop +#endif auto node = std::make_shared("node", "ns"); { @@ -106,7 +138,15 @@ TEST_F(TestStaticSingleThreadedExecutor, remove_node_failed) { } TEST_F(TestStaticSingleThreadedExecutor, remove_node_trigger_guard_failed) { +#ifdef __clang__ +# pragma clang diagnostic push +# pragma clang diagnostic ignored "-Wdeprecated-declarations" +#endif + DeprecatedStaticSingleThreadedExecutor executor; +#ifdef __clang__ +# pragma clang diagnostic pop +#endif auto node = std::make_shared("node", "ns"); executor.add_node(node); @@ -121,7 +161,15 @@ TEST_F(TestStaticSingleThreadedExecutor, remove_node_trigger_guard_failed) { } TEST_F(TestStaticSingleThreadedExecutor, execute_service) { +#ifdef __clang__ +# pragma clang diagnostic push +# pragma clang diagnostic ignored "-Wdeprecated-declarations" +#endif + DeprecatedStaticSingleThreadedExecutor executor; +#ifdef __clang__ +# pragma clang diagnostic pop +#endif auto node = std::make_shared("node", "ns"); executor.add_node(node);