Skip to content

Commit 084bdff

Browse files
committed
Ensure logging is initialized just once
Signed-off-by: Ivan Santiago Paunovic <ivanpauno@ekumenlabs.com>
1 parent 9c002c6 commit 084bdff

File tree

2 files changed

+58
-1
lines changed

2 files changed

+58
-1
lines changed

rclcpp/include/rclcpp/context.hpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -338,6 +338,9 @@ class Context : public std::enable_shared_from_this<Context>
338338
rclcpp::InitOptions init_options_;
339339
std::string shutdown_reason_;
340340

341+
// Keep shared ownership of global logging configure mutex.
342+
std::shared_ptr<std::mutex> logging_configure_mutex_;
343+
341344
std::unordered_map<std::type_index, std::shared_ptr<void>> sub_contexts_;
342345
// This mutex is recursive so that the constructor of a sub context may
343346
// attempt to acquire another sub context.

rclcpp/src/rclcpp/context.cpp

Lines changed: 55 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222
#include <utility>
2323

2424
#include "rcl/init.h"
25+
#include "rcl/logging.h"
2526
#include "rclcpp/detail/utilities.hpp"
2627
#include "rclcpp/exceptions.hpp"
2728
#include "rclcpp/logging.hpp"
@@ -34,8 +35,31 @@ static std::vector<std::weak_ptr<rclcpp::Context>> g_contexts;
3435

3536
using rclcpp::Context;
3637

38+
static
39+
std::shared_ptr<std::mutex>
40+
get_global_logging_configure_mutex()
41+
{
42+
static auto mutex = std::make_shared<std::mutex>();
43+
return mutex;
44+
}
45+
46+
static
47+
size_t &
48+
get_logging_reference_count()
49+
{
50+
static size_t ref_count = 0;
51+
return ref_count;
52+
}
53+
3754
Context::Context()
38-
: rcl_context_(nullptr), shutdown_reason_("") {}
55+
: rcl_context_(nullptr),
56+
shutdown_reason_(""),
57+
logging_configure_mutex_(get_global_logging_configure_mutex())
58+
{
59+
if (!logging_configure_mutex_) {
60+
throw std::runtime_error("global logging configure mutex is 'nullptr'");
61+
}
62+
}
3963

4064
Context::~Context()
4165
{
@@ -94,6 +118,22 @@ Context::init(
94118
rcl_context_.reset();
95119
rclcpp::exceptions::throw_from_rcl_error(ret, "failed to initialize rcl");
96120
}
121+
122+
{
123+
std::lock_guard<std::mutex> guard(*logging_configure_mutex_);
124+
size_t & count = get_logging_reference_count();
125+
if (0u == count) {
126+
ret = rcl_logging_configure(
127+
&rcl_context_->global_arguments,
128+
rcl_init_options_get_allocator(init_options_.get_rcl_init_options()));
129+
if (RCL_RET_OK != ret) {
130+
rcl_context_.reset();
131+
rclcpp::exceptions::throw_from_rcl_error(ret, "failed to configure logging");
132+
}
133+
}
134+
++count;
135+
}
136+
97137
try {
98138
std::vector<std::string> unparsed_ros_arguments = detail::get_unparsed_ros_arguments(
99139
argc, argv, &(rcl_context_->global_arguments), rcl_get_default_allocator());
@@ -309,6 +349,20 @@ Context::clean_up()
309349
{
310350
shutdown_reason_ = "";
311351
rcl_context_.reset();
352+
{
353+
std::lock_guard<std::mutex> guard(*logging_configure_mutex_);
354+
size_t & count = get_logging_reference_count();
355+
if (0u == --count) {
356+
rcl_ret_t rcl_ret = rcl_logging_fini();
357+
if (RCL_RET_OK != rcl_ret) {
358+
RCUTILS_SAFE_FWRITE_TO_STDERR(
359+
RCUTILS_STRINGIFY(__file__) ":"
360+
RCUTILS_STRINGIFY(__LINE__)
361+
" failed to fini logging");
362+
rcl_reset_error();
363+
}
364+
}
365+
}
312366
sub_contexts_.clear();
313367
}
314368

0 commit comments

Comments
 (0)