Skip to content

Commit f7093d3

Browse files
committed
Add warnings
Signed-off-by: Audrow Nash <[email protected]>
1 parent b5b8782 commit f7093d3

File tree

4 files changed

+12
-9
lines changed

4 files changed

+12
-9
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
@@ -377,31 +377,31 @@ class Server : public ServerBase, public std::enable_shared_from_this<Server<Act
377377
std::weak_ptr<Server<ActionT>> weak_this = this->shared_from_this();
378378

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

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

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 (uint32_t i = 1; i < static_cast<uint32_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)