Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix stack frame identification in rospy logging. #1141

Merged
merged 5 commits into from
Aug 15, 2017
Merged
Show file tree
Hide file tree
Changes from 4 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
77 changes: 40 additions & 37 deletions clients/rospy/src/rospy/core.py
Original file line number Diff line number Diff line change
Expand Up @@ -150,39 +150,50 @@ def _base_logger(msg, *args, **kwargs):
name = kwargs.pop('logger_name', None)
throttle = kwargs.pop('logger_throttle', None)
level = kwargs.pop('logger_level', None)

once = kwargs.pop('logger_once', False)

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

if throttle:
if once:
caller_id = _frame_to_caller_id(inspect.currentframe().f_back.f_back)
if _logging_once(caller_id):
logfunc(msg, *args)
elif throttle:
caller_id = _frame_to_caller_id(inspect.currentframe().f_back.f_back)
_logging_throttle(caller_id, logfunc, throttle, msg, *args)
if _logging_throttle(caller_id, throttle):
logfunc(msg, *args)
else:
logfunc(msg, *args)


loginfo = partial(_base_logger, logger_level='info')
def logdebug(msg, *args, **kwargs):
_base_logger(msg, *args, logger_level='debug', **kwargs)

logout = loginfo # alias deprecated name
def loginfo(msg, *args, **kwargs):
_base_logger(msg, *args, logger_level='info', **kwargs)

logdebug = partial(_base_logger, logger_level='debug')
def logwarn(msg, *args, **kwargs):
_base_logger(msg, *args, logger_level='warn', **kwargs)

logwarn = partial(_base_logger, logger_level='warn')
def logerr(msg, *args, **kwargs):
_base_logger(msg, *args, logger_level='error', **kwargs)

logerr = partial(_base_logger, logger_level='error')
def logfatal(msg, *args, **kwargs):
_base_logger(msg, *args, logger_level='critical', **kwargs)

logerror = logerr # alias logerr
logout = loginfo # alias deprecated name

logfatal = partial(_base_logger, logger_level='critical')
logerror = logerr # alias logerr


class LoggingThrottle(object):

last_logging_time_table = {}

def __call__(self, caller_id, logging_func, period, msg):
def __call__(self, caller_id, period):
"""Do logging specified message periodically.

- caller_id (str): Id to identify the caller
Expand All @@ -196,8 +207,9 @@ def __call__(self, caller_id, logging_func, period, msg):

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
return True
return False


_logging_throttle = LoggingThrottle()
Expand All @@ -213,56 +225,47 @@ def _frame_to_caller_id(frame):


def logdebug_throttle(period, msg):
logdebug(msg, logger_name=None, logger_throttle=period)
_base_logger(msg, logger_throttle=period, logger_level='debug')

def loginfo_throttle(period, msg):
loginfo(msg, logger_name=None, logger_throttle=period)
_base_logger(msg, logger_throttle=period, logger_level='info')

def logwarn_throttle(period, msg):
logwarn(msg, logger_name=None, logger_throttle=period)
_base_logger(msg, logger_throttle=period, logger_level='warn')

def logerr_throttle(period, msg):
logerr(msg, logger_name=None, logger_throttle=period)
_base_logger(msg, logger_throttle=period, logger_level='error')

def logfatal_throttle(period, msg):
logfatal(msg, logger_name=None, logger_throttle=period)
_base_logger(msg, logger_throttle=period, logger_level='critical')

class LoggingOnce(object):

called_caller_ids = set()

def __call__(self, caller_id, logging_func, msg):
def __call__(self, caller_id):
if caller_id not in self.called_caller_ids:
logging_func(msg)
self.called_caller_ids.add(caller_id)

return True
return False

_logging_once = LoggingOnce()


def logdebug_once(msg):
caller_id = _frame_to_caller_id(inspect.currentframe().f_back)
_logging_once(caller_id, logdebug, msg)

_base_logger(msg, logger_once=True, logger_level='debug')

def loginfo_once(msg):
caller_id = _frame_to_caller_id(inspect.currentframe().f_back)
_logging_once(caller_id, loginfo, msg)

_base_logger(msg, logger_once=True, logger_level='info')

def logwarn_once(msg):
caller_id = _frame_to_caller_id(inspect.currentframe().f_back)
_logging_once(caller_id, logwarn, msg)

_base_logger(msg, logger_once=True, logger_level='warn')

def logerr_once(msg):
caller_id = _frame_to_caller_id(inspect.currentframe().f_back)
_logging_once(caller_id, logerr, msg)

_base_logger(msg, logger_once=True, logger_level='error')

def logfatal_once(msg):
caller_id = _frame_to_caller_id(inspect.currentframe().f_back)
_logging_once(caller_id, logfatal, msg)
_base_logger(msg, logger_once=True, logger_level='critical')


#########################################################
Expand Down
37 changes: 23 additions & 14 deletions tools/rosgraph/src/rosgraph/roslogging.py
Original file line number Diff line number Diff line change
Expand Up @@ -60,24 +60,33 @@ def findCaller(self, dummy=False): # Dummy second arg to match Python3 function
if f is not None:
f = f.f_back
while hasattr(f, "f_code"):
# we search the right frame using the data already found by parent class
# following python logging findCaller() implementation logic
# Search for the right frame using the data already found by parent class.
co = f.f_code
filename = os.path.normcase(co.co_filename)
if filename != file_name or f.f_lineno != lineno or co.co_name != func_name:
f = f.f_back
continue
# we found the correct frame, now extending func_name with class name
try:
class_name = f.f_locals['self'].__class__.__name__
func_name = '%s.%s' % (class_name, func_name)
except KeyError: # if the function is unbound, there is no self.
pass
break
if filename == file_name and f.f_lineno == lineno and co.co_name == func_name:
break
f = f.f_back

# Jump up two more frames, as the logger methods have been double wrapped.
if f.f_back:
f = f.f_back
if f.f_back:
f = f.f_back
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

How about making this "move-two-frames-up" conditional on being "our" use case with the _base_logger?

if f.f_back and f.f_code and f.f_code.co_name == '_base_logger':
    f = f.f_back
    if f.f_back:
        f = f.f_back

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

That's a better idea. FWIW, I can't really see a case where it would be only one layer of wrapping, so the following should be safe:

if f.f_code and f.f_code.co_name == '_base_logger':
    f = f.f_back.f_back

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Better be safe than sorry: 64e284e

co = f.f_code
func_name = co.co_name

# Now extend the function name with class name, if available.
try:
class_name = f.f_locals['self'].__class__.__name__
func_name = '%s.%s' % (class_name, func_name)
except KeyError: # if the function is unbound, there is no self.
pass

if sys.version_info > (3, 2):
return file_name, lineno, func_name, None # Dummy last argument to match Python3 return type
# Dummy last argument to match Python3 return type
return co.co_filename, f.f_lineno, func_name, None
else:
return file_name, lineno, func_name
return co.co_filename, f.f_lineno, func_name

logging.setLoggerClass(RospyLogger)

Expand Down