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

suppress sequential identical messages #1309

Merged
Merged
Show file tree
Hide file tree
Changes from all 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
1 change: 1 addition & 0 deletions clients/rospy/src/rospy/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@
get_node_uri, get_ros_root, \
logdebug, logwarn, loginfo, logout, logerr, logfatal, \
logdebug_throttle, logwarn_throttle, loginfo_throttle, logerr_throttle, logfatal_throttle, \
logdebug_throttle_identical, logwarn_throttle_identical, loginfo_throttle_identical, logerr_throttle_identical, logfatal_throttle_identical, \
logdebug_once, logwarn_once, loginfo_once, logerr_once, logfatal_once, \
parse_rosrpc_uri
from .exceptions import *
Expand Down
73 changes: 62 additions & 11 deletions clients/rospy/src/rospy/core.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
import pickle
import inspect
import logging
from hashlib import md5
import os
import signal
import sys
Expand Down Expand Up @@ -143,14 +144,24 @@ def rospyerr(msg, *args):
def rospywarn(msg, *args):
"""Internal rospy client library warn logging"""
_rospy_logger.warn(msg, *args)



def _frame_to_caller_id(frame):
caller_id = (
inspect.getabsfile(frame),
frame.f_lineno,
frame.f_lasti,
)
return pickle.dumps(caller_id)


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)
throttle_identical = kwargs.pop('logger_throttle_identical', False)

rospy_logger = logging.getLogger('rosout')
if name:
Expand All @@ -161,6 +172,13 @@ def _base_logger(msg, *args, **kwargs):
caller_id = _frame_to_caller_id(inspect.currentframe().f_back.f_back)
if _logging_once(caller_id):
logfunc(msg, *args)
elif throttle_identical:
caller_id = _frame_to_caller_id(inspect.currentframe().f_back.f_back)
throttle_elapsed = False
if throttle is not None:
throttle_elapsed = _logging_throttle(caller_id, throttle)
if _logging_identical(caller_id, msg) or throttle_elapsed:
logfunc(msg, *args)
elif throttle:
caller_id = _frame_to_caller_id(inspect.currentframe().f_back.f_back)
if _logging_throttle(caller_id, throttle):
Expand Down Expand Up @@ -215,15 +233,6 @@ def __call__(self, caller_id, period):
_logging_throttle = LoggingThrottle()


def _frame_to_caller_id(frame):
caller_id = (
inspect.getabsfile(frame),
frame.f_lineno,
frame.f_lasti,
)
return pickle.dumps(caller_id)


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

Expand All @@ -239,6 +248,49 @@ def logerr_throttle(period, msg):
def logfatal_throttle(period, msg):
_base_logger(msg, logger_throttle=period, logger_level='critical')


class LoggingIdentical(object):

last_logging_msg_table = {}

def __call__(self, caller_id, msg):
"""Do logging specified message only if distinct from last message.

- caller_id (str): Id to identify the caller
- msg (str): Contents of message to log
"""
msg_hash = md5(msg).hexdigest()

if msg_hash != self.last_logging_msg_table.get(caller_id):
self.last_logging_msg_table[caller_id] = msg_hash
return True
return False


_logging_identical = LoggingIdentical()


def logdebug_throttle_identical(period, msg):
_base_logger(msg, logger_throttle=period, logger_throttle_identical=True,
logger_level='debug')

def loginfo_throttle_identical(period, msg):
_base_logger(msg, logger_throttle=period, logger_throttle_identical=True,
logger_level='info')

def logwarn_throttle_identical(period, msg):
_base_logger(msg, logger_throttle=period, logger_throttle_identical=True,
logger_level='warn')

def logerr_throttle_identical(period, msg):
_base_logger(msg, logger_throttle=period, logger_throttle_identical=True,
logger_level='error')

def logfatal_throttle_identical(period, msg):
_base_logger(msg, logger_throttle=period, logger_throttle_identical=True,
logger_level='critical')


class LoggingOnce(object):

called_caller_ids = set()
Expand Down Expand Up @@ -595,4 +647,3 @@ def xmlrpcapi(uri):
if not uriValidate[0] or not uriValidate[1]:
return None
return xmlrpcclient.ServerProxy(uri)

