diff --git a/clients/rospy/src/rospy/core.py b/clients/rospy/src/rospy/core.py index 354b0e97a1..1d5ffc74b5 100644 --- a/clients/rospy/src/rospy/core.py +++ b/clients/rospy/src/rospy/core.py @@ -176,6 +176,10 @@ def __call__(self, caller_id, logging_func, period, msg): (now - last_logging_time) > rospy.Duration(period)): logging_func(msg) self.last_logging_time_table[caller_id] = now + elif last_logging_time > now: + logging_func(msg) + self.last_logging_time_table = {} + self.last_logging_time_table[caller_id] = now _logging_throttle = LoggingThrottle()