Skip to content

Commit

Permalink
Check allocator validity in some rcl_logging functions (#116)
Browse files Browse the repository at this point in the history
If the allocator is zero-initialized, it may cause a segfault when it is
used later in the functions.

Signed-off-by: Scott K Logan <logans@cottsay.net>
  • Loading branch information
cottsay authored Mar 7, 2024
1 parent 17685e0 commit 133884b
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 1 deletion.
1 change: 1 addition & 0 deletions rcl_logging_interface/src/logging_dir.c
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ rcl_logging_get_logging_directory(rcutils_allocator_t allocator, char ** directo
RCUTILS_SET_ERROR_MSG("directory argument must not be null");
return RCL_LOGGING_RET_INVALID_ARGUMENT;
}
RCUTILS_CHECK_ALLOCATOR(&allocator, return RCL_LOGGING_RET_INVALID_ARGUMENT);
if (NULL != *directory) {
RCUTILS_SET_ERROR_MSG("directory argument must point to null");
return RCL_LOGGING_RET_INVALID_ARGUMENT;
Expand Down
2 changes: 2 additions & 0 deletions rcl_logging_spdlog/src/rcl_logging_spdlog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,6 +100,8 @@ rcl_logging_ret_t rcl_logging_external_initialize(
const char * config_file,
rcutils_allocator_t allocator)
{
RCUTILS_CHECK_ALLOCATOR(&allocator, return RCL_LOGGING_RET_INVALID_ARGUMENT);

std::lock_guard<std::mutex> lk(g_logger_mutex);
// It is possible for this to get called more than once in a process (some of
// the tests do this implicitly by calling rclcpp::init more than once).
Expand Down
2 changes: 1 addition & 1 deletion rcl_logging_spdlog/test/test_logging_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -192,7 +192,7 @@ TEST_F(AllocatorTest, init_invalid)
rcl_logging_external_initialize("anything", nullptr, bad_allocator));
rcutils_reset_error();
EXPECT_EQ(
RCL_LOGGING_RET_ERROR,
RCL_LOGGING_RET_INVALID_ARGUMENT,
rcl_logging_external_initialize(nullptr, nullptr, invalid_allocator));
rcutils_reset_error();
}
Expand Down

0 comments on commit 133884b

Please sign in to comment.