Skip to content

Commit

Permalink
get rid of unrelated changes.
Browse files Browse the repository at this point in the history
Signed-off-by: Tomoya.Fujita <Tomoya.Fujita@sony.com>
  • Loading branch information
fujitatomoya committed Aug 4, 2020
1 parent e8fb34a commit 7674be0
Show file tree
Hide file tree
Showing 2 changed files with 0 additions and 32 deletions.
3 changes: 0 additions & 3 deletions rclcpp/src/rclcpp/init_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,6 @@ 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 @@ -71,7 +70,6 @@ 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 Expand Up @@ -106,7 +104,6 @@ InitOptions::finalize_init_options_impl()
const rcl_init_options_t *
InitOptions::get_rcl_init_options() const
{
std::lock_guard<std::mutex> init_options_lock(init_options_mutex_);
return init_options_.get();
}

Expand Down
29 changes: 0 additions & 29 deletions rclcpp/test/rclcpp/test_init_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,38 +45,9 @@ TEST(TestInitOptions, test_construction) {
}
}

TEST(TestInitOptions, test_initialize_logging) {
{
auto options = rclcpp::InitOptions();
EXPECT_TRUE(options.auto_initialize_logging());
const rcl_init_options_t * rcl_options = options.get_rcl_init_options();
ASSERT_TRUE(rcl_options != nullptr);
ASSERT_TRUE(rcl_options->impl != nullptr);
}

{
auto options = rclcpp::InitOptions().auto_initialize_logging(true);
EXPECT_TRUE(options.auto_initialize_logging());
const rcl_init_options_t * rcl_options = options.get_rcl_init_options();
ASSERT_TRUE(rcl_options != nullptr);
ASSERT_TRUE(rcl_options->impl != nullptr);
}

{
auto options = rclcpp::InitOptions().auto_initialize_logging(false);
EXPECT_FALSE(options.auto_initialize_logging());
const rcl_init_options_t * rcl_options = options.get_rcl_init_options();
ASSERT_TRUE(rcl_options != nullptr);
ASSERT_TRUE(rcl_options->impl != nullptr);
}
}

TEST(TestInitOptions, test_domain_id) {
rcl_allocator_t allocator = rcl_get_default_allocator();
auto options = rclcpp::InitOptions(allocator);
const rcl_init_options_t * rcl_options = options.get_rcl_init_options();
ASSERT_TRUE(rcl_options != nullptr);
ASSERT_TRUE(rcl_options->impl != nullptr);

options.use_default_domain_id();
EXPECT_EQ(RCL_DEFAULT_DOMAIN_ID, options.get_domain_id());
Expand Down

0 comments on commit 7674be0

Please sign in to comment.