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

Adapt to '--ros-args ... [--]'-based ROS args extraction #816

Merged
merged 7 commits into from
Aug 7, 2019
Merged
Show file tree
Hide file tree
Changes from 6 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
5 changes: 5 additions & 0 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -254,6 +254,11 @@ if(BUILD_TESTING)
)
target_link_libraries(test_node_global_args ${PROJECT_NAME})
endif()
ament_add_gtest(test_node_options test/test_node_options.cpp)
if(TARGET test_node_options)
ament_target_dependencies(test_node_options "rcl")
target_link_libraries(test_node_options ${PROJECT_NAME})
endif()
ament_add_gtest(test_parameter_client test/test_parameter_client.cpp)
if(TARGET test_parameter_client)
ament_target_dependencies(test_parameter_client
Expand Down
3 changes: 2 additions & 1 deletion rclcpp/include/rclcpp/node_options.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,8 @@ class NodeOptions
/// Set the arguments, return this for parameter idiom.
/**
* These arguments are used to extract remappings used by the node and other
* settings.
* settings. Being specific to a ROS node, an implicit `--ros-args` scope flag
* always precedes these arguments.
*
* This will cause the internal rcl_node_options_t struct to be invalidated.
*/
Expand Down
25 changes: 19 additions & 6 deletions rclcpp/src/rclcpp/node_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,11 +90,25 @@ NodeOptions::get_rcl_node_options() const
node_options_->use_global_arguments = this->use_global_arguments_;
node_options_->domain_id = this->get_domain_id_from_env();

std::unique_ptr<const char *[]> c_args;
int c_argc = 0;
std::unique_ptr<const char *[]> c_argv;
if (!this->arguments_.empty()) {
c_args.reset(new const char *[this->arguments_.size()]);
for (std::size_t i = 0; i < this->arguments_.size(); ++i) {
c_args[i] = this->arguments_[i].c_str();
auto it = std::find(
this->arguments_.cbegin(), this->arguments_.cend(), RCL_ROS_ARGS_FLAG);

c_argc = static_cast<int>(this->arguments_.size());
if (it == this->arguments_.cend()) {
c_argc += 1;
}

c_argv.reset(new const char *[c_argc]);

std::size_t i = 0;
if (it == this->arguments_.cend()) {
c_argv[i++] = RCL_ROS_ARGS_FLAG;
}
for (std::size_t j = 0; j < this->arguments_.size(); ++i, ++j) {
c_argv[i] = this->arguments_[j].c_str();
}
}

Expand All @@ -103,8 +117,7 @@ NodeOptions::get_rcl_node_options() const
}

rmw_ret_t ret = rcl_parse_arguments(
static_cast<int>(this->arguments_.size()), c_args.get(), this->allocator_,
&(node_options_->arguments));
c_argc, c_argv.get(), this->allocator_, &(node_options_->arguments));

if (RCL_RET_OK != ret) {
throw_from_rcl_error(ret, "failed to parse arguments");
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/test/test_node_global_args.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,8 @@ class TestNodeWithGlobalArgs : public ::testing::Test
protected:
static void SetUpTestCase()
{
const char * const args[] = {"proc", "__node:=global_node_name"};
rclcpp::init(2, args);
const char * const args[] = {"proc", "--ros-args", "__node:=global_node_name"};
rclcpp::init(3, args);
}
};

Expand Down
110 changes: 110 additions & 0 deletions rclcpp/test/test_node_options.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,110 @@
// Copyright 2019 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <gtest/gtest.h>

#include <string>
#include <vector>

#include <rcl/allocator.h>
#include <rcl/arguments.h>
#include <rcl/remap.h>

#include "rclcpp/node_options.hpp"


TEST(TestNodeOptions, implicit_ros_args) {
rcl_allocator_t allocator = rcl_get_default_allocator();
auto options = rclcpp::NodeOptions(allocator)
.arguments({"__node:=some_node", "__ns:=/some_ns"});

const rcl_node_options_t * rcl_options = options.get_rcl_node_options();
ASSERT_TRUE(rcl_options != nullptr);
ASSERT_EQ(0, rcl_arguments_get_count_unparsed(&rcl_options->arguments));
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(
&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(
&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);
}

TEST(TestNodeOptions, explicit_ros_args) {
rcl_allocator_t allocator = rcl_get_default_allocator();
auto options = rclcpp::NodeOptions(allocator)
.arguments({"--ros-args", "__node:=some_node", "__ns:=/some_ns"});

const rcl_node_options_t * rcl_options = options.get_rcl_node_options();
ASSERT_TRUE(rcl_options != nullptr);
ASSERT_EQ(0, rcl_arguments_get_count_unparsed(&rcl_options->arguments));
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(
&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(
&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);
}

TEST(TestNodeOptions, explicit_ros_args_and_non_ros_args) {
rcl_allocator_t allocator = rcl_get_default_allocator();
auto options = rclcpp::NodeOptions(allocator).arguments({
"--non-ros-flag", "--ros-args", "__node:=some_node",
"__ns:=/some_ns", "--", "non-ros-arg"});

const rcl_node_options_t * rcl_options = options.get_rcl_node_options();
ASSERT_TRUE(rcl_options != nullptr);
ASSERT_EQ(0, rcl_arguments_get_count_unparsed_ros(&rcl_options->arguments));
ASSERT_EQ(2, rcl_arguments_get_count_unparsed(&rcl_options->arguments));

char * node_name = nullptr;
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(
&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(
&rcl_options->arguments, allocator, &output_indices));
ASSERT_TRUE(output_indices != nullptr);
const std::vector<std::string> & args = options.arguments();
EXPECT_EQ("--non-ros-flag", args[output_indices[0]]);
EXPECT_EQ("non-ros-arg", args[output_indices[1]]);
allocator.deallocate(output_indices, allocator.state);
}
6 changes: 4 additions & 2 deletions rclcpp/test/test_utilities.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,10 @@
#include "rclcpp/utilities.hpp"

TEST(TestUtilities, remove_ros_arguments) {
const char * const argv[] = {"process_name", "-d", "__ns:=/foo/bar",
"__ns:=/fiz/buz", "--foo=bar", "--baz"};
const char * const argv[] = {
"process_name", "-d", "--ros-args", "__ns:=/foo/bar", "__ns:=/fiz/buz", "--",
"--foo=bar", "--baz"
};
int argc = sizeof(argv) / sizeof(const char *);
auto args = rclcpp::remove_ros_arguments(argc, argv);

Expand Down