Skip to content

Commit

Permalink
Fix rclcpp::NodeOptions::operator= (#1211)
Browse files Browse the repository at this point in the history
Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
  • Loading branch information
hidmic authored Jul 2, 2020
1 parent 05e6b96 commit 84ae5a1
Show file tree
Hide file tree
Showing 2 changed files with 31 additions and 0 deletions.
1 change: 1 addition & 0 deletions rclcpp/src/rclcpp/node_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,7 @@ NodeOptions::operator=(const NodeOptions & other)
this->allow_undeclared_parameters_ = other.allow_undeclared_parameters_;
this->automatically_declare_parameters_from_overrides_ =
other.automatically_declare_parameters_from_overrides_;
this->node_options_.reset();
}
return *this;
}
Expand Down
30 changes: 30 additions & 0 deletions rclcpp/test/rclcpp/test_node_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -168,3 +168,33 @@ TEST(TestNodeOptions, enable_rosout) {
EXPECT_TRUE(options.get_rcl_node_options()->enable_rosout);
}
}

TEST(TestNodeOptions, copy) {
std::vector<std::string> expected_args{"--unknown-flag", "arg"};
auto options = rclcpp::NodeOptions().arguments(expected_args).use_global_arguments(false);
const rcl_node_options_t * rcl_options = options.get_rcl_node_options();

{
rclcpp::NodeOptions copied_options = options;
EXPECT_FALSE(copied_options.use_global_arguments());
EXPECT_EQ(expected_args, copied_options.arguments());
const rcl_node_options_t * copied_rcl_options = copied_options.get_rcl_node_options();
EXPECT_EQ(copied_rcl_options->use_global_arguments, rcl_options->use_global_arguments);
EXPECT_EQ(
rcl_arguments_get_count_unparsed(&copied_rcl_options->arguments),
rcl_arguments_get_count_unparsed(&rcl_options->arguments));
}

{
auto other_options = rclcpp::NodeOptions().use_global_arguments(true);
(void)other_options.get_rcl_node_options(); // force C structure initialization
other_options = options;
EXPECT_FALSE(other_options.use_global_arguments());
EXPECT_EQ(expected_args, other_options.arguments());
const rcl_node_options_t * other_rcl_options = other_options.get_rcl_node_options();
EXPECT_EQ(other_rcl_options->use_global_arguments, rcl_options->use_global_arguments);
EXPECT_EQ(
rcl_arguments_get_count_unparsed(&other_rcl_options->arguments),
rcl_arguments_get_count_unparsed(&rcl_options->arguments));
}
}

0 comments on commit 84ae5a1

Please sign in to comment.