Go to the documentation of this file.00001
00002
00003
00004 import cPickle as pickle
00005 import inspect
00006
00007 import rosgraph
00008 import rospy
00009
00010 from jsk_topic_tools.name_utils import unresolve_name
00011
00012
00013 def _log_msg_with_called_location(msg):
00014 try:
00015 return '[{node}] [{cls}::{method}] {msg}'.format(
00016 node=rospy.get_name(),
00017 cls=inspect.stack()[2][0].f_locals['self'].__class__.__name__,
00018 method=inspect.stack()[2][0].f_code.co_name,
00019 msg=msg)
00020 except KeyError:
00021 return '[{node}] [{func}] {msg}'.format(
00022 node=rospy.get_name(),
00023 func=inspect.stack()[2][0].f_code.co_name,
00024 msg=msg)
00025
00026
00027 def jsk_logdebug(msg):
00028 rospy.logdebug(_log_msg_with_called_location(msg))
00029
00030
00031 def jsk_loginfo(msg):
00032 rospy.loginfo(_log_msg_with_called_location(msg))
00033
00034
00035 def jsk_logwarn(msg):
00036 rospy.logwarn(_log_msg_with_called_location(msg))
00037
00038
00039 def jsk_logerr(msg):
00040 rospy.logerr(_log_msg_with_called_location(msg))
00041
00042
00043 def jsk_logfatal(msg):
00044 rospy.logfatal(_log_msg_with_called_location(msg))
00045
00046
00047 class LoggingThrottle(object):
00048
00049 last_logging_time_table = {}
00050
00051 def __call__(self, id, logging_func, period, msg):
00052 """Do logging specified message periodically.
00053
00054 - id (str): Id to identify the caller
00055 - logging_func (function): Function to do logging.
00056 - period (float): Period to do logging in second unit.
00057 - msg (object): Message to do logging.
00058 """
00059 now = rospy.Time.now()
00060
00061 last_logging_time = self.last_logging_time_table.get(id)
00062
00063 if (last_logging_time is None or
00064 (now - last_logging_time) > rospy.Duration(period)):
00065 logging_func(msg)
00066 self.last_logging_time_table[id] = now
00067
00068
00069 _logging_throttle = LoggingThrottle()
00070
00071
00072 def logdebug_throttle(period, msg):
00073 id = pickle.dumps(inspect.stack()[1][1:])
00074 _logging_throttle(id, rospy.logdebug, period, msg)
00075
00076
00077 def loginfo_throttle(period, msg):
00078 id = pickle.dumps(inspect.stack()[1][1:])
00079 _logging_throttle(id, rospy.loginfo, period, msg)
00080
00081
00082 def logwarn_throttle(period, msg):
00083 id = pickle.dumps(inspect.stack()[1][1:])
00084 _logging_throttle(id, rospy.logwarn, period, msg)
00085
00086
00087 def logerr_throttle(period, msg):
00088 id = pickle.dumps(inspect.stack()[1][1:])
00089 _logging_throttle(id, rospy.logerr, period, msg)
00090
00091
00092 def logfatal_throttle(period, msg):
00093 id = pickle.dumps(inspect.stack()[1][1:])
00094 _logging_throttle(id, rospy.logfatal, period, msg)
00095
00096
00097 def warn_no_remap(*names):
00098 node_name = rospy.get_name()
00099 resolved_names = [rosgraph.names.resolve_name(n, node_name) for n in names]
00100 mappings = rospy.names.get_resolved_mappings()
00101 for r_name in resolved_names:
00102 if r_name in mappings:
00103 continue
00104 name = unresolve_name(node_name, r_name)
00105 rospy.logwarn("[{node_name}] '{name}' has not been remapped."
00106 .format(node_name=node_name, name=name))