Skip to content

Commit 543a3c3

Browse files
authored
[rclcpp_action] Add warnings (#1405)
* Add warnings Signed-off-by: Audrow Nash <[email protected]> * Simplify for loop in test_client.cpp Signed-off-by: Audrow Nash <[email protected]> * Fix conversion warning in test_client static cast to size_t Signed-off-by: Audrow Nash <[email protected]> * Fix new warnings after rebasing on master Signed-off-by: Audrow Nash <[email protected]> * Fix shadowing in the benchmark action server Signed-off-by: Audrow Nash <[email protected]> * Static cast goal order to size_t Signed-off-by: Audrow Nash <[email protected]> * Remove unnecessary include Signed-off-by: Audrow Nash <[email protected]>
1 parent 62c958b commit 543a3c3

File tree

7 files changed

+29
-26
lines changed

7 files changed

+29
-26
lines changed

rclcpp_action/CMakeLists.txt

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,10 @@ if(NOT CMAKE_CXX_STANDARD)
1313
set(CMAKE_CXX_STANDARD 14)
1414
endif()
1515
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
16-
add_compile_options(-Wall -Wextra -Wpedantic -Wnon-virtual-dtor -Woverloaded-virtual)
16+
add_compile_options(
17+
-Wall -Wextra -Wpedantic -Wnon-virtual-dtor -Woverloaded-virtual
18+
-Wformat=2 -Wconversion -Wshadow -Wsign-conversion -Wcast-qual
19+
)
1720
endif()
1821

1922
set(${PROJECT_NAME}_SRCS

rclcpp_action/include/rclcpp_action/server.hpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -381,31 +381,31 @@ class Server : public ServerBase, public std::enable_shared_from_this<Server<Act
381381
std::weak_ptr<Server<ActionT>> weak_this = this->shared_from_this();
382382

383383
std::function<void(const GoalUUID &, std::shared_ptr<void>)> on_terminal_state =
384-
[weak_this](const GoalUUID & uuid, std::shared_ptr<void> result_message)
384+
[weak_this](const GoalUUID & goal_uuid, std::shared_ptr<void> result_message)
385385
{
386386
std::shared_ptr<Server<ActionT>> shared_this = weak_this.lock();
387387
if (!shared_this) {
388388
return;
389389
}
390390
// Send result message to anyone that asked
391-
shared_this->publish_result(uuid, result_message);
391+
shared_this->publish_result(goal_uuid, result_message);
392392
// Publish a status message any time a goal handle changes state
393393
shared_this->publish_status();
394394
// notify base so it can recalculate the expired goal timer
395395
shared_this->notify_goal_terminal_state();
396396
// Delete data now (ServerBase and rcl_action_server_t keep data until goal handle expires)
397397
std::lock_guard<std::mutex> lock(shared_this->goal_handles_mutex_);
398-
shared_this->goal_handles_.erase(uuid);
398+
shared_this->goal_handles_.erase(goal_uuid);
399399
};
400400

401401
std::function<void(const GoalUUID &)> on_executing =
402-
[weak_this](const GoalUUID & uuid)
402+
[weak_this](const GoalUUID & goal_uuid)
403403
{
404404
std::shared_ptr<Server<ActionT>> shared_this = weak_this.lock();
405405
if (!shared_this) {
406406
return;
407407
}
408-
(void)uuid;
408+
(void)goal_uuid;
409409
// Publish a status message any time a goal handle changes state
410410
shared_this->publish_status();
411411
};

rclcpp_action/src/server.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -474,10 +474,10 @@ ServerBase::execute_result_request_received(std::shared_ptr<void> & data)
474474

475475
if (result_response) {
476476
// Send the result now
477-
rcl_ret_t ret = rcl_action_send_result_response(
477+
rcl_ret_t rcl_ret = rcl_action_send_result_response(
478478
pimpl_->action_server_.get(), &request_header, result_response.get());
479-
if (RCL_RET_OK != ret) {
480-
rclcpp::exceptions::throw_from_rcl_error(ret);
479+
if (RCL_RET_OK != rcl_ret) {
480+
rclcpp::exceptions::throw_from_rcl_error(rcl_ret);
481481
}
482482
} else {
483483
// Store the request so it can be responded to later

rclcpp_action/test/benchmark/benchmark_action_client.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -81,7 +81,7 @@ class ActionClientPerformanceTest : public PerformanceTest
8181

8282
// Should be checked by the server above
8383
assert(goal->order > 0);
84-
result->sequence.resize(goal->order);
84+
result->sequence.resize(static_cast<size_t>(goal->order));
8585
result->sequence[0] = 0;
8686
if (goal->order == 1) {
8787
current_goal_handle->succeed(result);
@@ -92,7 +92,7 @@ class ActionClientPerformanceTest : public PerformanceTest
9292
current_goal_handle->succeed(result);
9393
return;
9494
}
95-
for (int i = 2; i < goal->order; ++i) {
95+
for (size_t i = 2; i < static_cast<size_t>(goal->order); ++i) {
9696
result->sequence[i] =
9797
result->sequence[i - 1] + result->sequence[i - 2];
9898
}
@@ -310,8 +310,8 @@ BENCHMARK_F(ActionClientPerformanceTest, async_cancel_goal)(benchmark::State & s
310310
rclcpp::spin_until_future_complete(node, future_cancel, std::chrono::seconds(1));
311311
auto cancel_response = future_cancel.get();
312312

313-
using CancelResponse = test_msgs::action::Fibonacci::Impl::CancelGoalService::Response;
314-
if (CancelResponse::ERROR_NONE != cancel_response->return_code) {
313+
using CancelActionResponse = test_msgs::action::Fibonacci::Impl::CancelGoalService::Response;
314+
if (CancelActionResponse::ERROR_NONE != cancel_response->return_code) {
315315
state.SkipWithError("Cancel request did not succeed");
316316
break;
317317
}
@@ -345,8 +345,8 @@ BENCHMARK_F(ActionClientPerformanceTest, async_cancel_all_goals)(benchmark::Stat
345345
rclcpp::spin_until_future_complete(node, future_cancel_all, std::chrono::seconds(1));
346346
auto cancel_response = future_cancel_all.get();
347347

348-
using CancelResponse = test_msgs::action::Fibonacci::Impl::CancelGoalService::Response;
349-
if (CancelResponse::ERROR_NONE != cancel_response->return_code) {
348+
using CancelActionResponse = test_msgs::action::Fibonacci::Impl::CancelGoalService::Response;
349+
if (CancelActionResponse::ERROR_NONE != cancel_response->return_code) {
350350
state.SkipWithError("Cancel request did not succeed");
351351
break;
352352
}

rclcpp_action/test/benchmark/benchmark_action_server.cpp

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -187,8 +187,8 @@ BENCHMARK_F(ActionServerPerformanceTest, action_server_cancel_goal)(benchmark::S
187187

188188
rclcpp::spin_until_future_complete(node, future_cancel, std::chrono::seconds(1));
189189
auto cancel_response = future_cancel.get();
190-
using CancelResponse = test_msgs::action::Fibonacci::Impl::CancelGoalService::Response;
191-
if (CancelResponse::ERROR_NONE != cancel_response->return_code) {
190+
using CancelActionResponse = test_msgs::action::Fibonacci::Impl::CancelGoalService::Response;
191+
if (CancelActionResponse::ERROR_NONE != cancel_response->return_code) {
192192
state.SkipWithError("Cancel request did not succeed");
193193
break;
194194
}
@@ -247,12 +247,12 @@ BENCHMARK_F(ActionServerPerformanceTest, action_server_set_success)(benchmark::S
247247
// too wide, they at least could agree it was fine. In my testing MSVC errored if goal_order was
248248
// not captured, but clang would warn if it was explicitly captured.
249249
const auto result = [&]() {
250-
auto result = std::make_shared<Fibonacci::Result>();
250+
auto action_result = std::make_shared<Fibonacci::Result>();
251251
for (int i = 0; i < goal_order; ++i) {
252252
// Not the fibonacci sequence, but that's not important to this benchmark
253-
result->sequence.push_back(i);
253+
action_result->sequence.push_back(i);
254254
}
255-
return result;
255+
return action_result;
256256
} ();
257257

258258
reset_heap_counters();
@@ -291,12 +291,12 @@ BENCHMARK_F(ActionServerPerformanceTest, action_server_abort)(benchmark::State &
291291

292292
// Capturing with & because MSVC and Clang disagree about how to capture goal_order
293293
const auto result = [&]() {
294-
auto result = std::make_shared<Fibonacci::Result>();
294+
auto action_result = std::make_shared<Fibonacci::Result>();
295295
for (int i = 0; i < goal_order; ++i) {
296296
// Not the fibonacci sequence, but that's not important to this benchmark
297-
result->sequence.push_back(i);
297+
action_result->sequence.push_back(i);
298298
}
299-
return result;
299+
return action_result;
300300
} ();
301301

302302
reset_heap_counters();

rclcpp_action/test/test_client.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -132,7 +132,7 @@ class TestClient : public ::testing::Test
132132
feedback_message.feedback.sequence.push_back(1);
133133
feedback_publisher->publish(feedback_message);
134134
client_executor.spin_once();
135-
for (int i = 1; i < goal_request->goal.order; ++i) {
135+
for (size_t i = 1; i < static_cast<size_t>(goal_request->goal.order); ++i) {
136136
feedback_message.feedback.sequence.push_back(
137137
feedback_message.feedback.sequence[i] +
138138
feedback_message.feedback.sequence[i - 1]);

rclcpp_action/test/test_types.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -25,12 +25,12 @@ TEST(TestActionTypes, goal_uuid_to_string) {
2525
EXPECT_STREQ("0123456789abcdef", rclcpp_action::to_string(goal_id).c_str());
2626

2727
for (uint8_t i = 0; i < UUID_SIZE; ++i) {
28-
goal_id[i] = 16u + i;
28+
goal_id[i] = static_cast<uint8_t>(16u + i);
2929
}
3030
EXPECT_STREQ("101112131415161718191a1b1c1d1e1f", rclcpp_action::to_string(goal_id).c_str());
3131

3232
for (uint8_t i = 0; i < UUID_SIZE; ++i) {
33-
goal_id[i] = std::numeric_limits<uint8_t>::max() - i;
33+
goal_id[i] = static_cast<uint8_t>(std::numeric_limits<uint8_t>::max() - i);
3434
}
3535
EXPECT_STREQ("fffefdfcfbfaf9f8f7f6f5f4f3f2f1f0", rclcpp_action::to_string(goal_id).c_str());
3636
}

0 commit comments

Comments
 (0)