Skip to content
Open
Show file tree
Hide file tree
Changes from 1 commit
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
52 changes: 52 additions & 0 deletions ros2node/ros2node/api/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,10 +16,15 @@
from typing import Any
from typing import List

import rclpy

from rclpy.node import HIDDEN_NODE_PREFIX
from ros2cli.helpers import wait_for
from ros2cli.node.strategy import NodeStrategy

from rcl_interfaces.msg import LoggerLevel
from rcl_interfaces.srv import SetLoggerLevels

INFO_NONUNIQUE_WARNING_TEMPLATE = (
'There are {num_nodes} nodes in the graph with the exact name "{node_name}". '
'You are seeing information about only one of them.'
Expand All @@ -28,6 +33,14 @@
NodeName = namedtuple('NodeName', ('name', 'namespace', 'full_name'))
TopicInfo = namedtuple('Topic', ('name', 'types'))

LEVEL_STR_TO_ENUM = {
'DEBUG': LoggerLevel.LOG_LEVEL_DEBUG,
'INFO': LoggerLevel.LOG_LEVEL_INFO,
'WARN': LoggerLevel.LOG_LEVEL_WARN,
'ERROR': LoggerLevel.LOG_LEVEL_ERROR,
'FATAL': LoggerLevel.LOG_LEVEL_FATAL,
}


def _is_hidden_name(name):
# note, we're assuming the hidden node prefix is the same for other hidden names
Expand Down Expand Up @@ -145,6 +158,45 @@ def get_action_client_info(*, node, remote_node_name, include_hidden=False):
for n, t in names_and_types if include_hidden or not _is_hidden_name(n)]


def call_log_level_set(node, node_name, level):
"""
Set the log level of the specified node using the SetLoggerLevels ROS service.
:param node: The rclpy node to use as the client
:param node_name: The full name of the target node
:param level: The log level as a string (e.g., 'DEBUG', 'INFO', 'WARN', 'ERROR', 'FATAL')
"""

# Prepare the service name for the target node
service_name = f'{node_name}/set_logger_levels'
client = node.create_client(SetLoggerLevels, service_name)

if not client.service_is_ready():
raise RuntimeError(f'Service {service_name} not ready')
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Just a comment about this part specifically:

As Tomoya said, the node will not have this service if its enable_logger_service node option isn't set to true: https://docs.ros.org/en/rolling/Tutorials/Demos/Logging-and-logger-configuration.html#logger-level-configuration-externally. It is false by default: https://github.com/ros2/rclcpp/blob/84c6fb1cfc945521680a0e1fccf5b32237acbcc3/rclcpp/include/rclcpp/node_options.hpp#L452

Instead of just throwing an error with a generic f'Service {service_name} not ready' message, it should let the user know that the service may not exist if the node doesn't have the enable_logger_service option enabled. This way the user knows exactly what to change in their code. Something like:

Suggested change
# Prepare the service name for the target node
service_name = f'{node_name}/set_logger_levels'
client = node.create_client(SetLoggerLevels, service_name)
if not client.service_is_ready():
raise RuntimeError(f'Service {service_name} not ready')
# Prepare the service name for the target node
service_name = f'{node_name}/set_logger_levels'
client = node.create_client(SetLoggerLevels, service_name)
if not client.service_is_ready():
raise RuntimeError(
f"Service '{service_name}' is not available. This service is only available if the "
f"'enable_logger_service' node option is enabled for node '{node_name}'."
)

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

ah! I missed this from your earlier comment:

Maybe it could be logged more clearly like: "Service not available. Are the logging services enabled?"

Then yes, definitely!

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Updated log line

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think this should explicitly mention the "'enable_logger_service' node option" not just "Are the logging services enabled?"

Users probably have no idea how to enable logging services. It's much more useful to tell them exactly what needs to change: enable the enable_logger_service node option


# Prepare the request
level_value = LEVEL_STR_TO_ENUM.get(level.upper(), None)
if level_value is None:
raise ValueError(
f'Invalid log level "{level}". Valid levels are: {", ".join(LEVEL_STR_TO_ENUM.keys())}')

request = SetLoggerLevels.Request()
logger_level = LoggerLevel()
logger_level.name = node_name
logger_level.level = level_value
request.levels = [logger_level]

# Call the service
future = client.call_async(request)
rclpy.spin_until_future_complete(node, future)
if future.result() is not None:
res = future.result()
if not all([r.successful for r in res.results]):
raise RuntimeError(
f'Failed to set log level for node "{node_name}": {res.results}')
else:
raise RuntimeError(f'Failed to set log level: {future.exception()}')


class NodeNameCompleter:
"""Callable returning a list of node names."""

Expand Down
34 changes: 34 additions & 0 deletions ros2node/ros2node/verb/log.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
# 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 ros2cli.node.strategy import add_arguments

from ros2node.verb import VerbExtension
from ros2node.api import call_log_level_set, LEVEL_STR_TO_ENUM
from ros2cli.node.direct import DirectNode


class LogVerb(VerbExtension):
"""Set the log level of a node"""
def add_arguments(self, parser, cli_name):
add_arguments(parser)

parser.add_argument('node_name', help='The name of the node')
parser.add_argument('-l', '--logger-name', help='The logger name, if it is different from the node name')
parser.add_argument('level', choices=LEVEL_STR_TO_ENUM.keys(), help='Log level')

def main(self, *, args):
with DirectNode(args) as node:
if args.logger_name is None:
args.logger_name = args.node_name.lstrip('/')
# Call the service to set the log level
call_log_level_set(node, args.logger_name, args.level)
1 change: 1 addition & 0 deletions ros2node/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
'ros2node.verb': [
'info = ros2node.verb.info:InfoVerb',
'list = ros2node.verb.list:ListVerb',
'log = ros2node.verb.log:LogVerb',
],
}
)