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

raise warning level #61

Merged
merged 1 commit into from
Jul 21, 2015
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
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,7 +138,7 @@ class Client : public ClientBase
SharedFuture async_send_request(
typename ServiceT::Request::SharedPtr & request)
{
return async_send_request(request, [](SharedFuture f) {});
return async_send_request(request, [](SharedFuture) {});
}

SharedFuture async_send_request(
Expand Down
2 changes: 2 additions & 0 deletions rclcpp/include/rclcpp/memory_strategy.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,11 +39,13 @@ class MemoryStrategy
RCLCPP_MAKE_SHARED_DEFINITIONS(MemoryStrategy);
virtual void ** borrow_handles(HandleType type, size_t number_of_handles)
{
(void)type;
return static_cast<void **>(alloc(sizeof(void *) * number_of_handles));
}

virtual void return_handles(HandleType type, void ** handles)
{
(void)type;
this->free(handles);
}

Expand Down
12 changes: 6 additions & 6 deletions rclcpp/include/rclcpp/parameter_service.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ class ParameterService
{
get_parameters_service_ = node_->create_service<rcl_interfaces::srv::GetParameters>(
node_->get_name() + "__get_parameters", [&node](
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<rmw_request_id_t>,
const std::shared_ptr<rcl_interfaces::srv::GetParameters::Request> request,
std::shared_ptr<rcl_interfaces::srv::GetParameters::Response> response)
{
Expand All @@ -63,7 +63,7 @@ class ParameterService

get_parameter_types_service_ = node_->create_service<rcl_interfaces::srv::GetParameterTypes>(
node_->get_name() + "__get_parameter_types", [&node](
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<rmw_request_id_t>,
const std::shared_ptr<rcl_interfaces::srv::GetParameterTypes::Request> request,
std::shared_ptr<rcl_interfaces::srv::GetParameterTypes::Response> response)
{
Expand All @@ -77,7 +77,7 @@ class ParameterService

set_parameters_service_ = node_->create_service<rcl_interfaces::srv::SetParameters>(
node_->get_name() + "__set_parameters", [&node](
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<rmw_request_id_t>,
const std::shared_ptr<rcl_interfaces::srv::SetParameters::Request> request,
std::shared_ptr<rcl_interfaces::srv::SetParameters::Response> response)
{
Expand All @@ -96,7 +96,7 @@ class ParameterService
set_parameters_atomically_service_ =
node_->create_service<rcl_interfaces::srv::SetParametersAtomically>(
node_->get_name() + "__set_parameters_atomically", [&node](
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<rmw_request_id_t>,
const std::shared_ptr<rcl_interfaces::srv::SetParametersAtomically::Request> request,
std::shared_ptr<rcl_interfaces::srv::SetParametersAtomically::Response> response)
{
Expand All @@ -114,7 +114,7 @@ class ParameterService

describe_parameters_service_ = node_->create_service<rcl_interfaces::srv::DescribeParameters>(
node_->get_name() + "__describe_parameters", [&node](
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<rmw_request_id_t>,
const std::shared_ptr<rcl_interfaces::srv::DescribeParameters::Request> request,
std::shared_ptr<rcl_interfaces::srv::DescribeParameters::Response> response)
{
Expand All @@ -125,7 +125,7 @@ class ParameterService

list_parameters_service_ = node_->create_service<rcl_interfaces::srv::ListParameters>(
node_->get_name() + "__list_parameters", [&node](
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<rmw_request_id_t>,
const std::shared_ptr<rcl_interfaces::srv::ListParameters::Request> request,
std::shared_ptr<rcl_interfaces::srv::ListParameters::Response> response)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,7 @@ class StaticMemoryStrategy : public memory_strategy::MemoryStrategy

void return_handles(HandleType type, void ** handles)
{
(void)handles;
switch (type) {
case HandleType::subscriber_handle:
memset(subscriber_pool_, 0, max_subscribers_);
Expand Down
2 changes: 2 additions & 0 deletions rclcpp/include/rclcpp/utilities.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,8 @@ namespace utilities
void
init(int argc, char * argv[])
{
(void)argc;
(void)argv;
// TODO(wjwwood): Handle rmw_ret_t's value.
rmw_init();
#ifdef HAS_SIGACTION
Expand Down