Skip to content

Commit

Permalink
Add named loggers to rospy (#948)
Browse files Browse the repository at this point in the history
  • Loading branch information
mikepurvis committed Feb 24, 2017
1 parent 22f43d7 commit edda71b
Show file tree
Hide file tree
Showing 3 changed files with 116 additions and 72 deletions.
162 changes: 91 additions & 71 deletions clients/rospy/src/rospy/core.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,11 +37,11 @@


import atexit
try:
import cPickle as pickle
except ImportError:
import pickle
import inspect
try:
import cPickle as pickle
except ImportError:
import pickle
import inspect
import logging
import os
import signal
Expand All @@ -68,6 +68,8 @@
from rospy.impl.validators import ParameterInvalid

from rosgraph_msgs.msg import Log
from functools import partial
from collections import namedtuple

_logger = logging.getLogger("rospy.core")

Expand Down Expand Up @@ -139,78 +141,96 @@ def rospywarn(msg, *args):
"""Internal rospy client library warn logging"""
_rospy_logger.warn(msg, *args)

logdebug = logging.getLogger('rosout').debug

logwarn = logging.getLogger('rosout').warning
def _base_logger(msg, *args, **kwargs):

name = kwargs.pop('logger_name', None)
throttle = kwargs.pop('logger_throttle', None)
level = kwargs.pop('logger_level', None)

rospy_logger = logging.getLogger('rosout')
if name:
rospy_logger = rospy_logger.getChild(name)
logfunc = getattr(rospy_logger, level)

if throttle:
caller_id = _frame_record_to_caller_id(inspect.stack()[2])
_logging_throttle(caller_id, logfunc, throttle, msg, *args)
else:
logfunc(msg, *args)


loginfo = partial(_base_logger, logger_level='info')

loginfo = logging.getLogger('rosout').info
logout = loginfo # alias deprecated name

logerr = logging.getLogger('rosout').error
logdebug = partial(_base_logger, logger_level='debug')

logwarn = partial(_base_logger, logger_level='warn')

logerr = partial(_base_logger, logger_level='error')

logerror = logerr # alias logerr

logfatal = logging.getLogger('rosout').critical


class LoggingThrottle(object):

last_logging_time_table = {}

def __call__(self, caller_id, logging_func, period, msg):
"""Do logging specified message periodically.
- caller_id (str): Id to identify the caller
- logging_func (function): Function to do logging.
- period (float): Period to do logging in second unit.
- msg (object): Message to do logging.
"""
now = rospy.Time.now()

last_logging_time = self.last_logging_time_table.get(caller_id)

if (last_logging_time is None or
(now - last_logging_time) > rospy.Duration(period)):
logging_func(msg)
self.last_logging_time_table[caller_id] = now


_logging_throttle = LoggingThrottle()


def _frame_record_to_caller_id(frame_record):
frame, _, lineno, _, code, _ = frame_record
caller_id = (
inspect.getabsfile(frame),
lineno,
frame.f_lasti,
)
return pickle.dumps(caller_id)


def logdebug_throttle(period, msg):
caller_id = _frame_record_to_caller_id(inspect.stack()[1])
_logging_throttle(caller_id, logdebug, period, msg)


def loginfo_throttle(period, msg):
caller_id = _frame_record_to_caller_id(inspect.stack()[1])
_logging_throttle(caller_id, loginfo, period, msg)


def logwarn_throttle(period, msg):
caller_id = _frame_record_to_caller_id(inspect.stack()[1])
_logging_throttle(caller_id, logwarn, period, msg)


def logerr_throttle(period, msg):
caller_id = _frame_record_to_caller_id(inspect.stack()[1])
_logging_throttle(caller_id, logerr, period, msg)


def logfatal_throttle(period, msg):
caller_id = _frame_record_to_caller_id(inspect.stack()[1])
_logging_throttle(caller_id, logfatal, period, msg)

logfatal = partial(_base_logger, logger_level='critical')


class LoggingThrottle(object):

LogEntry = namedtuple("LogEntry", "time digest")

last_log_entry = {}

def __call__(self, caller_id, logging_func, period, msg, *args):
"""Do logging specified message periodically. Messages with different contents will bypass throttling
- caller_id (str): Id to identify the caller
- logging_func (function): Function to do logging.
- period (float): Period to do logging in seconds.
- msg (object): Message to do logging.
"""
now = rospy.Time.now()

last = self.last_log_entry.get(caller_id, self.LogEntry(time=None, digest=None))
digest = hash(*args + tuple([str(msg)]))

if (last.time is None or (now - last.time) > rospy.Duration(period) or digest != last.digest):
logging_func(msg, *args)
self.last_log_entry[caller_id] = self.LogEntry(time=now, digest=digest)


_logging_throttle = LoggingThrottle()


def _frame_record_to_caller_id(frame_record):
frame, _, lineno, _, code, _ = frame_record
caller_id = (
inspect.getabsfile(frame),
lineno,
frame.f_lasti,
)
return pickle.dumps(caller_id)


def logdebug_throttle(period, msg):
logdebug(msg, logger_name=None, logger_throttle=period)


def loginfo_throttle(period, msg):
loginfo(msg, logger_name=None, logger_throttle=period)


def logwarn_throttle(period, msg):
logwarn(msg, logger_name=None, logger_throttle=period)


def logerr_throttle(period, msg):
logerr(msg, logger_name=None, logger_throttle=period)


def logfatal_throttle(period, msg):
logfatal(msg, logger_name=None, logger_throttle=period)


#########################################################
# CONSTANTS
Expand Down
18 changes: 18 additions & 0 deletions test/test_rospy/test/rostest/test_rospy_client_online.py
Original file line number Diff line number Diff line change
Expand Up @@ -149,6 +149,24 @@ def test_log(self):
rospy.sleep(rospy.Duration(2))
else:
self.assert_("test 4" in sys.stderr.getvalue())

rospy.loginfo("test child logger 1", logger_name="log1")
self.assert_("test child logger 1" in sys.stdout.getvalue())

rospy.logwarn("test child logger 2", logger_name="log2")
self.assert_("[WARN]" in sys.stderr.getvalue())
self.assert_("test child logger 2" in sys.stderr.getvalue())

sys.stderr = StringIO()
rospy.logerr("test child logger 3", logger_name="log3")
self.assert_("[ERROR]" in sys.stderr.getvalue())
self.assert_("test child logger 3" in sys.stderr.getvalue())

sys.stderr = StringIO()
rospy.logfatal("test child logger 4", logger_name="log4")
self.assert_("[FATAL]" in sys.stderr.getvalue())
self.assert_("test child logger 4" in sys.stderr.getvalue())

finally:
sys.stdout = real_stdout
sys.stderr = real_stderr
Expand Down
8 changes: 7 additions & 1 deletion test/test_rospy/test/unit/test_rospy_core.py
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,13 @@ def test_loggers(self):
rospy.logout('out')
rospy.logerr('err')
rospy.logfatal('fatal')

#basic named logger test
rospy.logdebug('debug', logger_name="child1")
rospy.logwarn('warn', logger_name="child1")
rospy.logout('out', logger_name="child1")
rospy.logerr('err', logger_name="child1")
rospy.logfatal('fatal', logger_name="child1")

def test_add_shutdown_hook(self):
def handle(reason):
pass
Expand Down

0 comments on commit edda71b

Please sign in to comment.