Use of -r/--remap flags where appropriate. (#834)
Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
This commit is contained in:
parent
f153cf7173
commit
a6e80fcaea
5 changed files with 22 additions and 11 deletions
|
@ -66,7 +66,7 @@ TEST_F(TestNode, get_name_and_namespace) {
|
||||||
}
|
}
|
||||||
{
|
{
|
||||||
auto options = rclcpp::NodeOptions()
|
auto options = rclcpp::NodeOptions()
|
||||||
.arguments({"__ns:=/another_ns"});
|
.arguments({"-r", "__ns:=/another_ns"});
|
||||||
auto node = std::make_shared<rclcpp::Node>("my_node", "/ns", options);
|
auto node = std::make_shared<rclcpp::Node>("my_node", "/ns", options);
|
||||||
EXPECT_STREQ("my_node", node->get_name());
|
EXPECT_STREQ("my_node", node->get_name());
|
||||||
EXPECT_STREQ("/another_ns", node->get_namespace());
|
EXPECT_STREQ("/another_ns", node->get_namespace());
|
||||||
|
|
|
@ -28,14 +28,15 @@ class TestNodeWithGlobalArgs : public ::testing::Test
|
||||||
protected:
|
protected:
|
||||||
static void SetUpTestCase()
|
static void SetUpTestCase()
|
||||||
{
|
{
|
||||||
const char * const args[] = {"proc", "--ros-args", "__node:=global_node_name"};
|
const char * const args[] = {"proc", "--ros-args", "-r", "__node:=global_node_name"};
|
||||||
rclcpp::init(3, args);
|
const int argc = sizeof(args) / sizeof(const char *);
|
||||||
|
rclcpp::init(argc, args);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
TEST_F(TestNodeWithGlobalArgs, local_arguments_before_global) {
|
TEST_F(TestNodeWithGlobalArgs, local_arguments_before_global) {
|
||||||
auto options = rclcpp::NodeOptions()
|
auto options = rclcpp::NodeOptions()
|
||||||
.arguments({"__node:=local_arguments_test"});
|
.arguments({"-r", "__node:=local_arguments_test"});
|
||||||
|
|
||||||
auto node = rclcpp::Node::make_shared("orig_name", options);
|
auto node = rclcpp::Node::make_shared("orig_name", options);
|
||||||
EXPECT_STREQ("local_arguments_test", node->get_name());
|
EXPECT_STREQ("local_arguments_test", node->get_name());
|
||||||
|
|
|
@ -27,7 +27,7 @@
|
||||||
TEST(TestNodeOptions, implicit_ros_args) {
|
TEST(TestNodeOptions, implicit_ros_args) {
|
||||||
rcl_allocator_t allocator = rcl_get_default_allocator();
|
rcl_allocator_t allocator = rcl_get_default_allocator();
|
||||||
auto options = rclcpp::NodeOptions(allocator)
|
auto options = rclcpp::NodeOptions(allocator)
|
||||||
.arguments({"__node:=some_node", "__ns:=/some_ns"});
|
.arguments({"-r", "__node:=some_node", "-r", "__ns:=/some_ns"});
|
||||||
|
|
||||||
const rcl_node_options_t * rcl_options = options.get_rcl_node_options();
|
const rcl_node_options_t * rcl_options = options.get_rcl_node_options();
|
||||||
ASSERT_TRUE(rcl_options != nullptr);
|
ASSERT_TRUE(rcl_options != nullptr);
|
||||||
|
@ -52,7 +52,7 @@ TEST(TestNodeOptions, implicit_ros_args) {
|
||||||
TEST(TestNodeOptions, explicit_ros_args) {
|
TEST(TestNodeOptions, explicit_ros_args) {
|
||||||
rcl_allocator_t allocator = rcl_get_default_allocator();
|
rcl_allocator_t allocator = rcl_get_default_allocator();
|
||||||
auto options = rclcpp::NodeOptions(allocator)
|
auto options = rclcpp::NodeOptions(allocator)
|
||||||
.arguments({"--ros-args", "__node:=some_node", "__ns:=/some_ns"});
|
.arguments({"--ros-args", "-r", "__node:=some_node", "-r", "__ns:=/some_ns"});
|
||||||
|
|
||||||
const rcl_node_options_t * rcl_options = options.get_rcl_node_options();
|
const rcl_node_options_t * rcl_options = options.get_rcl_node_options();
|
||||||
ASSERT_TRUE(rcl_options != nullptr);
|
ASSERT_TRUE(rcl_options != nullptr);
|
||||||
|
@ -77,8 +77,8 @@ TEST(TestNodeOptions, explicit_ros_args) {
|
||||||
TEST(TestNodeOptions, explicit_ros_args_and_non_ros_args) {
|
TEST(TestNodeOptions, explicit_ros_args_and_non_ros_args) {
|
||||||
rcl_allocator_t allocator = rcl_get_default_allocator();
|
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", "__node:=some_node",
|
"--non-ros-flag", "--ros-args", "-r", "__node:=some_node",
|
||||||
"__ns:=/some_ns", "--", "non-ros-arg"});
|
"-r", "__ns:=/some_ns", "--", "non-ros-arg"});
|
||||||
|
|
||||||
const rcl_node_options_t * rcl_options = options.get_rcl_node_options();
|
const rcl_node_options_t * rcl_options = options.get_rcl_node_options();
|
||||||
ASSERT_TRUE(rcl_options != nullptr);
|
ASSERT_TRUE(rcl_options != nullptr);
|
||||||
|
|
|
@ -23,8 +23,11 @@
|
||||||
|
|
||||||
TEST(TestUtilities, remove_ros_arguments) {
|
TEST(TestUtilities, remove_ros_arguments) {
|
||||||
const char * const argv[] = {
|
const char * const argv[] = {
|
||||||
"process_name", "-d", "--ros-args", "__ns:=/foo/bar", "__ns:=/fiz/buz", "--",
|
"process_name",
|
||||||
"--foo=bar", "--baz"
|
"-d", "--ros-args",
|
||||||
|
"-r", "__ns:=/foo/bar",
|
||||||
|
"-r", "__ns:=/fiz/buz",
|
||||||
|
"--", "--foo=bar", "--baz"
|
||||||
};
|
};
|
||||||
int argc = sizeof(argv) / sizeof(const char *);
|
int argc = sizeof(argv) / sizeof(const char *);
|
||||||
auto args = rclcpp::remove_ros_arguments(argc, argv);
|
auto args = rclcpp::remove_ros_arguments(argc, argv);
|
||||||
|
|
|
@ -142,13 +142,20 @@ ComponentManager::OnLoadNode(
|
||||||
parameters.push_back(rclcpp::Parameter::from_parameter_msg(p));
|
parameters.push_back(rclcpp::Parameter::from_parameter_msg(p));
|
||||||
}
|
}
|
||||||
|
|
||||||
std::vector<std::string> remap_rules {request->remap_rules};
|
std::vector<std::string> remap_rules;
|
||||||
|
remap_rules.reserve(request->remap_rules.size() * 2);
|
||||||
|
for (const std::string & rule : request->remap_rules) {
|
||||||
|
remap_rules.push_back("-r");
|
||||||
|
remap_rules.push_back(rule);
|
||||||
|
}
|
||||||
|
|
||||||
if (!request->node_name.empty()) {
|
if (!request->node_name.empty()) {
|
||||||
|
remap_rules.push_back("-r");
|
||||||
remap_rules.push_back("__node:=" + request->node_name);
|
remap_rules.push_back("__node:=" + request->node_name);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!request->node_namespace.empty()) {
|
if (!request->node_namespace.empty()) {
|
||||||
|
remap_rules.push_back("-r");
|
||||||
remap_rules.push_back("__ns:=" + request->node_namespace);
|
remap_rules.push_back("__ns:=" + request->node_namespace);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue