log_utils.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 import cPickle as pickle
5 import inspect
6 
7 import rosgraph
8 import rospy
9 
10 from jsk_topic_tools.name_utils import unresolve_name
11 
12 
14  try:
15  return '[{node}] [{cls}::{method}] {msg}'.format(
16  node=rospy.get_name(),
17  cls=inspect.stack()[2][0].f_locals['self'].__class__.__name__,
18  method=inspect.stack()[2][0].f_code.co_name,
19  msg=msg)
20  except KeyError:
21  return '[{node}] [{func}] {msg}'.format(
22  node=rospy.get_name(),
23  func=inspect.stack()[2][0].f_code.co_name,
24  msg=msg)
25 
26 
27 def jsk_logdebug(msg):
28  rospy.logdebug(_log_msg_with_called_location(msg))
29 
30 
31 def jsk_loginfo(msg):
32  rospy.loginfo(_log_msg_with_called_location(msg))
33 
34 
35 def jsk_logwarn(msg):
36  rospy.logwarn(_log_msg_with_called_location(msg))
37 
38 
39 def jsk_logerr(msg):
40  rospy.logerr(_log_msg_with_called_location(msg))
41 
42 
43 def jsk_logfatal(msg):
44  rospy.logfatal(_log_msg_with_called_location(msg))
45 
46 
47 class LoggingThrottle(object):
48 
49  last_logging_time_table = {}
50 
51  def __call__(self, id, logging_func, period, msg):
52  """Do logging specified message periodically.
53 
54  - id (str): Id to identify the caller
55  - logging_func (function): Function to do logging.
56  - period (float): Period to do logging in second unit.
57  - msg (object): Message to do logging.
58  """
59  now = rospy.Time.now()
60 
61  last_logging_time = self.last_logging_time_table.get(id)
62 
63  if (last_logging_time is None or
64  (now - last_logging_time) > rospy.Duration(period)):
65  logging_func(msg)
66  self.last_logging_time_table[id] = now
67 
68 
69 _logging_throttle = LoggingThrottle()
70 
71 
72 def logdebug_throttle(period, msg):
73  id = pickle.dumps(inspect.stack()[1][1:])
74  _logging_throttle(id, rospy.logdebug, period, msg)
75 
76 
77 def loginfo_throttle(period, msg):
78  id = pickle.dumps(inspect.stack()[1][1:])
79  _logging_throttle(id, rospy.loginfo, period, msg)
80 
81 
82 def logwarn_throttle(period, msg):
83  id = pickle.dumps(inspect.stack()[1][1:])
84  _logging_throttle(id, rospy.logwarn, period, msg)
85 
86 
87 def logerr_throttle(period, msg):
88  id = pickle.dumps(inspect.stack()[1][1:])
89  _logging_throttle(id, rospy.logerr, period, msg)
90 
91 
92 def logfatal_throttle(period, msg):
93  id = pickle.dumps(inspect.stack()[1][1:])
94  _logging_throttle(id, rospy.logfatal, period, msg)
95 
96 
97 def warn_no_remap(*names):
98  node_name = rospy.get_name()
99  resolved_names = [rosgraph.names.resolve_name(n, node_name) for n in names]
100  mappings = rospy.names.get_resolved_mappings()
101  for r_name in resolved_names:
102  if r_name in mappings:
103  continue
104  name = unresolve_name(node_name, r_name)
105  rospy.logwarn("[{node_name}] '{name}' has not been remapped."
106  .format(node_name=node_name, name=name))
def _log_msg_with_called_location(msg)
Definition: log_utils.py:13
def logerr_throttle(period, msg)
Definition: log_utils.py:87
def __call__(self, id, logging_func, period, msg)
Definition: log_utils.py:51
def logfatal_throttle(period, msg)
Definition: log_utils.py:92
def logdebug_throttle(period, msg)
Definition: log_utils.py:72
def loginfo_throttle(period, msg)
Definition: log_utils.py:77
def warn_no_remap(names)
Definition: log_utils.py:97
def logwarn_throttle(period, msg)
Definition: log_utils.py:82
def unresolve_name(node_name, name)
Definition: name_utils.py:5


jsk_topic_tools
Author(s): Kei Okada , Yusuke Furuta
autogenerated on Tue Feb 6 2018 03:45:19