Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Logging service support #1102

Merged
merged 5 commits into from
Apr 18, 2023
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
1 change: 1 addition & 0 deletions rclpy/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -181,6 +181,7 @@ if(BUILD_TESTING)
test/test_init_shutdown.py
test/test_logging.py
test/test_logging_rosout.py
test/test_logging_service.py
test/test_messages.py
test/test_node.py
test/test_parameter.py
Expand Down
10 changes: 8 additions & 2 deletions rclpy/rclpy/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,8 @@ def create_node(
start_parameter_services: bool = True,
parameter_overrides: List[Parameter] = None,
allow_undeclared_parameters: bool = False,
automatically_declare_parameters_from_overrides: bool = False
automatically_declare_parameters_from_overrides: bool = False,
enable_logger_service: bool = False
) -> 'Node':
"""
Create an instance of :class:`.Node`.
Expand All @@ -165,6 +166,9 @@ def create_node(
This option doesn't affect `parameter_overrides`.
:param automatically_declare_parameters_from_overrides: If True, the "parameter overrides" will
be used to implicitly declare parameters on the node during creation, default False.
:param enable_logger_service: ``True`` if ROS2 services are created to allow external nodes
to get and set logger levels of this node. Otherwise, logger levels are only managed
locally. That is, logger levels cannot be changed remotely.
:return: An instance of the newly created node.
"""
# imported locally to avoid loading extensions on module import
Expand All @@ -178,7 +182,9 @@ def create_node(
allow_undeclared_parameters=allow_undeclared_parameters,
automatically_declare_parameters_from_overrides=(
automatically_declare_parameters_from_overrides
))
),
enable_logger_service=enable_logger_service
)


def spin_once(node: 'Node', *, executor: 'Executor' = None, timeout_sec: float = None) -> None:
Expand Down
9 changes: 7 additions & 2 deletions rclpy/rclpy/logging.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,16 +43,21 @@ def clear_config():
initialize()


def set_logger_level(name, level):
def set_logger_level(name, level, detailed_error=False):
level = LoggingSeverity(level)
return _rclpy.rclpy_logging_set_logger_level(name, level)
return _rclpy.rclpy_logging_set_logger_level(name, level, detailed_error)


def get_logger_effective_level(name):
logger_level = _rclpy.rclpy_logging_get_logger_effective_level(name)
return LoggingSeverity(logger_level)


def get_logger_level(name):
logger_level = _rclpy.rclpy_logging_get_logger_level(name)
return LoggingSeverity(logger_level)


def get_logging_severity_from_string(log_severity):
return LoggingSeverity(
_rclpy.rclpy_logging_severity_level_from_string(log_severity))
Expand Down
66 changes: 66 additions & 0 deletions rclpy/rclpy/logging_service.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
# Copyright 2023 Sony Group Corporation.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from rcl_interfaces.msg import LoggerLevel, SetLoggerLevelsResult
from rcl_interfaces.srv import GetLoggerLevels
from rcl_interfaces.srv import SetLoggerLevels
import rclpy
from rclpy.qos import qos_profile_services_default
from rclpy.validate_topic_name import TOPIC_SEPARATOR_STRING


class LoggingService:

def __init__(self, node):
node_name = node.get_name()

get_logger_name_service_name = \
TOPIC_SEPARATOR_STRING.join((node_name, 'get_logger_levels'))
node.create_service(
GetLoggerLevels, get_logger_name_service_name,
self._get_logger_levels, qos_profile=qos_profile_services_default
)

set_logger_name_service_name = \
TOPIC_SEPARATOR_STRING.join((node_name, 'set_logger_levels'))
node.create_service(
SetLoggerLevels, set_logger_name_service_name,
self._set_logger_levels, qos_profile=qos_profile_services_default
)

def _get_logger_levels(self, request, response):
for name in request.names:
logger_level = LoggerLevel()
logger_level.name = name
try:
ret_level = rclpy.logging.get_logger_level(name)
except RuntimeError:
ret_level = 0
logger_level.level = ret_level
response.levels.append(logger_level)
return response

