Skip to content

Commit b7c7893

Browse files
authored
Removed clang warnings (#2605)
Signed-off-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
1 parent 4b1c125 commit b7c7893

File tree

5 files changed

+80
-3
lines changed

5 files changed

+80
-3
lines changed

rclcpp/test/rclcpp/executors/executor_types.hpp

Lines changed: 14 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -43,12 +43,19 @@ using DeprecatedStaticSingleThreadedExecutor = rclcpp::executors::StaticSingleTh
4343
# pragma warning(pop)
4444
#endif
4545

46+
#ifdef __clang__
47+
# pragma clang diagnostic push
48+
# pragma clang diagnostic ignored "-Wdeprecated-declarations"
49+
#endif
4650
using ExecutorTypes =
4751
::testing::Types<
4852
rclcpp::executors::SingleThreadedExecutor,
4953
rclcpp::executors::MultiThreadedExecutor,
5054
DeprecatedStaticSingleThreadedExecutor,
5155
rclcpp::experimental::executors::EventsExecutor>;
56+
#ifdef __clang__
57+
# pragma clang diagnostic pop
58+
#endif
5259

5360
class ExecutorTypeNames
5461
{
@@ -64,10 +71,16 @@ class ExecutorTypeNames
6471
if (std::is_same<T, rclcpp::executors::MultiThreadedExecutor>()) {
6572
return "MultiThreadedExecutor";
6673
}
67-
74+
#ifdef __clang__
75+
# pragma clang diagnostic push
76+
# pragma clang diagnostic ignored "-Wdeprecated-declarations"
77+
#endif
6878
if (std::is_same<T, DeprecatedStaticSingleThreadedExecutor>()) {
6979
return "StaticSingleThreadedExecutor";
7080
}
81+
#ifdef __clang__
82+
# pragma clang diagnostic pop
83+
#endif
7184

7285
if (std::is_same<T, rclcpp::experimental::executors::EventsExecutor>()) {
7386
return "EventsExecutor";

rclcpp/test/rclcpp/executors/test_executors.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -488,11 +488,19 @@ TYPED_TEST(TestExecutors, spin_some_max_duration)
488488
// do not properly implement max_duration (it seems), so disable this test
489489
// for them in the meantime.
490490
// see: https://github.com/ros2/rclcpp/issues/2462
491+
#ifdef __clang__
492+
# pragma clang diagnostic push
493+
# pragma clang diagnostic ignored "-Wdeprecated-declarations"
494+
#endif
495+
491496
if (
492497
std::is_same<ExecutorType, DeprecatedStaticSingleThreadedExecutor>())
493498
{
494499
GTEST_SKIP();
495500
}
501+
#ifdef __clang__
502+
# pragma clang diagnostic pop
503+
#endif
496504

497505
// Use an isolated callback group to avoid interference from any housekeeping
498506
// items that may be in the default callback group of the node.

rclcpp/test/rclcpp/executors/test_executors_timer_cancel_behavior.cpp

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -282,12 +282,20 @@ class TestTimerCancelBehavior : public ::testing::Test
282282
T executor;
283283
};
284284

285+
#if !defined(_WIN32)
286+
# ifdef __clang__
287+
# pragma clang diagnostic push
288+
# pragma clang diagnostic ignored "-Wdeprecated-declarations"
289+
# endif
290+
#endif
285291
using MainExecutorTypes =
286292
::testing::Types<
287293
rclcpp::executors::SingleThreadedExecutor,
288294
rclcpp::executors::MultiThreadedExecutor,
289295
DeprecatedStaticSingleThreadedExecutor>;
290-
296+
#ifdef __clang__
297+
# pragma clang diagnostic pop
298+
#endif
291299
// TODO(@fujitatomoya): this test excludes EventExecutor because it does not
292300
// support simulation time used for this test to relax the racy condition.
293301
// See more details for https://github.com/ros2/rclcpp/issues/2457.

rclcpp/test/rclcpp/executors/test_reinitialized_timers.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ class TestTimersLifecycle : public testing::Test
3232
void TearDown() override {rclcpp::shutdown();}
3333
};
3434

35-
TYPED_TEST_SUITE(TestTimersLifecycle, ExecutorTypes);
35+
TYPED_TEST_SUITE(TestTimersLifecycle, ExecutorTypes, ExecutorTypeNames);
3636

3737
TYPED_TEST(TestTimersLifecycle, timers_lifecycle_reinitialized_object)
3838
{

rclcpp/test/rclcpp/executors/test_static_single_threaded_executor.cpp

Lines changed: 48 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,15 @@ class TestStaticSingleThreadedExecutor : public ::testing::Test
4747
};
4848

4949
TEST_F(TestStaticSingleThreadedExecutor, add_callback_group_trigger_guard_failed) {
50+
#ifdef __clang__
51+
# pragma clang diagnostic push
52+
# pragma clang diagnostic ignored "-Wdeprecated-declarations"
53+
#endif
54+
5055
DeprecatedStaticSingleThreadedExecutor executor;
56+
#ifdef __clang__
57+
# pragma clang diagnostic pop
58+
#endif
5159
auto node = std::make_shared<rclcpp::Node>("node", "ns");
5260
rclcpp::CallbackGroup::SharedPtr cb_group = node->create_callback_group(
5361
rclcpp::CallbackGroupType::MutuallyExclusive);
@@ -62,7 +70,15 @@ TEST_F(TestStaticSingleThreadedExecutor, add_callback_group_trigger_guard_failed
6270
}
6371

6472
TEST_F(TestStaticSingleThreadedExecutor, add_node_trigger_guard_failed) {
73+
#ifdef __clang__
74+
# pragma clang diagnostic push
75+
# pragma clang diagnostic ignored "-Wdeprecated-declarations"
76+
#endif
77+
6578
DeprecatedStaticSingleThreadedExecutor executor;
79+
#ifdef __clang__
80+
# pragma clang diagnostic pop
81+
#endif
6682
auto node = std::make_shared<rclcpp::Node>("node", "ns");
6783

6884
{
@@ -75,7 +91,15 @@ TEST_F(TestStaticSingleThreadedExecutor, add_node_trigger_guard_failed) {
7591
}
7692

7793
TEST_F(TestStaticSingleThreadedExecutor, remove_callback_group_trigger_guard_failed) {
94+
#ifdef __clang__
95+
# pragma clang diagnostic push
96+
# pragma clang diagnostic ignored "-Wdeprecated-declarations"
97+
#endif
98+
7899
DeprecatedStaticSingleThreadedExecutor executor;
100+
#ifdef __clang__
101+
# pragma clang diagnostic pop
102+
#endif
79103
auto node = std::make_shared<rclcpp::Node>("node", "ns");
80104
rclcpp::CallbackGroup::SharedPtr cb_group = node->create_callback_group(
81105
rclcpp::CallbackGroupType::MutuallyExclusive);
@@ -93,7 +117,15 @@ TEST_F(TestStaticSingleThreadedExecutor, remove_callback_group_trigger_guard_fai
93117
}
94118

95119
TEST_F(TestStaticSingleThreadedExecutor, remove_node_failed) {
120+
#ifdef __clang__
121+
# pragma clang diagnostic push
122+
# pragma clang diagnostic ignored "-Wdeprecated-declarations"
123+
#endif
124+
96125
DeprecatedStaticSingleThreadedExecutor executor;
126+
#ifdef __clang__
127+
# pragma clang diagnostic pop
128+
#endif
97129
auto node = std::make_shared<rclcpp::Node>("node", "ns");
98130

99131
{
@@ -106,7 +138,15 @@ TEST_F(TestStaticSingleThreadedExecutor, remove_node_failed) {
106138
}
107139

108140
TEST_F(TestStaticSingleThreadedExecutor, remove_node_trigger_guard_failed) {
141+
#ifdef __clang__
142+
# pragma clang diagnostic push
143+
# pragma clang diagnostic ignored "-Wdeprecated-declarations"
144+
#endif
145+
109146
DeprecatedStaticSingleThreadedExecutor executor;
147+
#ifdef __clang__
148+
# pragma clang diagnostic pop
149+
#endif
110150
auto node = std::make_shared<rclcpp::Node>("node", "ns");
111151

112152
executor.add_node(node);
@@ -121,7 +161,15 @@ TEST_F(TestStaticSingleThreadedExecutor, remove_node_trigger_guard_failed) {
121161
}
122162

123163
TEST_F(TestStaticSingleThreadedExecutor, execute_service) {
164+
#ifdef __clang__
165+
# pragma clang diagnostic push
166+
# pragma clang diagnostic ignored "-Wdeprecated-declarations"
167+
#endif
168+
124169
DeprecatedStaticSingleThreadedExecutor executor;
170+
#ifdef __clang__
171+
# pragma clang diagnostic pop
172+
#endif
125173
auto node = std::make_shared<rclcpp::Node>("node", "ns");
126174
executor.add_node(node);
127175

0 commit comments

Comments
 (0)