Skip to content

Commit

Permalink
Removed clang warnings (#2605)
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde authored Aug 22, 2024
1 parent 4b1c125 commit b7c7893
Show file tree
Hide file tree
Showing 5 changed files with 80 additions and 3 deletions.
15 changes: 14 additions & 1 deletion rclcpp/test/rclcpp/executors/executor_types.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand All @@ -64,10 +71,16 @@ class ExecutorTypeNames
if (std::is_same<T, rclcpp::executors::MultiThreadedExecutor>()) {
return "MultiThreadedExecutor";
}

#ifdef __clang__
# pragma clang diagnostic push
# pragma clang diagnostic ignored "-Wdeprecated-declarations"
#endif
if (std::is_same<T, DeprecatedStaticSingleThreadedExecutor>()) {
return "StaticSingleThreadedExecutor";
}
#ifdef __clang__
# pragma clang diagnostic pop
#endif

if (std::is_same<T, rclcpp::experimental::executors::EventsExecutor>()) {
return "EventsExecutor";
Expand Down
8 changes: 8 additions & 0 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<ExecutorType, DeprecatedStaticSingleThreadedExecutor>())
{
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.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/test/rclcpp/executors/test_reinitialized_timers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<rclcpp::Node>("node", "ns");
rclcpp::CallbackGroup::SharedPtr cb_group = node->create_callback_group(
rclcpp::CallbackGroupType::MutuallyExclusive);
Expand All @@ -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<rclcpp::Node>("node", "ns");

{
Expand All @@ -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<rclcpp::Node>("node", "ns");
rclcpp::CallbackGroup::SharedPtr cb_group = node->create_callback_group(
rclcpp::CallbackGroupType::MutuallyExclusive);
Expand All @@ -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<rclcpp::Node>("node", "ns");

{
Expand All @@ -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<rclcpp::Node>("node", "ns");

executor.add_node(node);
Expand All @@ -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<rclcpp::Node>("node", "ns");
executor.add_node(node);

Expand Down

0 comments on commit b7c7893

Please sign in to comment.