diff --git a/clients/rospy/src/rospy/core.py b/clients/rospy/src/rospy/core.py index d8dabd2651..ed838fe2ae 100644 --- a/clients/rospy/src/rospy/core.py +++ b/clients/rospy/src/rospy/core.py @@ -72,6 +72,7 @@ from rospy.impl.validators import ParameterInvalid from rosgraph_msgs.msg import Log +from functools import partial _logger = logging.getLogger("rospy.core") @@ -143,17 +144,38 @@ 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 - -loginfo = logging.getLogger('rosout').info -logout = loginfo # alias deprecated name - -logerr = logging.getLogger('rosout').error -logerror = logerr # alias logerr - -logfatal = logging.getLogger('rosout').critical + +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_to_caller_id(inspect.currentframe().f_back.f_back) + _logging_throttle(caller_id, logfunc, throttle, msg, *args) + else: + logfunc(msg, *args) + + +loginfo = partial(_base_logger, logger_level='info') + +logout = loginfo # alias deprecated name + +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 = partial(_base_logger, logger_level='critical') class LoggingThrottle(object): @@ -191,29 +213,19 @@ def _frame_to_caller_id(frame): def logdebug_throttle(period, msg): - caller_id = _frame_to_caller_id(inspect.currentframe().f_back) - _logging_throttle(caller_id, logdebug, period, msg) - - + logdebug(msg, logger_name=None, logger_throttle=period) + def loginfo_throttle(period, msg): - caller_id = _frame_to_caller_id(inspect.currentframe().f_back) - _logging_throttle(caller_id, loginfo, period, msg) - - + loginfo(msg, logger_name=None, logger_throttle=period) + def logwarn_throttle(period, msg): - caller_id = _frame_to_caller_id(inspect.currentframe().f_back) - _logging_throttle(caller_id, logwarn, period, msg) - + logwarn(msg, logger_name=None, logger_throttle=period) def logerr_throttle(period, msg): - caller_id = _frame_to_caller_id(inspect.currentframe().f_back) - _logging_throttle(caller_id, logerr, period, msg) - - + logerr(msg, logger_name=None, logger_throttle=period) + def logfatal_throttle(period, msg): - caller_id = _frame_to_caller_id(inspect.currentframe().f_back) - _logging_throttle(caller_id, logfatal, period, msg) - + logfatal(msg, logger_name=None, logger_throttle=period) class LoggingOnce(object): diff --git a/test/test_rospy/test/rostest/test_rospy_client_online.py b/test/test_rospy/test/rostest/test_rospy_client_online.py index a42157674f..4000ed6212 100755 --- a/test/test_rospy/test/rostest/test_rospy_client_online.py +++ b/test/test_rospy/test/rostest/test_rospy_client_online.py @@ -182,6 +182,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 diff --git a/test/test_rospy/test/unit/test_rospy_core.py b/test/test_rospy/test/unit/test_rospy_core.py index bb0375ab43..d1889b8c0e 100644 --- a/test/test_rospy/test/unit/test_rospy_core.py +++ b/test/test_rospy/test/unit/test_rospy_core.py @@ -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