Skip to content

Commit be9139a

Browse files
fujitatomoyabrawner
authored andcommitted
initialize_logging_ should be copied. (#1272)
Signed-off-by: Tomoya.Fujita <[email protected]>
1 parent c61697e commit be9139a

File tree

2 files changed

+19
-0
lines changed

2 files changed

+19
-0
lines changed

rclcpp/src/rclcpp/init_options.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,7 @@ InitOptions::InitOptions(const InitOptions & other)
4444
: InitOptions(*other.get_rcl_init_options())
4545
{
4646
shutdown_on_sigint = other.shutdown_on_sigint;
47+
initialize_logging_ = other.initialize_logging_;
4748
}
4849

4950
bool
@@ -69,6 +70,7 @@ InitOptions::operator=(const InitOptions & other)
6970
rclcpp::exceptions::throw_from_rcl_error(ret, "failed to copy rcl init options");
7071
}
7172
this->shutdown_on_sigint = other.shutdown_on_sigint;
73+
this->initialize_logging_ = other.initialize_logging_;
7274
}
7375
return *this;
7476
}

rclcpp/test/rclcpp/test_init_options.cpp

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -44,3 +44,20 @@ TEST(TestInitOptions, test_construction) {
4444
ASSERT_TRUE(rcl_options_copy->impl != nullptr);
4545
}
4646
}
47+
48+
TEST(TestInitOptions, test_initialize_logging) {
49+
{
50+
auto options = rclcpp::InitOptions();
51+
EXPECT_TRUE(options.auto_initialize_logging());
52+
}
53+
54+
{
55+
auto options = rclcpp::InitOptions().auto_initialize_logging(true);
56+
EXPECT_TRUE(options.auto_initialize_logging());
57+
}
58+
59+
{
60+
auto options = rclcpp::InitOptions().auto_initialize_logging(false);
61+
EXPECT_FALSE(options.auto_initialize_logging());
62+
}
63+
}

0 commit comments

Comments
 (0)