From 7c1721a0b390be8242a6b824489d0bc861f6a0ad Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Mon, 3 Feb 2020 09:06:57 -0800 Subject: [PATCH] code style only: wrap after open parenthesis if not in one line (#977) Signed-off-by: Dirk Thomas --- .../experimental/intra_process_manager.hpp | 12 +++++------- rclcpp/include/rclcpp/parameter_client.hpp | 9 +++++---- .../strategies/allocator_memory_strategy.hpp | 12 ++++++++---- rclcpp/src/rclcpp/context.cpp | 6 ++---- rclcpp/src/rclcpp/duration.cpp | 5 +++-- rclcpp/src/rclcpp/node_options.cpp | 6 ++---- rclcpp/test/test_node.cpp | 3 ++- rclcpp/test/test_node_options.cpp | 18 ++++++++++++------ 8 files changed, 39 insertions(+), 32 deletions(-) diff --git a/rclcpp/include/rclcpp/experimental/intra_process_manager.hpp b/rclcpp/include/rclcpp/experimental/intra_process_manager.hpp index 7c216c6725..d671de701e 100644 --- a/rclcpp/include/rclcpp/experimental/intra_process_manager.hpp +++ b/rclcpp/include/rclcpp/experimental/intra_process_manager.hpp @@ -227,12 +227,10 @@ class IntraProcessManager // for the buffers that do not require ownership auto shared_msg = std::allocate_shared(*allocator, *message); - this->template add_shared_msg_to_buffers(shared_msg, - sub_ids.take_shared_subscriptions); + this->template add_shared_msg_to_buffers( + shared_msg, sub_ids.take_shared_subscriptions); this->template add_owned_msg_to_buffers( - std::move(message), - sub_ids.take_ownership_subscriptions, - allocator); + std::move(message), sub_ids.take_ownership_subscriptions, allocator); } } @@ -265,8 +263,8 @@ class IntraProcessManager // If there are no owning, just convert to shared. std::shared_ptr shared_msg = std::move(message); if (!sub_ids.take_shared_subscriptions.empty()) { - this->template add_shared_msg_to_buffers(shared_msg, - sub_ids.take_shared_subscriptions); + this->template add_shared_msg_to_buffers( + shared_msg, sub_ids.take_shared_subscriptions); } return shared_msg; } else { diff --git a/rclcpp/include/rclcpp/parameter_client.hpp b/rclcpp/include/rclcpp/parameter_client.hpp index 2cf09d8ae4..73053617dc 100644 --- a/rclcpp/include/rclcpp/parameter_client.hpp +++ b/rclcpp/include/rclcpp/parameter_client.hpp @@ -271,10 +271,11 @@ class SyncParametersClient { return get_parameter_impl( parameter_name, - std::function([¶meter_name]() -> T - { - throw std::runtime_error("Parameter '" + parameter_name + "' is not set"); - }) + std::function( + [¶meter_name]() -> T + { + throw std::runtime_error("Parameter '" + parameter_name + "' is not set"); + }) ); } diff --git a/rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp b/rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp index 905b203918..dae737060b 100644 --- a/rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp +++ b/rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp @@ -170,19 +170,23 @@ class AllocatorMemoryStrategy : public memory_strategy::MemoryStrategy return false; }); - group->find_service_ptrs_if([this](const rclcpp::ServiceBase::SharedPtr & service) { + group->find_service_ptrs_if( + [this](const rclcpp::ServiceBase::SharedPtr & service) { service_handles_.push_back(service->get_service_handle()); return false; }); - group->find_client_ptrs_if([this](const rclcpp::ClientBase::SharedPtr & client) { + group->find_client_ptrs_if( + [this](const rclcpp::ClientBase::SharedPtr & client) { client_handles_.push_back(client->get_client_handle()); return false; }); - group->find_timer_ptrs_if([this](const rclcpp::TimerBase::SharedPtr & timer) { + group->find_timer_ptrs_if( + [this](const rclcpp::TimerBase::SharedPtr & timer) { timer_handles_.push_back(timer->get_timer_handle()); return false; }); - group->find_waitable_ptrs_if([this](const rclcpp::Waitable::SharedPtr & waitable) { + group->find_waitable_ptrs_if( + [this](const rclcpp::Waitable::SharedPtr & waitable) { waitable_handles_.push_back(waitable); return false; }); diff --git a/rclcpp/src/rclcpp/context.cpp b/rclcpp/src/rclcpp/context.cpp index 8777e5f721..57937d35fb 100644 --- a/rclcpp/src/rclcpp/context.cpp +++ b/rclcpp/src/rclcpp/context.cpp @@ -95,10 +95,8 @@ Context::init( rclcpp::exceptions::throw_from_rcl_error(ret, "failed to initialize rcl"); } try { - std::vector unparsed_ros_arguments = - detail::get_unparsed_ros_arguments(argc, argv, - &(rcl_context_->global_arguments), - rcl_get_default_allocator()); + std::vector unparsed_ros_arguments = detail::get_unparsed_ros_arguments( + argc, argv, &(rcl_context_->global_arguments), rcl_get_default_allocator()); if (!unparsed_ros_arguments.empty()) { throw exceptions::UnknownROSArgsError(std::move(unparsed_ros_arguments)); } diff --git a/rclcpp/src/rclcpp/duration.cpp b/rclcpp/src/rclcpp/duration.cpp index 07d3698dda..2114ddd16f 100644 --- a/rclcpp/src/rclcpp/duration.cpp +++ b/rclcpp/src/rclcpp/duration.cpp @@ -204,8 +204,9 @@ Duration::operator*(double scale) const scale, std::numeric_limits::max()); long double scale_ld = static_cast(scale); - return Duration(static_cast( - static_cast(rcl_duration_.nanoseconds) * scale_ld)); + return Duration( + static_cast( + static_cast(rcl_duration_.nanoseconds) * scale_ld)); } rcl_duration_value_t diff --git a/rclcpp/src/rclcpp/node_options.cpp b/rclcpp/src/rclcpp/node_options.cpp index 0852f3d946..af424ae106 100644 --- a/rclcpp/src/rclcpp/node_options.cpp +++ b/rclcpp/src/rclcpp/node_options.cpp @@ -116,10 +116,8 @@ NodeOptions::get_rcl_node_options() const throw_from_rcl_error(ret, "failed to parse arguments"); } - std::vector unparsed_ros_arguments = - detail::get_unparsed_ros_arguments(c_argc, c_argv.get(), - &(node_options_->arguments), - this->allocator_); + std::vector unparsed_ros_arguments = detail::get_unparsed_ros_arguments( + c_argc, c_argv.get(), &(node_options_->arguments), this->allocator_); if (!unparsed_ros_arguments.empty()) { throw exceptions::UnknownROSArgsError(std::move(unparsed_ros_arguments)); } diff --git a/rclcpp/test/test_node.cpp b/rclcpp/test/test_node.cpp index 213252d79b..2bab00e678 100644 --- a/rclcpp/test/test_node.cpp +++ b/rclcpp/test/test_node.cpp @@ -687,7 +687,8 @@ TEST_F(TestNode, declare_parameter_with_cli_overrides) { test_resources_path / "test_parameters.yaml").string(); // test cases with overrides rclcpp::NodeOptions no; - no.arguments({ + no.arguments( + { "--ros-args", "-p", "parameter_bool:=true", "-p", "parameter_int:=42", diff --git a/rclcpp/test/test_node_options.cpp b/rclcpp/test/test_node_options.cpp index 7ffe070adf..a90cfd1f02 100644 --- a/rclcpp/test/test_node_options.cpp +++ b/rclcpp/test/test_node_options.cpp @@ -35,14 +35,16 @@ TEST(TestNodeOptions, ros_args_only) { ASSERT_EQ(0, rcl_arguments_get_count_unparsed_ros(&rcl_options->arguments)); char * node_name = nullptr; - EXPECT_EQ(RCL_RET_OK, rcl_remap_node_name( + EXPECT_EQ( + RCL_RET_OK, rcl_remap_node_name( &rcl_options->arguments, nullptr, "my_node", allocator, &node_name)); ASSERT_TRUE(node_name != nullptr); EXPECT_STREQ("some_node", node_name); allocator.deallocate(node_name, allocator.state); char * namespace_name = nullptr; - EXPECT_EQ(RCL_RET_OK, rcl_remap_node_namespace( + EXPECT_EQ( + RCL_RET_OK, rcl_remap_node_namespace( &rcl_options->arguments, nullptr, "my_ns", allocator, &namespace_name)); ASSERT_TRUE(namespace_name != nullptr); EXPECT_STREQ("/some_ns", namespace_name); @@ -51,7 +53,8 @@ TEST(TestNodeOptions, ros_args_only) { TEST(TestNodeOptions, ros_args_and_non_ros_args) { rcl_allocator_t allocator = rcl_get_default_allocator(); - auto options = rclcpp::NodeOptions(allocator).arguments({ + auto options = rclcpp::NodeOptions(allocator).arguments( + { "--non-ros-flag", "--ros-args", "-r", "__node:=some_node", "-r", "__ns:=/some_ns", "--", "non-ros-arg"}); @@ -61,21 +64,24 @@ TEST(TestNodeOptions, ros_args_and_non_ros_args) { ASSERT_EQ(2, rcl_arguments_get_count_unparsed(&rcl_options->arguments)); char * node_name = nullptr; - EXPECT_EQ(RCL_RET_OK, rcl_remap_node_name( + EXPECT_EQ( + RCL_RET_OK, rcl_remap_node_name( &rcl_options->arguments, nullptr, "my_node", allocator, &node_name)); ASSERT_TRUE(node_name != nullptr); EXPECT_STREQ("some_node", node_name); allocator.deallocate(node_name, allocator.state); char * namespace_name = nullptr; - EXPECT_EQ(RCL_RET_OK, rcl_remap_node_namespace( + EXPECT_EQ( + RCL_RET_OK, rcl_remap_node_namespace( &rcl_options->arguments, nullptr, "my_ns", allocator, &namespace_name)); ASSERT_TRUE(namespace_name != nullptr); EXPECT_STREQ("/some_ns", namespace_name); allocator.deallocate(namespace_name, allocator.state); int * output_indices = nullptr; - EXPECT_EQ(RCL_RET_OK, rcl_arguments_get_unparsed( + EXPECT_EQ( + RCL_RET_OK, rcl_arguments_get_unparsed( &rcl_options->arguments, allocator, &output_indices)); ASSERT_TRUE(output_indices != nullptr); const std::vector & args = options.arguments();