rospy overview: Initialization and Shutdown | Messages | Publishers and Subscribers | Services | Parameter Server | Logging | Names and Node Information | Time | Exceptions

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)
rospy.loginfo(msg, *args)
rospy.logwarn(msg, *args)
rospy.logerr(msg, *args)
rospy.logfatal(msg, *args)

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

  • loginfo. Note that this may not be sent to the screen depending on the value of the roslaunch/XML/node output parameter.

stderr

  • logerr, logfatal, and logwarn.

Node log file

  • all. Your node's log file will be in ROS_ROOT/log or ~/.ros/log, unless you override it with the ROS_LOG_DIR environment variable. If you are using roslaunch, you can use the roslaunch-logs command to tell you the location of the log directory. See also: Override Logging Configuration.

/rosout topic

  • loginfo, logwarn, logerr, and logfatal. Your messages will not appear on the /rosout topic until your node is fully initialized, so you may not see the initial messages. If you wish to see logdebug messages on /rosout, you can pass in the log_level parameter to rospy.init_node(), e.g.:

    rospy.init_node('my_node', log_level=rospy.DEBUG)

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)

Advanced: Override Logging Configuration

New in Diamondback

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

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

Wiki: rospy/Overview/Logging (last edited 2011-11-09 00:16:44 by PatrickMihelich)