Skip to content

Commit

Permalink
initialize_logging_ should be copied. (#1272)
Browse files Browse the repository at this point in the history
Signed-off-by: Tomoya.Fujita <Tomoya.Fujita@sony.com>
  • Loading branch information
fujitatomoya authored and brawner committed Oct 6, 2020
1 parent c61697e commit be9139a
Show file tree
Hide file tree
Showing 2 changed files with 19 additions and 0 deletions.
2 changes: 2 additions & 0 deletions rclcpp/src/rclcpp/init_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ InitOptions::InitOptions(const InitOptions & other)
: InitOptions(*other.get_rcl_init_options())
{
shutdown_on_sigint = other.shutdown_on_sigint;
initialize_logging_ = other.initialize_logging_;
}

bool
Expand All @@ -69,6 +70,7 @@ InitOptions::operator=(const InitOptions & other)
rclcpp::exceptions::throw_from_rcl_error(ret, "failed to copy rcl init options");
}
this->shutdown_on_sigint = other.shutdown_on_sigint;
this->initialize_logging_ = other.initialize_logging_;
}
return *this;
}
Expand Down
17 changes: 17 additions & 0 deletions rclcpp/test/rclcpp/test_init_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,3 +44,20 @@ TEST(TestInitOptions, test_construction) {
ASSERT_TRUE(rcl_options_copy->impl != nullptr);
}
}

TEST(TestInitOptions, test_initialize_logging) {
{
auto options = rclcpp::InitOptions();
EXPECT_TRUE(options.auto_initialize_logging());
}

{
auto options = rclcpp::InitOptions().auto_initialize_logging(true);
EXPECT_TRUE(options.auto_initialize_logging());
}

{
auto options = rclcpp::InitOptions().auto_initialize_logging(false);
EXPECT_FALSE(options.auto_initialize_logging());
}
}

0 comments on commit be9139a

Please sign in to comment.