1
1
#!/usr/bin/env python
2
2
3
- # Copyright 2023 Philipp Schillinger, Team ViGIR, Christopher Newport University
3
+ # Copyright 2024 Philipp Schillinger, Team ViGIR, Christopher Newport University
4
4
#
5
5
# Redistribution and use in source and binary forms, with or without
6
6
# modification, are permitted provided that the following conditions are met:
31
31
32
32
"""Realize behavior-specific logging."""
33
33
34
+ from rclpy .exceptions import ParameterNotDeclaredException
34
35
from rclpy .node import Node
36
+ from rclpy .duration import Duration
35
37
36
38
from flexbe_msgs .msg import BehaviorLog
37
39
@@ -47,13 +49,37 @@ class Logger:
47
49
48
50
LOGGING_TOPIC = 'flexbe/log'
49
51
52
+ # max number of items in last logged dict (used for log_throttle)
53
+ MAX_LAST_LOGGED_SIZE = 1024
54
+ LAST_LOGGED_CLEARING_RATIO = 0.2
55
+
50
56
_pub = None
51
57
_node = None
52
58
53
59
@staticmethod
54
60
def initialize (node : Node ):
55
61
Logger ._node = node
56
62
Logger ._pub = node .create_publisher (BehaviorLog , Logger .LOGGING_TOPIC , 100 )
63
+ Logger ._last_logged = {}
64
+
65
+ # Optional parameters that can be defined
66
+ try :
67
+ size_param = node .get_parameter ("max_throttle_logging_size" )
68
+ if size_param .type_ == size_param .Type .INTEGER :
69
+ Logger .MAX_LAST_LOGGED_SIZE = size_param .value
70
+ except ParameterNotDeclaredException as exc :
71
+ pass
72
+
73
+ try :
74
+ clear_param = node .get_parameter ("throttle_logging_clear_ratio" )
75
+ if clear_param .type_ in (clear_param .Type .INTEGER , clear_param .Type .DOUBLE ):
76
+ Logger .LAST_LOGGED_CLEARING_RATIO = clear_param .value
77
+ except ParameterNotDeclaredException as exc :
78
+ pass
79
+
80
+ Logger ._node .get_logger ().debug (f"Enable throttle logging option with "
81
+ f"max size={ Logger .MAX_LAST_LOGGED_SIZE } "
82
+ f"clear ratio={ Logger .LAST_LOGGED_CLEARING_RATIO } " )
57
83
58
84
@staticmethod
59
85
def log (text : str , severity : int ):
@@ -67,6 +93,25 @@ def log(text: str, severity: int):
67
93
# also log locally
68
94
Logger .local (text , severity )
69
95
96
+ @staticmethod
97
+ def log_throttle (period : float , text : str , severity : int ):
98
+ # create unique identifier for each logging message
99
+ log_id = f"{ severity } _{ text } "
100
+ time_now = Logger ._node .get_clock ().now ()
101
+ # only log when it's the first time or period time has passed for the logging message
102
+ if not log_id in Logger ._last_logged .keys () or \
103
+ time_now - Logger ._last_logged [log_id ] > Duration (seconds = period ):
104
+ Logger .log (text , severity )
105
+ Logger ._last_logged .update ({log_id : time_now })
106
+
107
+ if len (Logger ._last_logged ) > Logger .MAX_LAST_LOGGED_SIZE :
108
+ # iterate through last logged items, sorted by the timestamp (oldest last)
109
+ clear_size = Logger .MAX_LAST_LOGGED_SIZE * (1 - Logger .LAST_LOGGED_CLEARING_RATIO )
110
+ for i , log in enumerate (sorted (Logger ._last_logged .items (), key = lambda item : item [1 ], reverse = True )):
111
+ # remove defined percentage of oldest items
112
+ if i > clear_size :
113
+ Logger ._last_logged .pop (log [0 ])
114
+
70
115
@staticmethod
71
116
def local (text : str , severity : int ):
72
117
if Logger ._node is None :
@@ -87,57 +132,81 @@ def local(text: str, severity: int):
87
132
# NOTE: Below text strings can only have single % symbols if they are being treated
88
133
# as format strings with appropriate arguments (otherwise replace with %% for simple string without args)
89
134
@staticmethod
90
- def logdebug (text , * args ):
135
+ def logdebug (text : str , * args ):
91
136
Logger .log (text % args , Logger .REPORT_DEBUG )
92
137
93
138
@staticmethod
94
- def loginfo (text , * args ):
139
+ def loginfo (text : str , * args ):
95
140
Logger .log (text % args , Logger .REPORT_INFO )
96
141
97
142
@staticmethod
98
- def logwarn (text , * args ):
143
+ def logwarn (text : str , * args ):
99
144
Logger .log (text % args , Logger .REPORT_WARN )
100
145
101
146
@staticmethod
102
- def loghint (text , * args ):
147
+ def loghint (text : str , * args ):
103
148
Logger .log (text % args , Logger .REPORT_HINT )
104
149
105
150
@staticmethod
106
- def logerr (text , * args ):
151
+ def logerr (text : str , * args ):
107
152
Logger .log (text % args , Logger .REPORT_ERROR )
108
153
109
154
@staticmethod
110
- def localdebug (text , * args ):
155
+ def logdebug_throttle (period : float , text : str , * args ):
156
+ Logger .log_throttle (period , text % args , Logger .REPORT_DEBUG )
157
+
158
+ @staticmethod
159
+ def loginfo_throttle (period : float , text : str , * args ):
160
+ Logger .log_throttle (period , text % args , Logger .REPORT_INFO )
161
+
162
+ @staticmethod
163
+ def logwarn_throttle (period : float , text : str , * args ):
164
+ Logger .log_throttle (period , text % args , Logger .REPORT_WARN )
165
+
166
+ @staticmethod
167
+ def loghint_throttle (period : float , text : str , * args ):
168
+ Logger .log_throttle (period , text % args , Logger .REPORT_HINT )
169
+
170
+ @staticmethod
171
+ def logerr_throttle (period : float , text : str , * args ):
172
+ Logger .log_throttle (period , text % args , Logger .REPORT_ERROR )
173
+
174
+ @staticmethod
175
+ def localdebug (text : str , * args ):
111
176
Logger .local (text % args , Logger .REPORT_DEBUG )
112
177
113
178
@staticmethod
114
- def localinfo (text , * args ):
179
+ def localinfo (text : str , * args ):
115
180
Logger .local (text % args , Logger .REPORT_INFO )
116
181
117
182
@staticmethod
118
- def localwarn (text , * args ):
183
+ def localwarn (text : str , * args ):
119
184
Logger .local (text % args , Logger .REPORT_WARN )
120
185
121
186
@staticmethod
122
- def localerr (text , * args ):
187
+ def localhint (text : str , * args ):
188
+ Logger .local (text % args , Logger .REPORT_HINT )
189
+
190
+ @staticmethod
191
+ def localerr (text : str , * args ):
123
192
Logger .local (text % args , Logger .REPORT_ERROR )
124
193
125
194
@staticmethod
126
- def debug (text , * args ):
195
+ def debug (text : str , * args ):
127
196
Logger .logdebug (text , * args )
128
197
129
198
@staticmethod
130
- def info (text , * args ):
199
+ def info (text : str , * args ):
131
200
Logger .loginfo (text , * args )
132
201
133
202
@staticmethod
134
- def warning (text , * args ):
203
+ def warning (text : str , * args ):
135
204
Logger .logwarn (text , * args )
136
205
137
206
@staticmethod
138
- def hint (text , * args ):
207
+ def hint (text : str , * args ):
139
208
Logger .loghint (text , * args )
140
209
141
210
@staticmethod
142
- def error (text , * args ):
211
+ def error (text : str , * args ):
143
212
Logger .logerr (text , * args )
0 commit comments