[Documentation] [TitleIndex] [WordIndex

ROS has its own topic-based mechanism, called rosout for recording log messages from nodes. These log messages are human-readable string messages that convey the status of a node.

rospy has several methods for writing log messages, all starting with "log":

rospy.logdebug(msg, *args, **kwargs)
rospy.loginfo(msg, *args, **kwargs)
rospy.logwarn(msg, *args, **kwargs)
rospy.logerr(msg, *args, **kwargs)
rospy.logfatal(msg, *args, **kwargs)

These levels have a one-to-one correspondence to ROS' logging verbosity levels.

Each rospy.log*() method can take in a string msg. If msg is a format string, you can pass in the arguments for the string separately, e.g.

rospy.logerr("%s returned the invalid value %s", other_name, other_value)

Reading log messages

There are four potential places a log message may end up depending on the verbosity level:

stdout

stderr

Node log file

/rosout topic

Here is a table summarizing the above:

Debug

Info

Warn

Error

Fatal

stdout

X

stderr

X

X

X

log file

X

X

X

X

X

/rosout

o

X

X

X

X

Also note that this table is different for roscpp.

Example

Here's a quick example with a talker Node:

   1     topic = 'chatter'
   2     pub = rospy.Publisher(topic, String)
   3     rospy.init_node('talker', anonymous=True)
   4     rospy.loginfo("I will publish to the topic %s", topic)
   5     while not rospy.is_shutdown():
   6         str = "hello world %s"%rospy.get_time()
   7         rospy.loginfo(str)
   8         pub.publish(str)
   9         rospy.sleep(0.1)

Logging Periodically

New in Kinetic

Since Kinetic, rospy supports writing log messages periodically. The output will print a message at most once per "period" second by rospy.log*_throttle(period, msg).

   1 while True:
   2     rospy.loginfo_throttle(60, "This message will print every 60 seconds")

New in Melodic

There is also a variation that throttles only if the message contents are identical

   1 while True:
   2     rospy.loginfo_throttle_identical(10, "This message will print every 10 seconds")

Logging Once

New in Lunar

Since Lunar, rospy supports writing log messages only once after it is spawned. The output will print a message once by rospy.log*_once(msg).

   1 while True:
   2     rospy.loginfo_once("This message will print only once")

Named Logging

New in Lunar

Since Lunar, named loggers can be used in rospy by passing the logger_name keyword argument. Named loggers output to a child of the default logger and thereby allow logging statements to be grouped and enabled/disabled based on the logger name.

   1 rospy.loginfo("This will output to logger rosout.my_logger_name.", logger_name="my_logger_name")

The logger level for specific loggers can be changed by calling the /<node name>/set_logger_level service or by using the Logger Level GUI.

Advanced: Override Logging Configuration

By default, rospy and other ROS python libraries use $ROS_ROOT/../../etc/ros/python_logging.conf. This file is the standard fileConfig format used by the Python logging module (see https://docs.python.org/library/logging.config.html#configuration-file-format).

You can override the location of this configuration file by setting the ROS_PYTHON_LOG_CONFIG_FILE environment variable.

New in Lunar

Since Lunar, a yaml file (by default $ROS_ROOT/../../etc/ros/python_logging.yaml but it is reconfigurable as well) can be used to configure python logging as explained in the python logging documentation. This more recent configuration format will give you access to more settings than the traditional one. The recent diff related to this feature is on the github repo. rospy automatically detects the latter by file extension either '.yaml' or '.yml'. So If you mean to use YAML format, make sure add the proper extension.

Logger Level GUI

rqt_logger_level provides a GUI to change rospy's logger level for individual loggers during runtime.


2024-11-16 17:44