Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions rclpy/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ endif()
find_package(ament_cmake REQUIRED)
find_package(ament_cmake_python REQUIRED)
find_package(rcl REQUIRED)
find_package(rcl_logging_interface REQUIRED)
find_package(rcl_action REQUIRED)
find_package(rcl_yaml_param_parser REQUIRED)
find_package(rcutils REQUIRED)
Expand Down Expand Up @@ -142,6 +143,7 @@ add_library(
configure_python_c_extension_library(rclpy_logging)
ament_target_dependencies(rclpy_logging
"rcutils"
"rcl_logging_interface"
)

# Signal handling library
Expand Down
1 change: 1 addition & 0 deletions rclpy/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@

<depend>rmw_implementation</depend>
<depend>rcl</depend>
<depend>rcl_logging_interface</depend>
<depend>rcl_action</depend>
<depend>rcl_yaml_param_parser</depend>
<depend>unique_identifier_msgs</depend>
Expand Down
11 changes: 11 additions & 0 deletions rclpy/rclpy/logging.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@


from enum import IntEnum
from pathlib import Path

from rclpy.impl.implementation_singleton import rclpy_logging_implementation as _rclpy_logging
import rclpy.impl.rcutils_logger
Expand Down Expand Up @@ -70,3 +71,13 @@ def get_logger_effective_level(name):
def get_logging_severity_from_string(log_severity):
return LoggingSeverity(
_rclpy_logging.rclpy_logging_severity_level_from_string(log_severity))


def get_logging_directory() -> Path:
"""
Return the current logging directory being used.

For more details, see .. c:function::
rcl_logging_ret_t rcl_logging_get_logging_directory(rcutils_allocator_t, char **)
"""
return Path(_rclpy_logging.rclpy_logging_get_logging_directory())
27 changes: 27 additions & 0 deletions rclpy/src/rclpy/_rclpy_logging.c
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@
#include <rcutils/logging.h>
#include <rcutils/time.h>

#include <rcl_logging_interface/rcl_logging_interface.h>

/// Initialize the logging system.
/**
* \return None or
Expand Down Expand Up @@ -254,6 +256,27 @@ rclpy_get_fatal_logging_severity(PyObject * Py_UNUSED(self), PyObject * Py_UNUSE
return PyLong_FromLongLong(RCUTILS_LOG_SEVERITY_FATAL);
}

/// Get the current logging directory from rcutils.
/// \return Unicode UTF8 object containing the current logging directory.
static PyObject *
rclpy_logging_get_logging_directory(PyObject * Py_UNUSED(self), PyObject * Py_UNUSED(args))
{
char * log_dir = NULL;
rcutils_allocator_t allocator = rcutils_get_default_allocator();
rcl_logging_ret_t ret = rcl_logging_get_logging_directory(allocator, &log_dir);
if (RCL_LOGGING_RET_OK != ret) {
PyErr_Format(
PyExc_RuntimeError,
"Failed to get current logging directory, error: \"%s\", return code: \"%d\"\n",
rcutils_get_error_string().str, ret);
rcutils_reset_error();
return NULL;
}
PyObject * py_log_dir = PyUnicode_DecodeFSDefault(log_dir);
allocator.deallocate(log_dir, allocator.state);
return py_log_dir;
}

/// Define the public methods of this module
static PyMethodDef rclpy_logging_methods[] = {
{
Expand Down Expand Up @@ -309,6 +332,10 @@ static PyMethodDef rclpy_logging_methods[] = {
"rclpy_get_fatal_logging_severity", rclpy_get_fatal_logging_severity,
METH_VARARGS, "Get log fatal severity level as int from rcutils"
},
{
"rclpy_logging_get_logging_directory", rclpy_logging_get_logging_directory,
METH_VARARGS, "Get the current logging directory from rcutils"
},

{NULL, NULL, 0, NULL} /* sentinel */
};
Expand Down
11 changes: 11 additions & 0 deletions rclpy/test/test_logging.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@
# limitations under the License.

import inspect
import os
from pathlib import Path
import time
import unittest

Expand Down Expand Up @@ -368,6 +370,15 @@ def test_nonexistent_logging_severity_from_string(self):
with self.assertRaises(RuntimeError):
rclpy.logging.get_logging_severity_from_string('non_existent_severity')

def test_get_logging_directory(self):
os.environ['HOME'] = '/fake_home_dir'
os.environ.pop('USERPROFILE', None)
os.environ.pop('ROS_LOG_DIR', None)
os.environ.pop('ROS_HOME', None)
log_dir = rclpy.logging.get_logging_directory()
assert isinstance(log_dir, Path)
assert log_dir == Path('/fake_home_dir') / '.ros' / 'log'


if __name__ == '__main__':
unittest.main()