Skip to content

Commit

Permalink
Add line break after first open paren in multiline function call (#785)
Browse files Browse the repository at this point in the history
* Add line break after first open paren in multiline function call

as per developer guide:
https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#open-versus-cuddled-braces
see ament/ament_lint#148

Signed-off-by: Dan Rose <dan@digilabs.io>

Fix dedent when first function argument starts with a brace

Signed-off-by: Dan Rose <dan@digilabs.io>

Line break with multiline if condition
Remove line breaks where allowed.

Signed-off-by: Dan Rose <dan@digilabs.io>

Fixup after rebase

Signed-off-by: Dan Rose <dan@digilabs.io>

Fixup again after reverting indent_paren_open_brace

Signed-off-by: Dan Rose <dan@digilabs.io>

* Revert comment spacing change, condense some lines

Signed-off-by: Dan Rose <dan@digilabs.io>
  • Loading branch information
rotu authored and dirk-thomas committed Aug 7, 2019
1 parent dc3c36c commit 4a5eed9
Show file tree
Hide file tree
Showing 41 changed files with 588 additions and 367 deletions.
9 changes: 6 additions & 3 deletions rclcpp/include/rclcpp/any_subscription_callback.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -184,10 +184,12 @@ class AnySubscriptionCallback
} else if (const_shared_ptr_with_info_callback_) {
const_shared_ptr_with_info_callback_(message, message_info);
} else {
if (unique_ptr_callback_ || unique_ptr_with_info_callback_ ||
if (
unique_ptr_callback_ || unique_ptr_with_info_callback_ ||
shared_ptr_callback_ || shared_ptr_with_info_callback_)
{
throw std::runtime_error("unexpected dispatch_intra_process const shared "
throw std::runtime_error(
"unexpected dispatch_intra_process const shared "
"message call with no const shared_ptr callback");
} else {
throw std::runtime_error("unexpected message without any callback set");
Expand All @@ -209,7 +211,8 @@ class AnySubscriptionCallback
} else if (unique_ptr_with_info_callback_) {
unique_ptr_with_info_callback_(std::move(message), message_info);
} else if (const_shared_ptr_callback_ || const_shared_ptr_with_info_callback_) {
throw std::runtime_error("unexpected dispatch_intra_process unique message call"
throw std::runtime_error(
"unexpected dispatch_intra_process unique message call"
" with const shared_ptr callback");
} else {
throw std::runtime_error("unexpected message without any callback set");
Expand Down
21 changes: 11 additions & 10 deletions rclcpp/include/rclcpp/message_memory_strategy.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,16 +95,17 @@ class MessageMemoryStrategy
rclcpp::exceptions::throw_from_rcl_error(ret);
}

auto serialized_msg = std::shared_ptr<rcl_serialized_message_t>(msg,
[](rmw_serialized_message_t * msg) {
auto ret = rmw_serialized_message_fini(msg);
delete msg;
if (ret != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"failed to destroy serialized message: %s", rcl_get_error_string().str);
}
});
auto serialized_msg = std::shared_ptr<rcl_serialized_message_t>(
msg,
[](rmw_serialized_message_t * msg) {
auto ret = rmw_serialized_message_fini(msg);
delete msg;
if (ret != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"failed to destroy serialized message: %s", rcl_get_error_string().str);
}
});

return serialized_msg;
}
Expand Down
4 changes: 1 addition & 3 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -404,9 +404,7 @@ Node::get_parameter_or_set(

bool got_parameter = get_parameter(sub_name, value);
if (!got_parameter) {
this->set_parameters({
rclcpp::Parameter(sub_name, alternative_value),
});
this->set_parameters({rclcpp::Parameter(sub_name, alternative_value), });
value = alternative_value;
}
}
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/include/rclcpp/publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,12 +70,12 @@ class Publisher : public PublisherBase
allocator::set_allocator_for_deleter(&message_deleter_, message_allocator_.get());

if (event_callbacks.deadline_callback) {
this->add_event_handler(event_callbacks.deadline_callback,
this->add_event_handler(
event_callbacks.deadline_callback,
RCL_PUBLISHER_OFFERED_DEADLINE_MISSED);
}
if (event_callbacks.liveliness_callback) {
this->add_event_handler(event_callbacks.liveliness_callback,
RCL_PUBLISHER_LIVELINESS_LOST);
this->add_event_handler(event_callbacks.liveliness_callback, RCL_PUBLISHER_LIVELINESS_LOST);
}
}

Expand Down
6 changes: 4 additions & 2 deletions rclcpp/include/rclcpp/subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,11 +100,13 @@ class Subscription : public SubscriptionBase
message_memory_strategy_(memory_strategy)
{
if (event_callbacks.deadline_callback) {
this->add_event_handler(event_callbacks.deadline_callback,
this->add_event_handler(
event_callbacks.deadline_callback,
RCL_SUBSCRIPTION_REQUESTED_DEADLINE_MISSED);
}
if (event_callbacks.liveliness_callback) {
this->add_event_handler(event_callbacks.liveliness_callback,
this->add_event_handler(
event_callbacks.liveliness_callback,
RCL_SUBSCRIPTION_LIVELINESS_CHANGED);
}
}
Expand Down
5 changes: 3 additions & 2 deletions rclcpp/src/rclcpp/clock.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,8 +119,9 @@ Clock::create_jump_callback(
}

// Try to add the jump callback to the clock
rcl_ret_t ret = rcl_clock_add_jump_callback(&rcl_clock_, threshold,
Clock::on_time_jump, handler.get());
rcl_ret_t ret = rcl_clock_add_jump_callback(
&rcl_clock_, threshold, Clock::on_time_jump,
handler.get());
if (RCL_RET_OK != ret) {
exceptions::throw_from_rcl_error(ret, "Failed to add time jump callback");
}
Expand Down
3 changes: 2 additions & 1 deletion rclcpp/src/rclcpp/node_interfaces/node_graph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,8 @@ NodeGraph::get_node_names() const
std::vector<std::string> nodes;
auto names_and_namespaces = get_node_names_and_namespaces();

std::transform(names_and_namespaces.begin(),
std::transform(
names_and_namespaces.begin(),
names_and_namespaces.end(),
std::back_inserter(nodes),
[](std::pair<std::string, std::string> nns) {
Expand Down
34 changes: 17 additions & 17 deletions rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -242,9 +242,7 @@ __check_parameter_value_in_range(
if (!descriptor.floating_point_range.empty() && value.get_type() == rclcpp::PARAMETER_DOUBLE) {
double v = value.get<double>();
auto fp_range = descriptor.floating_point_range.at(0);
if (__are_doubles_equal(v, fp_range.from_value) ||
__are_doubles_equal(v, fp_range.to_value))
{
if (__are_doubles_equal(v, fp_range.from_value) || __are_doubles_equal(v, fp_range.to_value)) {
return result;
}
if ((v < fp_range.from_value) || (v > fp_range.to_value)) {
Expand Down Expand Up @@ -831,25 +829,27 @@ NodeParameters::list_parameters(const std::vector<std::string> & prefixes, uint6
bool get_all = (prefixes.size() == 0) &&
((depth == rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE) ||
(static_cast<uint64_t>(std::count(kv.first.begin(), kv.first.end(), *separator)) < depth));
bool prefix_matches = std::any_of(prefixes.cbegin(), prefixes.cend(),
[&kv, &depth, &separator](const std::string & prefix) {
if (kv.first == prefix) {
return true;
} else if (kv.first.find(prefix + separator) == 0) {
size_t length = prefix.length();
std::string substr = kv.first.substr(length);
// Cast as unsigned integer to avoid warning
return (depth == rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE) ||
(static_cast<uint64_t>(std::count(substr.begin(), substr.end(), *separator)) < depth);
}
return false;
});
bool prefix_matches = std::any_of(
prefixes.cbegin(), prefixes.cend(),
[&kv, &depth, &separator](const std::string & prefix) {
if (kv.first == prefix) {
return true;
} else if (kv.first.find(prefix + separator) == 0) {
size_t length = prefix.length();
std::string substr = kv.first.substr(length);
// Cast as unsigned integer to avoid warning
return (depth == rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE) ||
(static_cast<uint64_t>(std::count(substr.begin(), substr.end(), *separator)) < depth);
}
return false;
});
if (get_all || prefix_matches) {
result.names.push_back(kv.first);
size_t last_separator = kv.first.find_last_of(separator);
if (std::string::npos != last_separator) {
std::string prefix = kv.first.substr(0, last_separator);
if (std::find(result.prefixes.cbegin(), result.prefixes.cend(), prefix) ==
if (
std::find(result.prefixes.cbegin(), result.prefixes.cend(), prefix) ==
result.prefixes.cend())
{
result.prefixes.push_back(prefix);
Expand Down
56 changes: 32 additions & 24 deletions rclcpp/src/rclcpp/parameter_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,10 +71,11 @@ AsyncParametersClient::AsyncParametersClient(
node_services_interface->add_client(set_parameters_base, nullptr);

set_parameters_atomically_client_ =
Client<rcl_interfaces::srv::SetParametersAtomically>::make_shared(node_base_interface.get(),
node_graph_interface,
remote_node_name_ + "/" + parameter_service_names::set_parameters_atomically,
options);
Client<rcl_interfaces::srv::SetParametersAtomically>::make_shared(
node_base_interface.get(),
node_graph_interface,
remote_node_name_ + "/" + parameter_service_names::set_parameters_atomically,
options);
auto set_parameters_atomically_base = std::dynamic_pointer_cast<ClientBase>(
set_parameters_atomically_client_);
node_services_interface->add_client(set_parameters_atomically_base, nullptr);
Expand Down Expand Up @@ -150,8 +151,7 @@ AsyncParametersClient::get_parameters(
rcl_interfaces::msg::Parameter parameter;
parameter.name = request->names[i];
parameter.value = pvalue;
parameters.push_back(rclcpp::Parameter::from_parameter_msg(
parameter));
parameters.push_back(rclcpp::Parameter::from_parameter_msg(parameter));
}

promise_result->set_value(parameters);
Expand Down Expand Up @@ -211,10 +211,9 @@ AsyncParametersClient::set_parameters(

auto request = std::make_shared<rcl_interfaces::srv::SetParameters::Request>();

std::transform(parameters.begin(), parameters.end(), std::back_inserter(request->parameters),
[](rclcpp::Parameter p) {
return p.to_parameter_msg();
}
std::transform(
parameters.begin(), parameters.end(), std::back_inserter(request->parameters),
[](rclcpp::Parameter p) {return p.to_parameter_msg();}
);

set_parameters_client_->async_send_request(
Expand Down Expand Up @@ -245,10 +244,9 @@ AsyncParametersClient::set_parameters_atomically(

auto request = std::make_shared<rcl_interfaces::srv::SetParametersAtomically::Request>();

std::transform(parameters.begin(), parameters.end(), std::back_inserter(request->parameters),
[](rclcpp::Parameter p) {
return p.to_parameter_msg();
}
std::transform(
parameters.begin(), parameters.end(), std::back_inserter(request->parameters),
[](rclcpp::Parameter p) {return p.to_parameter_msg();}
);

set_parameters_atomically_client_->async_send_request(
Expand Down Expand Up @@ -411,8 +409,10 @@ SyncParametersClient::get_parameters(const std::vector<std::string> & parameter_
{
auto f = async_parameters_client_->get_parameters(parameter_names);
using rclcpp::executors::spin_node_until_future_complete;
if (spin_node_until_future_complete(*executor_, node_base_interface_, f) ==
rclcpp::executor::FutureReturnCode::SUCCESS)
if (
spin_node_until_future_complete(
*executor_, node_base_interface_,
f) == rclcpp::executor::FutureReturnCode::SUCCESS)
{
return f.get();
}
Expand All @@ -435,8 +435,10 @@ SyncParametersClient::get_parameter_types(const std::vector<std::string> & param
auto f = async_parameters_client_->get_parameter_types(parameter_names);

using rclcpp::executors::spin_node_until_future_complete;
if (spin_node_until_future_complete(*executor_, node_base_interface_, f) ==
rclcpp::executor::FutureReturnCode::SUCCESS)
if (
spin_node_until_future_complete(
*executor_, node_base_interface_,
f) == rclcpp::executor::FutureReturnCode::SUCCESS)
{
return f.get();
}
Expand All @@ -450,8 +452,10 @@ SyncParametersClient::set_parameters(
auto f = async_parameters_client_->set_parameters(parameters);

using rclcpp::executors::spin_node_until_future_complete;
if (spin_node_until_future_complete(*executor_, node_base_interface_, f) ==
rclcpp::executor::FutureReturnCode::SUCCESS)
if (
spin_node_until_future_complete(
*executor_, node_base_interface_,
f) == rclcpp::executor::FutureReturnCode::SUCCESS)
{
return f.get();
}
Expand All @@ -465,8 +469,10 @@ SyncParametersClient::set_parameters_atomically(
auto f = async_parameters_client_->set_parameters_atomically(parameters);

using rclcpp::executors::spin_node_until_future_complete;
if (spin_node_until_future_complete(*executor_, node_base_interface_, f) ==
rclcpp::executor::FutureReturnCode::SUCCESS)
if (
spin_node_until_future_complete(
*executor_, node_base_interface_,
f) == rclcpp::executor::FutureReturnCode::SUCCESS)
{
return f.get();
}
Expand All @@ -482,8 +488,10 @@ SyncParametersClient::list_parameters(
auto f = async_parameters_client_->list_parameters(parameter_prefixes, depth);

using rclcpp::executors::spin_node_until_future_complete;
if (spin_node_until_future_complete(*executor_, node_base_interface_, f) ==
rclcpp::executor::FutureReturnCode::SUCCESS)
if (
spin_node_until_future_complete(
*executor_, node_base_interface_,
f) == rclcpp::executor::FutureReturnCode::SUCCESS)
{
return f.get();
}
Expand Down
20 changes: 11 additions & 9 deletions rclcpp/src/rclcpp/parameter_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,10 +59,11 @@ ParameterService::ParameterService(
{
try {
auto types = node_params->get_parameter_types(request->names);
std::transform(types.cbegin(), types.cend(),
std::back_inserter(response->types), [](const uint8_t & type) {
return static_cast<rclcpp::ParameterType>(type);
});
std::transform(
types.cbegin(), types.cend(),
std::back_inserter(response->types), [](const uint8_t & type) {
return static_cast<rclcpp::ParameterType>(type);
});
} catch (const rclcpp::exceptions::ParameterNotDeclaredException & ex) {
RCLCPP_WARN(rclcpp::get_logger("rclcpp"), "Failed to get parameter types: %s", ex.what());
}
Expand Down Expand Up @@ -103,11 +104,12 @@ ParameterService::ParameterService(
std::shared_ptr<rcl_interfaces::srv::SetParametersAtomically::Response> response)
{
std::vector<rclcpp::Parameter> pvariants;
std::transform(request->parameters.cbegin(), request->parameters.cend(),
std::back_inserter(pvariants),
[](const rcl_interfaces::msg::Parameter & p) {
return rclcpp::Parameter::from_parameter_msg(p);
});
std::transform(
request->parameters.cbegin(), request->parameters.cend(),
std::back_inserter(pvariants),
[](const rcl_interfaces::msg::Parameter & p) {
return rclcpp::Parameter::from_parameter_msg(p);
});
try {
auto result = node_params->set_parameters_atomically(pvariants);
response->result = result;
Expand Down
6 changes: 4 additions & 2 deletions rclcpp/src/rclcpp/time_source.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,8 @@ void TimeSource::attachNode(
} else {
// TODO(wjwwood): use set_on_parameters_set_callback to catch the type mismatch,
// before the use_sim_time parameter can ever be set to an invalid value
RCLCPP_ERROR(logger_, "Invalid type '%s' for parameter 'use_sim_time', should be 'bool'",
RCLCPP_ERROR(
logger_, "Invalid type '%s' for parameter 'use_sim_time', should be 'bool'",
rclcpp::to_string(use_sim_time_param.get_type()).c_str());
}

Expand Down Expand Up @@ -154,7 +155,8 @@ void TimeSource::detachClock(std::shared_ptr<rclcpp::Clock> clock)

TimeSource::~TimeSource()
{
if (node_base_ || node_topics_ || node_graph_ || node_services_ ||
if (
node_base_ || node_topics_ || node_graph_ || node_services_ ||
node_logging_ || node_clock_ || node_parameters_)
{
this->detachNode();
Expand Down
13 changes: 8 additions & 5 deletions rclcpp/src/rclcpp/timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,8 @@ TimerBase::TimerBase(
*timer_handle_.get() = rcl_get_zero_initialized_timer();

rcl_clock_t * clock_handle = clock_->get_clock_handle();
if (rcl_timer_init(
if (
rcl_timer_init(
timer_handle_.get(), clock_handle, rcl_context.get(), period.count(), nullptr,
rcl_get_default_allocator()) != RCL_RET_OK)
{
Expand Down Expand Up @@ -110,12 +111,14 @@ std::chrono::nanoseconds
TimerBase::time_until_trigger()
{
int64_t time_until_next_call = 0;
if (rcl_timer_get_time_until_next_call(timer_handle_.get(),
&time_until_next_call) != RCL_RET_OK)
if (
rcl_timer_get_time_until_next_call(
timer_handle_.get(),
&time_until_next_call) != RCL_RET_OK)
{
throw std::runtime_error(
std::string("Timer could not get time until next call: ") +
rcl_get_error_string().str);
std::string(
"Timer could not get time until next call: ") + rcl_get_error_string().str);
}
return std::chrono::nanoseconds(time_until_next_call);
}
Expand Down
Loading

0 comments on commit 4a5eed9

Please sign in to comment.