From 9b027999fdce3d95e3f9b106e2713959e97da712 Mon Sep 17 00:00:00 2001 From: HannesBachter Date: Wed, 8 Mar 2023 16:36:40 +0100 Subject: [PATCH 1/5] add Logger.log*_throttle --- flexbe_core/src/flexbe_core/logger.py | 55 +++++++++++++++++++++++---- 1 file changed, 48 insertions(+), 7 deletions(-) diff --git a/flexbe_core/src/flexbe_core/logger.py b/flexbe_core/src/flexbe_core/logger.py index 98e0e3c..7f5f9e1 100644 --- a/flexbe_core/src/flexbe_core/logger.py +++ b/flexbe_core/src/flexbe_core/logger.py @@ -21,6 +21,7 @@ class Logger(object): @staticmethod def initialize(): Logger._pub = rospy.Publisher(Logger.LOGGING_TOPIC, BehaviorLog, queue_size=100) + Logger._last_logged = None @staticmethod def log(text, severity): @@ -50,29 +51,69 @@ def local(text, severity): rospy.logdebug(text + ' (unknown log level %s)' % str(severity)) @staticmethod - def logdebug(text, *args): + def logdebug(text: str, *args): Logger.log(text % args, Logger.REPORT_DEBUG) @staticmethod - def loginfo(text, *args): + def loginfo(text: str, *args): Logger.log(text % args, Logger.REPORT_INFO) @staticmethod - def logwarn(text, *args): + def logwarn(text: str, *args): Logger.log(text % args, Logger.REPORT_WARN) @staticmethod - def loghint(text, *args): + def loghint(text: str, *args): Logger.log(text % args, Logger.REPORT_HINT) @staticmethod - def logerr(text, *args): + def logerr(text: str, *args): Logger.log(text % args, Logger.REPORT_ERROR) @staticmethod - def localdebug(text, *args): + def logdebug_throttle(period: float, text: str, *args): + # only log when it's the first time or period time has passed + if not Logger._last_logged or \ + rospy.Time.now().to_sec() - Logger._last_logged.to_sec() > period: + Logger.log(text % args, Logger.REPORT_DEBUG) + Logger._last_logged = rospy.Time.now() + + @staticmethod + def loginfo_throttle(period: float, text: str, *args): + # only log when it's the first time or period time has passed + if not Logger._last_logged or \ + rospy.Time.now().to_sec() - Logger._last_logged.to_sec() > period: + Logger.log(text % args, Logger.REPORT_INFO) + Logger._last_logged = rospy.Time.now() + + @staticmethod + def logwarn_throttle(period: float, text: str, *args): + # only log when it's the first time or period time has passed + if not Logger._last_logged or \ + rospy.Time.now().to_sec() - Logger._last_logged.to_sec() > period: + Logger.log(text % args, Logger.REPORT_WARN) + Logger._last_logged = rospy.Time.now() + + @staticmethod + def loghint_throttle(period: float, text: str, *args): + # only log when it's the first time or period time has passed + if not Logger._last_logged or \ + rospy.Time.now().to_sec() - Logger._last_logged.to_sec() > period: + Logger.log(text % args, Logger.REPORT_HINT) + Logger._last_logged = rospy.Time.now() + + @staticmethod + def logerr_throttle(period: float, text: str, *args): + # only log when it's the first time or period time has passed + if not Logger._last_logged or \ + rospy.Time.now().to_sec() - Logger._last_logged.to_sec() > period: + Logger.log(text % args, Logger.REPORT_ERROR) + Logger._last_logged = rospy.Time.now() + + @staticmethod + def localdebug(text: str, *args): Logger.local(text % args, Logger.REPORT_DEBUG) @staticmethod - def localinfo(text, *args): + def localinfo(text: str, *args): Logger.local(text % args, Logger.REPORT_INFO) From 0192336a732a739db8930501758c4398eb85cae9 Mon Sep 17 00:00:00 2001 From: HannesBachter Date: Fri, 10 Mar 2023 10:33:13 +0100 Subject: [PATCH 2/5] connect throttle timestamp with unique logging id --- flexbe_core/src/flexbe_core/logger.py | 45 +++++++++++---------------- 1 file changed, 19 insertions(+), 26 deletions(-) diff --git a/flexbe_core/src/flexbe_core/logger.py b/flexbe_core/src/flexbe_core/logger.py index 7f5f9e1..01487d5 100644 --- a/flexbe_core/src/flexbe_core/logger.py +++ b/flexbe_core/src/flexbe_core/logger.py @@ -21,7 +21,7 @@ class Logger(object): @staticmethod def initialize(): Logger._pub = rospy.Publisher(Logger.LOGGING_TOPIC, BehaviorLog, queue_size=100) - Logger._last_logged = None + Logger._last_logged = {} @staticmethod def log(text, severity): @@ -35,6 +35,16 @@ def log(text, severity): # also log locally Logger.local(text, severity) + @staticmethod + def log_throttle(period, text, severity): + # creat unique identifier for each logging message + log_id = str(severity) + "_" + text + # only log when it's the first time or period time has passed for the logging message + if not log_id in Logger._last_logged.keys() or \ + rospy.Time.now().to_sec() - Logger._last_logged[log_id].to_sec() > period: + Logger.log(text, severity) + Logger._last_logged.update({log_id: rospy.Time.now()}) + @staticmethod def local(text, severity): if severity == Logger.REPORT_INFO: @@ -72,43 +82,26 @@ def logerr(text: str, *args): @staticmethod def logdebug_throttle(period: float, text: str, *args): - # only log when it's the first time or period time has passed - if not Logger._last_logged or \ - rospy.Time.now().to_sec() - Logger._last_logged.to_sec() > period: - Logger.log(text % args, Logger.REPORT_DEBUG) - Logger._last_logged = rospy.Time.now() + Logger.log_throttle(period, text % args, Logger.REPORT_DEBUG) @staticmethod def loginfo_throttle(period: float, text: str, *args): - # only log when it's the first time or period time has passed - if not Logger._last_logged or \ - rospy.Time.now().to_sec() - Logger._last_logged.to_sec() > period: - Logger.log(text % args, Logger.REPORT_INFO) - Logger._last_logged = rospy.Time.now() + Logger.log_throttle(period, text % args, Logger.REPORT_INFO) + @staticmethod def logwarn_throttle(period: float, text: str, *args): - # only log when it's the first time or period time has passed - if not Logger._last_logged or \ - rospy.Time.now().to_sec() - Logger._last_logged.to_sec() > period: - Logger.log(text % args, Logger.REPORT_WARN) - Logger._last_logged = rospy.Time.now() + Logger.log_throttle(period, text % args, Logger.REPORT_WARN) @staticmethod def loghint_throttle(period: float, text: str, *args): - # only log when it's the first time or period time has passed - if not Logger._last_logged or \ - rospy.Time.now().to_sec() - Logger._last_logged.to_sec() > period: - Logger.log(text % args, Logger.REPORT_HINT) - Logger._last_logged = rospy.Time.now() + Logger.log_throttle(period, text % args, Logger.REPORT_HINT) + @staticmethod def logerr_throttle(period: float, text: str, *args): - # only log when it's the first time or period time has passed - if not Logger._last_logged or \ - rospy.Time.now().to_sec() - Logger._last_logged.to_sec() > period: - Logger.log(text % args, Logger.REPORT_ERROR) - Logger._last_logged = rospy.Time.now() + Logger.log_throttle(period, text % args, Logger.REPORT_ERROR) + @staticmethod def localdebug(text: str, *args): From 5deddc99a87611d8932fe1dd5fc584c370347ab7 Mon Sep 17 00:00:00 2001 From: fmessmer Date: Fri, 17 Mar 2023 15:11:11 +0100 Subject: [PATCH 3/5] harmonize --- flexbe_core/src/flexbe_core/logger.py | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/flexbe_core/src/flexbe_core/logger.py b/flexbe_core/src/flexbe_core/logger.py index 01487d5..1c7fe78 100644 --- a/flexbe_core/src/flexbe_core/logger.py +++ b/flexbe_core/src/flexbe_core/logger.py @@ -110,3 +110,15 @@ def localdebug(text: str, *args): @staticmethod def localinfo(text: str, *args): Logger.local(text % args, Logger.REPORT_INFO) + + @staticmethod + def localwarn(text: str, *args): + Logger.local(text % args, Logger.REPORT_WARN) + + @staticmethod + def localhint(text: str, *args): + Logger.local(text % args, Logger.REPORT_HINT) + + @staticmethod + def localerr(text: str, *args): + Logger.local(text % args, Logger.REPORT_ERROR) From 55025a60ce2bf1faa3fdc92732ac6c2ff901ba14 Mon Sep 17 00:00:00 2001 From: HannesBachter Date: Mon, 20 Nov 2023 12:41:33 +0100 Subject: [PATCH 4/5] keep throttle helper dict to max 1024 entries --- flexbe_core/src/flexbe_core/logger.py | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/flexbe_core/src/flexbe_core/logger.py b/flexbe_core/src/flexbe_core/logger.py index 1c7fe78..97f2693 100644 --- a/flexbe_core/src/flexbe_core/logger.py +++ b/flexbe_core/src/flexbe_core/logger.py @@ -16,6 +16,9 @@ class Logger(object): LOGGING_TOPIC = 'flexbe/log' + # max number of items in last logged dict (used for log_throttle) + MAX_LAST_LOGGED_SIZE = 1024 + _pub = None @staticmethod @@ -45,6 +48,13 @@ def log_throttle(period, text, severity): Logger.log(text, severity) Logger._last_logged.update({log_id: rospy.Time.now()}) + if len(Logger._last_logged) > Logger.MAX_LAST_LOGGED_SIZE: + # iterate through last logged items, sorted by the timestamp (oldest last) + for i, log in enumerate(sorted(Logger._last_logged.items(), key=lambda item: item[1], reverse=True)): + # remove oldest items that exceed the max logged size + if i > Logger.MAX_LAST_LOGGED_SIZE: + Logger._last_logged.pop(log[0]) + @staticmethod def local(text, severity): if severity == Logger.REPORT_INFO: From 99505caf0f1fbbd53218e4e84da293d379e946a8 Mon Sep 17 00:00:00 2001 From: HannesBachter Date: Tue, 21 Nov 2023 09:49:57 +0100 Subject: [PATCH 5/5] clear specified ratio of last logged throttle dict --- flexbe_core/src/flexbe_core/logger.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/flexbe_core/src/flexbe_core/logger.py b/flexbe_core/src/flexbe_core/logger.py index 97f2693..7290a30 100644 --- a/flexbe_core/src/flexbe_core/logger.py +++ b/flexbe_core/src/flexbe_core/logger.py @@ -18,6 +18,7 @@ class Logger(object): # max number of items in last logged dict (used for log_throttle) MAX_LAST_LOGGED_SIZE = 1024 + LAST_LOGGED_CLEARING_RATIO = 0.2 _pub = None @@ -51,8 +52,8 @@ def log_throttle(period, text, severity): if len(Logger._last_logged) > Logger.MAX_LAST_LOGGED_SIZE: # iterate through last logged items, sorted by the timestamp (oldest last) for i, log in enumerate(sorted(Logger._last_logged.items(), key=lambda item: item[1], reverse=True)): - # remove oldest items that exceed the max logged size - if i > Logger.MAX_LAST_LOGGED_SIZE: + # remove defined percentage of oldest items + if i > (Logger.MAX_LAST_LOGGED_SIZE * (1 - Logger.LAST_LOGGED_CLEARING_RATIO)): Logger._last_logged.pop(log[0]) @staticmethod