Skip to content

Commit a6e80fc

Browse files
authored
Use of -r/--remap flags where appropriate. (#834)
Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
1 parent f153cf7 commit a6e80fc

5 files changed

Lines changed: 22 additions & 11 deletions

File tree

rclcpp/test/test_node.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,7 @@ TEST_F(TestNode, get_name_and_namespace) {
6666
}
6767
{
6868
auto options = rclcpp::NodeOptions()
69-
.arguments({"__ns:=/another_ns"});
69+
.arguments({"-r", "__ns:=/another_ns"});
7070
auto node = std::make_shared<rclcpp::Node>("my_node", "/ns", options);
7171
EXPECT_STREQ("my_node", node->get_name());
7272
EXPECT_STREQ("/another_ns", node->get_namespace());

rclcpp/test/test_node_global_args.cpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -28,14 +28,15 @@ class TestNodeWithGlobalArgs : public ::testing::Test
2828
protected:
2929
static void SetUpTestCase()
3030
{
31-
const char * const args[] = {"proc", "--ros-args", "__node:=global_node_name"};
32-
rclcpp::init(3, args);
31+
const char * const args[] = {"proc", "--ros-args", "-r", "__node:=global_node_name"};
32+
const int argc = sizeof(args) / sizeof(const char *);
33+
rclcpp::init(argc, args);
3334
}
3435
};
3536

3637
TEST_F(TestNodeWithGlobalArgs, local_arguments_before_global) {
3738
auto options = rclcpp::NodeOptions()
38-
.arguments({"__node:=local_arguments_test"});
39+
.arguments({"-r", "__node:=local_arguments_test"});
3940

4041
auto node = rclcpp::Node::make_shared("orig_name", options);
4142
EXPECT_STREQ("local_arguments_test", node->get_name());

rclcpp/test/test_node_options.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@
2727
TEST(TestNodeOptions, implicit_ros_args) {
2828
rcl_allocator_t allocator = rcl_get_default_allocator();
2929
auto options = rclcpp::NodeOptions(allocator)
30-
.arguments({"__node:=some_node", "__ns:=/some_ns"});
30+
.arguments({"-r", "__node:=some_node", "-r", "__ns:=/some_ns"});
3131

3232
const rcl_node_options_t * rcl_options = options.get_rcl_node_options();
3333
ASSERT_TRUE(rcl_options != nullptr);
@@ -52,7 +52,7 @@ TEST(TestNodeOptions, implicit_ros_args) {
5252
TEST(TestNodeOptions, explicit_ros_args) {
5353
rcl_allocator_t allocator = rcl_get_default_allocator();
5454
auto options = rclcpp::NodeOptions(allocator)
55-
.arguments({"--ros-args", "__node:=some_node", "__ns:=/some_ns"});
55+
.arguments({"--ros-args", "-r", "__node:=some_node", "-r", "__ns:=/some_ns"});
5656

5757
const rcl_node_options_t * rcl_options = options.get_rcl_node_options();
5858
ASSERT_TRUE(rcl_options != nullptr);
@@ -77,8 +77,8 @@ TEST(TestNodeOptions, explicit_ros_args) {
7777
TEST(TestNodeOptions, explicit_ros_args_and_non_ros_args) {
7878
rcl_allocator_t allocator = rcl_get_default_allocator();
7979
auto options = rclcpp::NodeOptions(allocator).arguments({
80-
"--non-ros-flag", "--ros-args", "__node:=some_node",
81-
"__ns:=/some_ns", "--", "non-ros-arg"});
80+
"--non-ros-flag", "--ros-args", "-r", "__node:=some_node",
81+
"-r", "__ns:=/some_ns", "--", "non-ros-arg"});
8282

8383
const rcl_node_options_t * rcl_options = options.get_rcl_node_options();
8484
ASSERT_TRUE(rcl_options != nullptr);

rclcpp/test/test_utilities.cpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -23,8 +23,11 @@
2323

2424
TEST(TestUtilities, remove_ros_arguments) {
2525
const char * const argv[] = {
26-
"process_name", "-d", "--ros-args", "__ns:=/foo/bar", "__ns:=/fiz/buz", "--",
27-
"--foo=bar", "--baz"
26+
"process_name",
27+
"-d", "--ros-args",
28+
"-r", "__ns:=/foo/bar",
29+
"-r", "__ns:=/fiz/buz",
30+
"--", "--foo=bar", "--baz"
2831
};
2932
int argc = sizeof(argv) / sizeof(const char *);
3033
auto args = rclcpp::remove_ros_arguments(argc, argv);

rclcpp_components/src/component_manager.cpp

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -142,13 +142,20 @@ ComponentManager::OnLoadNode(
142142
parameters.push_back(rclcpp::Parameter::from_parameter_msg(p));
143143
}
144144

145-
std::vector<std::string> remap_rules {request->remap_rules};
145+
std::vector<std::string> remap_rules;
146+
remap_rules.reserve(request->remap_rules.size() * 2);
147+
for (const std::string & rule : request->remap_rules) {
148+
remap_rules.push_back("-r");
149+
remap_rules.push_back(rule);
150+
}
146151

147152
if (!request->node_name.empty()) {
153+
remap_rules.push_back("-r");
148154
remap_rules.push_back("__node:=" + request->node_name);
149155
}
150156

151157
if (!request->node_namespace.empty()) {
158+
remap_rules.push_back("-r");
152159
remap_rules.push_back("__ns:=" + request->node_namespace);
153160
}
154161

0 commit comments

Comments
 (0)