def _set_logger_levels(self, request, response):
for level in request.levels:
result = SetLoggerLevelsResult()
result.successful = False
try:
rclpy.logging.set_logger_level(level.name, level.level, detailed_error=True)
result.successful = True
except ValueError:
result.reason = 'Failed reason: Invaild logger level.'
except RuntimeError as e:
result.reason = str(e)
response.results.append(result)
return response
10 changes: 9 additions & 1 deletion rclpy/rclpy/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,7 @@
from rclpy.guard_condition import GuardCondition
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
from rclpy.logging import get_logger
from rclpy.logging_service import LoggingService
from rclpy.parameter import Parameter, PARAMETER_SEPARATOR_STRING
from rclpy.parameter_service import ParameterService
from rclpy.publisher import Publisher
Expand Down Expand Up @@ -126,7 +127,8 @@ def __init__(
start_parameter_services: bool = True,
parameter_overrides: List[Parameter] = None,
allow_undeclared_parameters: bool = False,
automatically_declare_parameters_from_overrides: bool = False
automatically_declare_parameters_from_overrides: bool = False,
enable_logger_service: bool = False
) -> None:
"""
Create a Node.
Expand All @@ -150,6 +152,9 @@ def __init__(
This flag affects the behavior of parameter-related operations.
:param automatically_declare_parameters_from_overrides: If True, the "parameter overrides"
will be used to implicitly declare parameters on the node during creation.
:param enable_logger_service: ``True`` if ROS2 services are created to allow external nodes
to get and set logger levels of this node. Otherwise, logger levels are only managed
locally. That is, logger levels cannot be changed remotely.
"""
self.__handle = None
self._context = get_default_context() if context is None else context
Expand Down Expand Up @@ -231,6 +236,9 @@ def __init__(
if start_parameter_services:
self._parameter_service = ParameterService(self)

if enable_logger_service:
self._logger_service = LoggingService(self)

@property
def publishers(self) -> Iterator[Publisher]:
"""Get publishers that have been created on this node."""
Expand Down
42 changes: 38 additions & 4 deletions rclpy/src/rclpy/_rclpy_logging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,12 +23,16 @@ namespace py = pybind11;
#include <rcl_logging_interface/rcl_logging_interface.h>
#include <rcl/logging_rosout.h>

#include <mutex>
#include <stdexcept>
#include <string>

#include "exceptions.hpp"
#include "logging.hpp"
#include "logging_api.hpp"

static std::mutex g_logging_lock;

/// Initialize the logging system.
/**
* \return None
Expand Down Expand Up @@ -63,15 +67,21 @@ rclpy_logging_shutdown()
*
* \param[in] name Fully-qualified name of logger.
* \param[in] level to set
* \param[in] detailed_error True for reporting detailed rcutils error.
* \return None
*/
void
rclpy_logging_set_logger_level(const char * name, int level)
rclpy_logging_set_logger_level(const char * name, int level, bool detailed_error = false)
fujitatomoya marked this conversation as resolved.
Show resolved Hide resolved
{
std::lock_guard<std::mutex> lock(g_logging_lock);
fujitatomoya marked this conversation as resolved.
Show resolved Hide resolved
rcutils_ret_t ret = rcutils_logging_set_logger_level(name, level);
if (ret != RCUTILS_RET_OK) {
rcutils_reset_error();
throw std::runtime_error("Failed to set level for logger");
if (detailed_error) {
throw std::runtime_error(rclpy::append_rcutils_error("Failed reason"));
} else {
rcutils_reset_error();
throw std::runtime_error("Failed to set level for logger");
}
}
}

Expand All @@ -87,6 +97,7 @@ rclpy_logging_set_logger_level(const char * name, int level)
int
rclpy_logging_get_logger_effective_level(const char * name)
{
std::lock_guard<std::mutex> lock(g_logging_lock);
int logger_level = rcutils_logging_get_logger_effective_level(name);

if (logger_level < 0) {
Expand All @@ -96,6 +107,26 @@ rclpy_logging_get_logger_effective_level(const char * name)
return logger_level;
}

/// Get the level of a logger
/**
* This considers the severity level of the specifed logger only.
*
* \param[in] name Fully-qualified name of logger.
* \return The level of the logger
*/
int
rclpy_logging_get_logger_level(const char * name)
{
std::lock_guard<std::mutex> lock(g_logging_lock);
int logger_level = rcutils_logging_get_logger_level(name);

if (logger_level < 0) {
rcutils_reset_error();
throw std::runtime_error("Failed to get level for logger");
}
return logger_level;
}

/// Determine if the logger is enabled for a severity.
/**
*
Expand Down Expand Up @@ -214,13 +245,16 @@ define_logging_api(py::module m)
m.def("rclpy_logging_get_separator_string", []() {return RCUTILS_LOGGING_SEPARATOR_STRING;});
m.def("rclpy_logging_initialize", &rclpy_logging_initialize);
m.def("rclpy_logging_shutdown", &rclpy_logging_shutdown);
m.def("rclpy_logging_set_logger_level", &rclpy_logging_set_logger_level);
m.def(
"rclpy_logging_set_logger_level", &rclpy_logging_set_logger_level,
py::arg("name"), py::arg("level"), py::arg("detailed_error") = false);
m.def("rclpy_logging_get_logger_effective_level", &rclpy_logging_get_logger_effective_level);
m.def("rclpy_logging_logger_is_enabled_for", &rclpy_logging_logger_is_enabled_for);
m.def("rclpy_logging_rcutils_log", &rclpy_logging_rcutils_log);
m.def("rclpy_logging_severity_level_from_string", &rclpy_logging_severity_level_from_string);
m.def("rclpy_logging_get_logging_directory", &rclpy_logging_get_logging_directory);
m.def("rclpy_logging_rosout_add_sublogger", &rclpy_logging_rosout_add_sublogger);
m.def("rclpy_logging_rosout_remove_sublogger", &rclpy_logging_rosout_remove_sublogger);
m.def("rclpy_logging_get_logger_level", &rclpy_logging_get_logger_level);
}
} // namespace rclpy
Loading