Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[rclcpp_action] Add warnings #1405

Merged
merged 7 commits into from
Dec 19, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 4 additions & 1 deletion rclcpp_action/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,10 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic -Wnon-virtual-dtor -Woverloaded-virtual)
add_compile_options(
-Wall -Wextra -Wpedantic -Wnon-virtual-dtor -Woverloaded-virtual
-Wformat=2 -Wconversion -Wshadow -Wsign-conversion -Wcast-qual
)
endif()

set(${PROJECT_NAME}_SRCS
Expand Down
10 changes: 5 additions & 5 deletions rclcpp_action/include/rclcpp_action/server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -381,31 +381,31 @@ class Server : public ServerBase, public std::enable_shared_from_this<Server<Act
std::weak_ptr<Server<ActionT>> weak_this = this->shared_from_this();

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

std::function<void(const GoalUUID &)> on_executing =
[weak_this](const GoalUUID & uuid)
[weak_this](const GoalUUID & goal_uuid)
{
std::shared_ptr<Server<ActionT>> shared_this = weak_this.lock();
if (!shared_this) {
return;
}
(void)uuid;
(void)goal_uuid;
// Publish a status message any time a goal handle changes state
shared_this->publish_status();
};
Expand Down
6 changes: 3 additions & 3 deletions rclcpp_action/src/server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -474,10 +474,10 @@ ServerBase::execute_result_request_received(std::shared_ptr<void> & data)

if (result_response) {
// Send the result now
rcl_ret_t ret = rcl_action_send_result_response(
rcl_ret_t rcl_ret = rcl_action_send_result_response(
pimpl_->action_server_.get(), &request_header, result_response.get());
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret);
if (RCL_RET_OK != rcl_ret) {
rclcpp::exceptions::throw_from_rcl_error(rcl_ret);
}
} else {
// Store the request so it can be responded to later
Expand Down
12 changes: 6 additions & 6 deletions rclcpp_action/test/benchmark/benchmark_action_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ class ActionClientPerformanceTest : public PerformanceTest

// Should be checked by the server above
assert(goal->order > 0);
result->sequence.resize(goal->order);
result->sequence.resize(static_cast<size_t>(goal->order));
clalancette marked this conversation as resolved.
Show resolved Hide resolved
result->sequence[0] = 0;
if (goal->order == 1) {
current_goal_handle->succeed(result);
Expand All @@ -92,7 +92,7 @@ class ActionClientPerformanceTest : public PerformanceTest
current_goal_handle->succeed(result);
return;
}
for (int i = 2; i < goal->order; ++i) {
for (size_t i = 2; i < static_cast<size_t>(goal->order); ++i) {
clalancette marked this conversation as resolved.
Show resolved Hide resolved
result->sequence[i] =
result->sequence[i - 1] + result->sequence[i - 2];
}
Expand Down Expand Up @@ -310,8 +310,8 @@ BENCHMARK_F(ActionClientPerformanceTest, async_cancel_goal)(benchmark::State & s
rclcpp::spin_until_future_complete(node, future_cancel, std::chrono::seconds(1));
auto cancel_response = future_cancel.get();

using CancelResponse = test_msgs::action::Fibonacci::Impl::CancelGoalService::Response;
if (CancelResponse::ERROR_NONE != cancel_response->return_code) {
using CancelActionResponse = test_msgs::action::Fibonacci::Impl::CancelGoalService::Response;
clalancette marked this conversation as resolved.
Show resolved Hide resolved
if (CancelActionResponse::ERROR_NONE != cancel_response->return_code) {
state.SkipWithError("Cancel request did not succeed");
break;
}
Expand Down Expand Up @@ -345,8 +345,8 @@ BENCHMARK_F(ActionClientPerformanceTest, async_cancel_all_goals)(benchmark::Stat
rclcpp::spin_until_future_complete(node, future_cancel_all, std::chrono::seconds(1));
auto cancel_response = future_cancel_all.get();

using CancelResponse = test_msgs::action::Fibonacci::Impl::CancelGoalService::Response;
if (CancelResponse::ERROR_NONE != cancel_response->return_code) {
using CancelActionResponse = test_msgs::action::Fibonacci::Impl::CancelGoalService::Response;
if (CancelActionResponse::ERROR_NONE != cancel_response->return_code) {
state.SkipWithError("Cancel request did not succeed");
break;
}
Expand Down
16 changes: 8 additions & 8 deletions rclcpp_action/test/benchmark/benchmark_action_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -187,8 +187,8 @@ BENCHMARK_F(ActionServerPerformanceTest, action_server_cancel_goal)(benchmark::S

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

reset_heap_counters();
Expand Down Expand Up @@ -291,12 +291,12 @@ BENCHMARK_F(ActionServerPerformanceTest, action_server_abort)(benchmark::State &

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

reset_heap_counters();
Expand Down
2 changes: 1 addition & 1 deletion rclcpp_action/test/test_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ class TestClient : public ::testing::Test
feedback_message.feedback.sequence.push_back(1);
feedback_publisher->publish(feedback_message);
client_executor.spin_once();
for (int i = 1; i < goal_request->goal.order; ++i) {
for (size_t i = 1; i < static_cast<size_t>(goal_request->goal.order); ++i) {
clalancette marked this conversation as resolved.
Show resolved Hide resolved
feedback_message.feedback.sequence.push_back(
feedback_message.feedback.sequence[i] +
feedback_message.feedback.sequence[i - 1]);
Expand Down
4 changes: 2 additions & 2 deletions rclcpp_action/test/test_types.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,12 +25,12 @@ TEST(TestActionTypes, goal_uuid_to_string) {
EXPECT_STREQ("0123456789abcdef", rclcpp_action::to_string(goal_id).c_str());

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

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