93 changes: 91 additions & 2 deletions test/test_rospy/test/rostest/test_rospy_client_online.py
Original file line number Diff line number Diff line change
Expand Up @@ -164,7 +164,7 @@ def test_log(self):
self.assert_("test 1" in lout_last)
lout_len = len(lout.getvalue())
rospy.sleep(rospy.Duration(1))
elif i == 1: # making sure the length of lerr doesnt change
elif i == 1: # making sure the length of lout doesnt change
self.assert_(lout_len == len(lout.getvalue()))
rospy.sleep(rospy.Duration(2))
else:
Expand Down Expand Up @@ -211,7 +211,96 @@ def test_log(self):
rospy.sleep(rospy.Duration(2))
else:
self.assert_("test 4" in lerr_last)


# logXXX_throttle_identical
lout_len = -1
for i in range(5):
if i < 2:
test_text = "test 1"
else:
test_text = "test 1a"
rospy.loginfo_throttle_identical(2, test_text)
lout_last = lout.getvalue().splitlines()[-1]
if i == 0: # Confirm test text was logged
self.assert_(test_text in lout_last)
lout_len = len(lout.getvalue())
elif i == 1: # Confirm the length of lout hasn't changed
self.assert_(lout_len == len(lout.getvalue()))
elif i == 2: # Confirm the new message was logged correctly
self.assert_(test_text in lout_last)
lout_len = len(lout.getvalue())
rospy.sleep(rospy.Duration(2))
elif i == 3: # Confirm the length of lout has changed
self.assert_(lout_len != len(lout.getvalue()))
else: # Confirm new test text is in last log
self.assert_(test_text in lout_last)

lerr_len = -1
for i in range(5):
if i < 2:
test_text = "test 2"
else:
test_text = "test 2a"
rospy.logwarn_throttle_identical(2, test_text)
lerr_last = lerr.getvalue().splitlines()[-1]
if i == 0: # Confirm test text was logged
self.assert_(test_text in lerr_last)
lerr_len = len(lerr.getvalue())
elif i == 1: # Confirm the length of lerr hasn't changed
self.assert_(lerr_len == len(lerr.getvalue()))
elif i == 2: # Confirm the new message was logged correctly
self.assert_(test_text in lerr_last)
lerr_len = len(lerr.getvalue())
rospy.sleep(rospy.Duration(2))
elif i == 3: # Confirm the length of lerr has incremented
self.assert_(lerr_len != len(lerr.getvalue()))
else: # Confirm new test text is in last log
self.assert_(test_text in lerr_last)

lerr_len = -1
for i in range(5):
if i < 2:
test_text = "test 3"
else:
test_text = "test 3a"
rospy.logerr_throttle_identical(2, test_text)
lerr_last = lerr.getvalue().splitlines()[-1]
if i == 0: # Confirm test text was logged
self.assert_(test_text in lerr_last)
lerr_len = len(lerr.getvalue())
elif i == 1: # Confirm the length of lerr hasn't changed
self.assert_(lerr_len == len(lerr.getvalue()))
elif i == 2: # Confirm the new message was logged correctly
self.assert_(test_text in lerr_last)
lerr_len = len(lerr.getvalue())
rospy.sleep(rospy.Duration(2))
elif i == 3: # Confirm the length of lerr has incremented
self.assert_(lerr_len != len(lerr.getvalue()))
else: # Confirm new test text is in last log
self.assert_(test_text in lerr_last)

lerr_len = -1
for i in range(5):
if i < 2:
test_text = "test 4"
else:
test_text = "test 4a"
rospy.logfatal_throttle_identical(2, test_text)
lerr_last = lerr.getvalue().splitlines()[-1]
if i == 0: # Confirm test text was logged
self.assert_(test_text in lerr_last)
lerr_len = len(lerr.getvalue())
elif i == 1: # Confirm the length of lerr hasn't changed
self.assert_(lerr_len == len(lerr.getvalue()))
elif i == 2: # Confirm the new message was logged correctly
self.assert_(test_text in lerr_last)
lerr_len = len(lerr.getvalue())
rospy.sleep(rospy.Duration(2))
elif i == 3: # Confirm the length of lerr has incremented
self.assert_(lerr_len != len(lerr.getvalue()))
else: # Confirm new test text is in last log
self.assert_(test_text in lerr_last)

rospy.loginfo("test child logger 1", logger_name="log1")
lout_last = lout.getvalue().splitlines()[-1]
self.assert_("test child logger 1" in lout_last)
Expand Down