code style only: wrap after open parenthesis if not in one line (#977)
Signed-off-by: Dirk Thomas <dirk-thomas@users.noreply.github.com>
This commit is contained in:
parent
c2b855897f
commit
7c1721a0b3
8 changed files with 39 additions and 32 deletions
|
@ -227,12 +227,10 @@ public:
|
|||
// for the buffers that do not require ownership
|
||||
auto shared_msg = std::allocate_shared<MessageT, MessageAllocatorT>(*allocator, *message);
|
||||
|
||||
this->template add_shared_msg_to_buffers<MessageT>(shared_msg,
|
||||
sub_ids.take_shared_subscriptions);
|
||||
this->template add_shared_msg_to_buffers<MessageT>(
|
||||
shared_msg, sub_ids.take_shared_subscriptions);
|
||||
this->template add_owned_msg_to_buffers<MessageT, Alloc, Deleter>(
|
||||
std::move(message),
|
||||
sub_ids.take_ownership_subscriptions,
|
||||
allocator);
|
||||
std::move(message), sub_ids.take_ownership_subscriptions, allocator);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -265,8 +263,8 @@ public:
|
|||
// If there are no owning, just convert to shared.
|
||||
std::shared_ptr<MessageT> shared_msg = std::move(message);
|
||||
if (!sub_ids.take_shared_subscriptions.empty()) {
|
||||
this->template add_shared_msg_to_buffers<MessageT>(shared_msg,
|
||||
sub_ids.take_shared_subscriptions);
|
||||
this->template add_shared_msg_to_buffers<MessageT>(
|
||||
shared_msg, sub_ids.take_shared_subscriptions);
|
||||
}
|
||||
return shared_msg;
|
||||
} else {
|
||||
|
|
|
@ -271,10 +271,11 @@ public:
|
|||
{
|
||||
return get_parameter_impl(
|
||||
parameter_name,
|
||||
std::function<T()>([¶meter_name]() -> T
|
||||
{
|
||||
throw std::runtime_error("Parameter '" + parameter_name + "' is not set");
|
||||
})
|
||||
std::function<T()>(
|
||||
[¶meter_name]() -> T
|
||||
{
|
||||
throw std::runtime_error("Parameter '" + parameter_name + "' is not set");
|
||||
})
|
||||
);
|
||||
}
|
||||
|
||||
|
|
|
@ -170,19 +170,23 @@ public:
|
|||
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;
|
||||
});
|
||||
|
|
|
@ -95,10 +95,8 @@ Context::init(
|
|||
rclcpp::exceptions::throw_from_rcl_error(ret, "failed to initialize rcl");
|
||||
}
|
||||
try {
|
||||
std::vector<std::string> unparsed_ros_arguments =
|
||||
detail::get_unparsed_ros_arguments(argc, argv,
|
||||
&(rcl_context_->global_arguments),
|
||||
rcl_get_default_allocator());
|
||||
std::vector<std::string> 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));
|
||||
}
|
||||
|
|
|
@ -204,8 +204,9 @@ Duration::operator*(double scale) const
|
|||
scale,
|
||||
std::numeric_limits<rcl_duration_value_t>::max());
|
||||
long double scale_ld = static_cast<long double>(scale);
|
||||
return Duration(static_cast<rcl_duration_value_t>(
|
||||
static_cast<long double>(rcl_duration_.nanoseconds) * scale_ld));
|
||||
return Duration(
|
||||
static_cast<rcl_duration_value_t>(
|
||||
static_cast<long double>(rcl_duration_.nanoseconds) * scale_ld));
|
||||
}
|
||||
|
||||
rcl_duration_value_t
|
||||
|
|
|
@ -116,10 +116,8 @@ NodeOptions::get_rcl_node_options() const
|
|||
throw_from_rcl_error(ret, "failed to parse arguments");
|
||||
}
|
||||
|
||||
std::vector<std::string> unparsed_ros_arguments =
|
||||
detail::get_unparsed_ros_arguments(c_argc, c_argv.get(),
|
||||
&(node_options_->arguments),
|
||||
this->allocator_);
|
||||
std::vector<std::string> 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));
|
||||
}
|
||||
|
|
|
@ -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",
|
||||
|
|
|
@ -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<std::string> & args = options.arguments();
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue