Skip to content

Debug ROS Applications: How to Configure ROS Log Levelsâ¿»

Estimated time to read: 14 minutes

Your ROS code finish the building process without any error, you smile.
Now you are ready to deploy it to your robot in few simple steps, thanks to Robotair.
You start the application and ... The camera doesn't work at the expected frame rate, the computer vision application estimate a wrong distance, nothing goes as expected. This is the typical situation in which we want to use a logging system for debugging, with the proper logging levels.

Fortunately, ROS provide an easy to use logging system, with five severity levels, ordered by "importance" as DEBUG, INFO, WARN, ERROR, and FATAL.

You read the ROS documentation, and you add log messages to your code...
Now the DEBUG level will be responsible for development feedback. You deployed again your app over the air with Robotair, but when everything is on, you don't visualize any DEBUG message...
Surprise! The logging system has a minum severity level, and only the messages with higher level than that will be considered.
By default the minum level is INFO, but you want to change it to DEBUG for a specific node in the ROS network (locally), or for a set of nodes running in your project (or for all nodes, globally).
How can you achieve it?

In this tutorial we are going to explore the usage of the ROS logging system, focusing on the different techniques to configure the visible severity levels.
Fasten your seatbelts, and get ready to read some logging messages.

ROS 1 vs ROS 2: Brief Premise to Understand this Guideâ¿»

This is not the place to describe the differce between ROS 1 and ROS 2, but a brief premise is important to understand the structure of this guide.

When writing ROS code, developers know that Python and C++ based nodes rely on different client libraries.
In ROS 1 these client libraries (roscpp and rospy) are completely independent, in ROS 2 (rclcpp and rclpy) they are build upon a common base layer (rcl, implemented in C). In the context of the logging system, ROS 1 has a different infrastructure to manage C++ and Python loggers and verbosity level, while in ROS 2 the underline structure is the same.

For this reason, there are relevant difference when using different ROS version and programming languages, and this guide will be divided in a ROS 1 and ROS 2 section, analyzing How to configure loggers verbosity level both for Python and C++ applications, at a global level (acting to all the nodes running, when possible) and at the single node level.

ROS 1â¿»

When your project is developed with ROS 1, you have the possibility to set a global minimum severity level from a configuration file, both for C++ and Python based projects. If instead you want to reconfigure the logging level from the node source code (only for that node) it is also possible (independently of the programming language).

Python | Global Levelâ¿»

When ROS 1 nodes are written using the Python client library, the logging system rely on a global configuration file python_logging.conf. This file is divided in different sections, and it allows to reconfigure different aspects of the logging system.
Let's focus on the severity level.

The section we are interested on is [logger_rosout]

python_logging.conf

...
[logger_rosout]
level=<SEVERITY_LEVEL>
handlers=streamHandler
propagate=1
qualname=rosout
...

Navigate to this configuration file in your system /opt/ros/<ros-distro>/etc/ros/python_logging.conf ,change the level to the desired minimum <SEVERITY_LEVEL> (by default it is INFO), and save. Now you are ready to see the changes in your logging system.

[!NOTE] If you are working with a containerized ROS application, this configuration file edit can be mapped to a simple instruction in the Dockerfile responsible for the Robotair build.

Python |Node Levelâ¿»

With rospy, loggers rely on the Python logging module, and doesn't provide a direct method to change the level from the ROS client library. However there exists a workaround, using the Python logging module:

node_code.py

#!/usr/bin/env python
import rospy
import logging

class MyNode:
    def __init__(self):
        rospy.init_node('<node_name>')

        # Change the log level for this node
        self.set_log_level(logging.DEBUG)

        # Test logging 
        rospy.logdebug("Hello with DEBUG level.")
        rospy.loginfo("Hello with INFO level.")

        # Additional node initialization code...

    def set_log_level(self, level):
        # For best practice, code a level check here...
        logger = logging.getLogger('rosout')
        logger.setLevel(level)

    def run(self):
        rospy.spin()

if __name__ == '__main__':
    node = MyNode()
    node.run()

The defined method set_log_level(level) retrieve the logger and reconfigure the severity level for the node. You just have to modify your node source code by including that method, and call it in the node initilaization, after rospy.init_node('<node_name>'), to configure the node with the desired level.

The syntax for the admissible levels is: - logging.DEBUG - logging.INFO - logging.WARN - logging.ERROR - logging.FATAL

C++ | Global Levelâ¿»

Similarly to the Python client library, when nodes are based on C++, the logging system uses the infromation from a configuration file rosconsole.config (different from the python one).
The structure of this file is simple, and to reconfigure the logging level the same considetion as before holds, you just have to navigate to /opt/ros/<ros-distro>/share/ros/config/rosconsole.config and change this line:

rosconsole.config

...
log4j.logger.ros=<SEVERITY_LEVEL>
...

[!NOTE] rosconsole.config is based on log4cxx, which support environmental variable substitution (differently from python_logging.conf). Therefore, you can write log4j.logger.ros=${SEVERITY_LEVEL}, where SEVERIT_LEVEL is not hardcoded, but an environmental variable properly assigned.
Otherwise you can use the same procedure noticed before, and change the severity level with Dockerfile instructions

C++ | Node Levelâ¿»

DIfferently from rospy, in roscpp loggers are build on top of it, and it is possible to rely on the rosconsole API to change the severity level locally.

node_code.cpp

#include <ros/ros.h>
#include <ros/console.h>

class MyNode
{
public:
    MyNode()
    {
        // Change the log level for this node
        setLogLevel(ros::console::levels::Debug);

        // Test logging
        ROS_DEBUG("Hello with DEBUG Level.");
        ROS_INFO("Hello with INFO level.");

       // Additional node initialization code...

    }

    void run()
    {
        ros::spin();
    }

private:
    void setLogLevel(ros::console::Level level)
    {
        // For best practice, code a level check here...
        if (ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, level)) {
            ros::console::notifyLoggerLevelsChanged();
        }
    }
};

int main(int argc, char **argv)
{
    ros::init(argc, argv, "<node_name>");

    MyNode node;
    node.run();

    return 0;
}

The function ros::console::set_logger_level(logger_name, level) is responsible for reconfiguring the logger level, thanks to the rosconsole package. Changing the local node logging level is as simple as adding this additional set of commands to your roscpp source code.

The syntax for the admissible levels is: - ros::console::levels::Debug - ros::console::levels::Info - ros::console::levels::Warn - ros::console::levels::Error - ros::console::levels::Fatal

ROS 2â¿»

You know that ROS 1 is EOL, and you decide to develop your project with ROS 2.
Due to the same underlininig infrastructure of the client libraries, changing the logging level for each node is even simpler than before.
You can do it from the node source code, but also when running it from a launch file, or the command line (or with a Docker command)! Unfrotunately, currently there isn't any direct functionality or configuration file to set the global logging level for the overall ROS 2 Network, but we are going to explore a possible alternative.

Python | Node Levelâ¿»

The Python client library for ROS 2 rclpy implements the logging mechanism, and provide techniques to reconfigure loggers from the node source code:

node_code.py

#!/usr/bin/env python3
import rclpy
import rclpy.logging
from rclpy.node import Node


class MyNode(Node):

    def __init__(self):
        super().__init__("py_test")
        self.counter_ = 0
        # Change the log level for this node
        self.get_logger().set_level(rclpy.logging.LoggingSeverity.DEBUG)
        # Test logging 
        self.get_logger().debug("Hello with DEBUG level.")
        self.get_logger().info("Hello with INFO level.")

        # Additional node initialization code...

def main(args=None):
    rclpy.init(args=args)
    node = MyNode()
    rclpy.spin(node)
    rclpy.shutdown()

if __name__ == "__main__":
    main()

The method self.get_logger().set_level(level) is responsible for reconfiguring the logger level

The syntax for the admissible levels is: - rclpy.logging.LoggingSeverity.DEBUG - rclpy.logging.LoggingSeverity.INFO - rclpy.logging.LoggingSeverity.WARN - rclpy.logging.LoggingSeverity.ERROR - rclpy.logging.LoggingSeverity.FATAL

C++ | Node Levelâ¿»

The C++ client library for ROS 2 rclcpp also implements the logging mechanism, and provide techniques to reconfigure loggers from the node source code:

node_code.cpp

#include "rclcpp/rclcpp.hpp"

