0
$\begingroup$

I'm trying to convert some code from ros1 into ros2. In ros1, it was possible to print logging messages from anywhere in a process by using rospy.loginfo("my_message") once a node was initialised.

In ros2 things work differently, and the logger is attached to a node and is retrieved with the node.get_logger() function. However, this is sometimes inconvenient, because accessing that logger would require passing the node object around to a variety of other objects which shouldn't care about the node. These objects might be used multiple times in different parts of the system.

I found this question Global logger for logging without a node which indicates that you can do something like

import rclpy
from rclpy.impl import rcutils_logger
from rclpy.node import Node
if __name__ == "__main__":
    rclpy.init()
    my_node = Node("my_node")
    my_node.get_logger().info("Did something")
    rcutils_logger.RcutilsLogger(name="temp_logger").info("Non-ros component message")

This does work, but results in logs like

[INFO] [1738333789.963975903] [my_node]: Did something
[INFO] [1738333789.964233143] [temp_logger]: Non-ros component message

where the message from the rcutils logger appears from a different logger than the one from the node, since we specify a different name. This could be a problem if we're using this non-ros component in multiple different places, since we don't know which node the message is actually coming from.

In this tiny example we could just call the temporary logger a different name, but in practice that wouldn't work since we don't know what node we're actually in when creating the logger. Perhaps there are two possible options here:

  1. Retrieve the logger for the node in some way which doesn't require ros interaction. Perhaps through the logging api?
  2. Get the correct name for the node and instantiate the logger that way. But this probably requires ros interaction to get node names.

I would appreciate any suggestions for approaches to logging without access to a node, which would appear in the ROS logs.

$\endgroup$

1 Answer 1

0
$\begingroup$

A possible solution is to customise python's root logger so that messages sent to that logger get routed through the node's logging functions instead. This will only work for processes which contain a single node, since we're attaching a specific node to function as the root logger.

import rclpy
from rclpy.node import Node
import logging


class ROS2Logger(logging.Logger):

    # Map between levels in ROS2 and python's logging module
    severity_map_ros = {
        LoggingSeverity.DEBUG: logging.DEBUG,
        LoggingSeverity.INFO: logging.INFO,
        LoggingSeverity.WARN: logging.WARN,
        LoggingSeverity.ERROR: logging.ERROR,
        LoggingSeverity.FATAL: logging.FATAL,
    }

    def __init__(self, node: rclpy.node.Node):
        super().__init__("root")
        # Add a custom handler which will intercept messages from python logging and send them through the node's logger
        self.addHandler(ROS2LoggingHandler(node))
        # Set the python logger's level from the node's severity. If this isn't set correctly some messages will be
        # missed by the handler
        self.setLevel(self.severity_map_ros[my_node.get_logger().get_effective_level()])


class ROS2LoggingHandler(logging.Handler):

    def __init__(self, node: rclpy.node.Node):
        super().__init__()
        self.node_logger = node.get_logger()

    def emit(self, record: LogRecord):
        # Check the level of the record in relation to the log levels, and use the corresponding function of the
        # node's logger
        if record.levelno >= logging.FATAL:
            self.node_logger.fatal(record.msg)
        elif record.levelno >= logging.ERROR:
            self.node_logger.error(record.msg)
        elif record.levelno >= logging.WARNING:
            self.node_logger.warning(record.msg)
        elif record.levelno >= logging.INFO:
            self.node_logger.info(record.msg)
        else:
            self.node_logger.debug(record.msg)


if __name__ == "__main__":
    rclpy.init()

    my_node = Node("my_node")
    my_node.get_logger().set_level(LoggingSeverity.DEBUG)

    logging.root = ROS2Logger(my_node)

    my_node.get_logger().info("Node did something")
    logging.getLogger().debug("debug")
    logging.getLogger().info("info")
    logging.getLogger().warning("warning")
    logging.getLogger().error("error")
    logging.getLogger().fatal("fatal")

This results in the following log, which as desired will be associated with the node in question:

[INFO] [1738337555.933412948] [my_node]: Node did something
[DEBUG] [1738337555.933703164] [my_node]: debug
[INFO] [1738337555.933937413] [my_node]: info
[WARN] [1738337555.934165346] [my_node]: warning
[ERROR] [1738337555.934387091] [my_node]: error
[FATAL] [1738337555.934604045] [my_node]: fatal

The downside is that you need to import the custom logger everywhere you'd like to use it, and replace the root logger with it.

$\endgroup$

Start asking to get answers

Find the answer to your question by asking.

Ask question

Explore related questions

See similar questions with these tags.