Skip to content

Commit 4e4f0cf

Browse files
Shut down context during init if logging config fails (#2594)
We already do this clean-up if some other tasks below fail. Before: [ RUN ] TestUtilities.test_context_init_shutdown_fails [ERROR] [1722555370.075637014] [rclcpp]: rcl context unexpectedly not shutdown during cleanup [WARN] [1722555370.077175569] [rclcpp]: logging was initialized more than once [ OK ] TestUtilities.test_context_init_shutdown_fails (3 ms) After: [ RUN ] TestUtilities.test_context_init_shutdown_fails [WARN] [1722555108.693207861] [rclcpp]: logging was initialized more than once [ OK ] TestUtilities.test_context_init_shutdown_fails (3 ms) Also, remove an unnecessary line in `test_utilities`, and expect context to not be valid if init fails. Signed-off-by: Christophe Bedard <christophe.bedard@apex.ai>
1 parent c468967 commit 4e4f0cf

File tree

2 files changed

+20
-20
lines changed

2 files changed

+20
-20
lines changed

rclcpp/src/rclcpp/context.cpp

Lines changed: 18 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -212,28 +212,27 @@ Context::init(
212212
}
213213
rcl_context_.reset(context, __delete_context);
214214

215-
if (init_options.auto_initialize_logging()) {
216-
logging_mutex_ = get_global_logging_mutex();
217-
std::lock_guard<std::recursive_mutex> guard(*logging_mutex_);
218-
size_t & count = get_logging_reference_count();
219-
if (0u == count) {
220-
ret = rcl_logging_configure_with_output_handler(
221-
&rcl_context_->global_arguments,
222-
rcl_init_options_get_allocator(init_options.get_rcl_init_options()),
223-
rclcpp_logging_output_handler);
224-
if (RCL_RET_OK != ret) {
225-
rcl_context_.reset();
226-
rclcpp::exceptions::throw_from_rcl_error(ret, "failed to configure logging");
215+
try {
216+
if (init_options.auto_initialize_logging()) {
217+
logging_mutex_ = get_global_logging_mutex();
218+
std::lock_guard<std::recursive_mutex> guard(*logging_mutex_);
219+
size_t & count = get_logging_reference_count();
220+
if (0u == count) {
221+
ret = rcl_logging_configure_with_output_handler(
222+
&rcl_context_->global_arguments,
223+
rcl_init_options_get_allocator(init_options.get_rcl_init_options()),
224+
rclcpp_logging_output_handler);
225+
if (RCL_RET_OK != ret) {
226+
rclcpp::exceptions::throw_from_rcl_error(ret, "failed to configure logging");
227+
}
228+
} else {
229+
RCLCPP_WARN(
230+
rclcpp::get_logger("rclcpp"),
231+
"logging was initialized more than once");
227232
}
228-
} else {
229-
RCLCPP_WARN(
230-
rclcpp::get_logger("rclcpp"),
231-
"logging was initialized more than once");
233+
++count;
232234
}
233-
++count;
234-
}
235235

236-
try {
237236
std::vector<std::string> unparsed_ros_arguments = detail::get_unparsed_ros_arguments(
238237
argc, argv, &(rcl_context_->global_arguments), rcl_get_default_allocator());
239238
if (!unparsed_ros_arguments.empty()) {

rclcpp/test/rclcpp/test_utilities.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -178,18 +178,19 @@ MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t, <)
178178

179179
TEST(TestUtilities, test_context_init_shutdown_fails) {
180180
{
181-
auto context = std::make_shared<rclcpp::contexts::DefaultContext>();
182181
auto context_fail_init = std::make_shared<rclcpp::contexts::DefaultContext>();
183182
auto mock = mocking_utils::patch_and_return(
184183
"lib:rclcpp", rcl_init, RCL_RET_ERROR);
185184
EXPECT_THROW(context_fail_init->init(0, nullptr), rclcpp::exceptions::RCLError);
185+
EXPECT_FALSE(context_fail_init->is_valid());
186186
}
187187

188188
{
189189
auto context_fail_init = std::make_shared<rclcpp::contexts::DefaultContext>();
190190
auto mock = mocking_utils::patch_and_return(
191191
"lib:rclcpp", rcl_logging_configure_with_output_handler, RCL_RET_ERROR);
192192
EXPECT_THROW(context_fail_init->init(0, nullptr), rclcpp::exceptions::RCLError);
193+
EXPECT_FALSE(context_fail_init->is_valid());
193194
}
194195

195196
{

0 commit comments

Comments
 (0)