class MyNode : public rclcpp::Node
{
public:
    MyNode() : Node("cpp_test")
    {
        // Change the log level for this node
        auto ret = rcutils_logging_set_logger_level(
            get_logger().get_name(), RCUTILS_LOG_SEVERITY_DEBUG);
        if (ret != RCUTILS_RET_OK) { // checking logger is reconfigured without any error
            RCLCPP_ERROR(get_logger(), "Error setting severity: %s", rcutils_get_error_string().str);
            rcutils_reset_error();
        }
        // Test logging
        RCLCPP_DEBUG(this->get_logger(), "Hello world with DEBUG level");
        RCLCPP_INFO(this->get_logger(), "Hello world with INFO level ");

        // Additional node initialization code...
    }

private:
    // Additional methods (callbacks and so on...)
};

int main(int argc, char **argv)
{
    rclcpp::init(argc, argv);
    auto node = std::make_shared<MyNode>();
    rclcpp::spin(node);
    rclcpp::shutdown();
    return 0;
}

The function rcutils_logging_set_logger_level(logger_name, level) is responsible for reconfiguring the logger (with name logger_name) level.

The syntax for the admissible levels is: - RCUTILS_LOG_SEVERITY_DEBUG - RCUTILS_LOG_SEVERITY_INFO - RCUTILS_LOG_SEVERITY_WARN - RCUTILS_LOG_SEVERITY_ERROR - RCUTILS_LOG_SEVERITY_FATAL

Python & C++ | run/launch Timeâ¿»

As introduced above, in ROS 2 it is possible to configure the severity level of a node logger, without affecting the source code.
This is done when running the node, with the following command:

ros2 run <pkg_name> <node_name> --ros-args --log-level <SEVERITY_LEVEL>

The additional command line argument --ros-args --log-level <SEVERITY_LEVEL> is responsible for the logger configuration, and it can be easily added to a launch file.

project_bringup.launch.py

...
node_description = Node(
  package=<pkg_name>
  executable=<node_name>
  name=<custom_node_name>
  arguments=['--ros-args','--log-level','<SEVERITY_LEVEL>'] 
)
...

The syntax for the admissible levels is: - debug/DEBUG - info/INFO - warn/WARN - error/ERROR - fatal/FATAL

In this way, you can configure multiple nodes in your ROS 2 project from the launch file.
Moreover, you can consider to use launch arguments to avoid hard-coding the of your nodes. Using launch files (and launch arguments) is a possible alternative to the ROS 1 global logging configuration, even if it will work only for the configured nodes of your project, not for any node added to the ROS network. An advantage of this method is that it is indepentent of the client library of your ROS nodes (the programming language used).

Your Turn!â¿»

In conclusion, in this tutorial we have explored different ways to change the sevrity level of ROS 1 and ROS 2 loggers. While ROS 1 "global" level is based on a configuration file (differnet for C++ and Python nodes), in ROS 2 there isn't any option to set a level for all the upcoming running nodes in your project. Anyway, we have seen that in ROS 2 it is simple to change each "local" node level when it is initialized, with a running argument. Moreover, both for ROS 1 and ROS 2 there exists techniques to reconfigure the severity level in the node source code, at the initialization step. If it was not evident, notice that the same code based "node level" methods can be used at runtime, for example in a timer/subscription callback.

Now its your turn to level up your debugging skills using the ROS logging system, and deploying your debugged ROS applications over the air, with few simple clicks, thanks to Robotair!

📖 References⿻

If you are interested in learning more, here are some resources to check out: - ROS 1 vs ROS 2 | Overview for ROS Developers: roboticsbackend.com - ROS 1 | Verbosity/Severity Levels: wiki.ros.org - ROS 1 | (C++) Logging Documentation: wiki.ros.org - ROS 1 | (C++) rosconsole Documentation: wiki.ros.org - ROS 1 | (C++) Log messages (A Gentile Introduction to ROS, Ch.4): jokane.net - ROS 1 | (Python) Logging Documentation: wiki.ros.org - ROS 1 | (Python) Logging Configuration File: docs.python.org - ROS 2 | (C++ & Python) Logging Documentation: docs.ros.org - ROS 2 | (C++ & Python) Logging and logger configuration demo: docs.ros.org