Merge pull request #382 from ros2/remove_indent_off

remove obsolete INDENT-OFF usage
This commit is contained in:
Dirk Thomas 2017-09-29 14:24:31 -07:00 committed by GitHub
commit 070b3125c1
8 changed files with 20 additions and 51 deletions

View file

@ -52,13 +52,11 @@ public:
auto it = sub_contexts_.find(type_i);
if (it == sub_contexts_.end()) {
// It doesn't exist yet, make it
// *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
sub_context = std::shared_ptr<SubContext>(
new SubContext(std::forward<Args>(args) ...),
[](SubContext * sub_context_ptr) {
delete sub_context_ptr;
});
// *INDENT-ON*
sub_contexts_[type_i] = sub_context;
} else {
// It exists, get it out and cast it.

View file

@ -228,11 +228,11 @@ private:
typename std::vector<element, VectorAlloc>::iterator
get_iterator_of_key(uint64_t key)
{
// *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
auto it = std::find_if(elements_.begin(), elements_.end(), [key](element & e) -> bool {
auto it = std::find_if(
elements_.begin(), elements_.end(),
[key](element & e) -> bool {
return e.key == key && e.in_use;
});
// *INDENT-ON*
return it;
}

View file

@ -205,20 +205,18 @@ public:
T
get_parameter(const std::string & parameter_name, const T & default_value)
{
// *INDENT-OFF*
return get_parameter_impl(parameter_name,
return get_parameter_impl(
parameter_name,
std::function<T()>([&default_value]() -> T {return default_value;}));
// *INDENT-ON*
}
template<typename T>
T
get_parameter(const std::string & parameter_name)
{
// *INDENT-OFF*
return get_parameter_impl(parameter_name,
return get_parameter_impl(
parameter_name,
std::function<T()>([]() -> T {throw std::runtime_error("Parameter not set");}));
// *INDENT-ON*
}
RCLCPP_PUBLIC

View file

@ -99,7 +99,6 @@ ClientBase::wait_for_service_nanoseconds(std::chrono::nanoseconds timeout)
time_to_wait = std::chrono::nanoseconds(0);
}
// continue forever if timeout is negative, otherwise continue until out of time_to_wait
// *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
do {
if (!rclcpp::utilities::ok()) {
return false;
@ -115,8 +114,7 @@ ClientBase::wait_for_service_nanoseconds(std::chrono::nanoseconds timeout)
}
// server is not ready, loop if there is time left
time_to_wait = timeout - (std::chrono::steady_clock::now() - start);
} while (timeout < std::chrono::nanoseconds(0) || time_to_wait > std::chrono::nanoseconds(0));
// *INDENT-ON*
} while (time_to_wait > std::chrono::nanoseconds(0) || timeout < std::chrono::nanoseconds(0));
return false; // timeout exceeded while waiting for the server to be ready
}

View file

@ -131,14 +131,12 @@ Executor::remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node
weak_nodes_.erase(
std::remove_if(
weak_nodes_.begin(), weak_nodes_.end(),
// *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
[&](rclcpp::node_interfaces::NodeBaseInterface::WeakPtr & i)
{
bool matched = (i.lock() == node_ptr);
node_removed |= matched;
return matched;
}
// *INDENT-ON*
)
);
std::atomic_bool & has_executor = node_ptr->get_associated_with_executor_atomic();
@ -361,12 +359,10 @@ Executor::wait_for_work(std::chrono::nanoseconds timeout)
weak_nodes_.erase(
remove_if(
weak_nodes_.begin(), weak_nodes_.end(),
// *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
[](rclcpp::node_interfaces::NodeBaseInterface::WeakPtr i)
{
return i.expired();
}
// *INDENT-ON*
)
);
}

View file

@ -115,7 +115,6 @@ AsyncParametersClient::get_parameters(
auto request = std::make_shared<rcl_interfaces::srv::GetParameters::Request>();
request->names = names;
// *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
get_parameters_client_->async_send_request(
request,
[request, promise_result, future_result, &callback](
@ -139,7 +138,6 @@ AsyncParametersClient::get_parameters(
}
}
);
// *INDENT-ON*
return future_result;
}
@ -158,7 +156,6 @@ AsyncParametersClient::get_parameter_types(
auto request = std::make_shared<rcl_interfaces::srv::GetParameterTypes::Request>();
request->names = names;
// *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
get_parameter_types_client_->async_send_request(
request,
[promise_result, future_result, &callback](
@ -175,7 +172,6 @@ AsyncParametersClient::get_parameter_types(
}
}
);
// *INDENT-ON*
return future_result;
}
@ -193,7 +189,6 @@ AsyncParametersClient::set_parameters(
auto request = std::make_shared<rcl_interfaces::srv::SetParameters::Request>();
// *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
std::transform(parameters.begin(), parameters.end(), std::back_inserter(request->parameters),
[](rclcpp::parameter::ParameterVariant p) {
return p.to_parameter();
@ -211,7 +206,6 @@ AsyncParametersClient::set_parameters(
}
}
);
// *INDENT-ON*
return future_result;
}
@ -229,7 +223,6 @@ AsyncParametersClient::set_parameters_atomically(
auto request = std::make_shared<rcl_interfaces::srv::SetParametersAtomically::Request>();
// *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
std::transform(parameters.begin(), parameters.end(), std::back_inserter(request->parameters),
[](rclcpp::parameter::ParameterVariant p) {
return p.to_parameter();
@ -247,7 +240,6 @@ AsyncParametersClient::set_parameters_atomically(
}
}
);
// *INDENT-ON*
return future_result;
}
@ -268,7 +260,6 @@ AsyncParametersClient::list_parameters(
request->prefixes = prefixes;
request->depth = depth;
// *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
list_parameters_client_->async_send_request(
request,
[promise_result, future_result, &callback](
@ -280,7 +271,6 @@ AsyncParametersClient::list_parameters(
}
}
);
// *INDENT-ON*
return future_result;
}

View file

@ -29,7 +29,6 @@ ParameterService::ParameterService(
: node_(node)
{
std::weak_ptr<rclcpp::node::Node> captured_node = node_;
// *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
get_parameters_service_ = node_->create_service<rcl_interfaces::srv::GetParameters>(
std::string(node_->get_name()) + "/" + parameter_service_names::get_parameters,
[captured_node](
@ -46,8 +45,7 @@ ParameterService::ParameterService(
response->values.push_back(pvariant.get_parameter_value());
}
},
qos_profile
);
qos_profile);
get_parameter_types_service_ = node_->create_service<rcl_interfaces::srv::GetParameterTypes>(
std::string(node_->get_name()) + "/" + parameter_service_names::get_parameter_types,
@ -66,8 +64,7 @@ ParameterService::ParameterService(
return static_cast<rclcpp::parameter::ParameterType>(type);
});
},
qos_profile
);
qos_profile);
set_parameters_service_ = node_->create_service<rcl_interfaces::srv::SetParameters>(
std::string(node_->get_name()) + "/" + parameter_service_names::set_parameters,
@ -87,8 +84,7 @@ ParameterService::ParameterService(
auto results = node->set_parameters(pvariants);
response->results = results;
},
qos_profile
);
qos_profile);
set_parameters_atomically_service_ =
node_->create_service<rcl_interfaces::srv::SetParametersAtomically>(
@ -106,14 +102,12 @@ ParameterService::ParameterService(
std::transform(request->parameters.cbegin(), request->parameters.cend(),
std::back_inserter(pvariants),
[](const rcl_interfaces::msg::Parameter & p) {
return rclcpp::parameter::ParameterVariant::
from_parameter(p);
return rclcpp::parameter::ParameterVariant::from_parameter(p);
});
auto result = node->set_parameters_atomically(pvariants);
response->result = result;
},
qos_profile
);
qos_profile);
describe_parameters_service_ = node_->create_service<rcl_interfaces::srv::DescribeParameters>(
std::string(node_->get_name()) + "/" + parameter_service_names::describe_parameters,
@ -129,8 +123,7 @@ ParameterService::ParameterService(
auto descriptors = node->describe_parameters(request->names);
response->descriptors = descriptors;
},
qos_profile
);
qos_profile);
list_parameters_service_ = node_->create_service<rcl_interfaces::srv::ListParameters>(
std::string(node_->get_name()) + "/" + parameter_service_names::list_parameters,
@ -146,7 +139,5 @@ ParameterService::ParameterService(
auto result = node->list_parameters(request->prefixes, request->depth);
response->result = result;
},
qos_profile
);
// *INDENT-ON*
qos_profile);
}

View file

@ -139,12 +139,10 @@ signal_handler(int signal_value)
old_action.sa_sigaction(signal_value, siginfo, context);
}
} else {
// *INDENT-OFF*
if (
old_action.sa_handler != NULL && // Is set
old_action.sa_handler != SIG_DFL && // Is not default
old_action.sa_handler != SIG_IGN) // Is not ignored
// *INDENT-ON*
{
old_action.sa_handler(signal_value);
}