Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 import rosnode
00034 import rospy
00035 import rosservice
00036
00037 from python_qt_binding.QtCore import QObject, qWarning
00038
00039
00040 class LoggerLevelServiceCaller(QObject):
00041
00042 """
00043 Handles service calls for getting lists of nodes and loggers
00044 Also handles sending requests to change logger levels
00045 """
00046
00047 def __init__(self):
00048 super(LoggerLevelServiceCaller, self).__init__()
00049
00050 def get_levels(self):
00051 return [self.tr('Debug'), self.tr('Info'), self.tr('Warn'), self.tr('Error'), self.tr('Fatal')]
00052
00053 def get_loggers(self, node):
00054 if self._refresh_loggers(node):
00055 return self._current_loggers
00056 else:
00057 return []
00058
00059 def get_node_names(self):
00060 """
00061 Gets a list of available services via a ros service call.
00062 :returns: a list of all nodes that provide the set_logger_level service, ''list(str)''
00063 """
00064 set_logger_level_nodes = []
00065 nodes = rosnode.get_node_names()
00066 for name in sorted(nodes):
00067 for service in rosservice.get_service_list(name):
00068 if service == name + '/set_logger_level':
00069 set_logger_level_nodes.append(name)
00070 return set_logger_level_nodes
00071
00072 def _refresh_loggers(self, node):
00073 """
00074 Stores a list of loggers available for passed in node
00075 :param node: name of the node to query, ''str''
00076 """
00077 self._current_loggers = []
00078 self._current_levels = {}
00079 servicename = node + '/get_loggers'
00080 try:
00081 service = rosservice.get_service_class_by_name(servicename)
00082 except rosservice.ROSServiceIOException as e:
00083 qWarning('During get_service_class_by_name "%s":\n%s' % (servicename, e))
00084 return False
00085 request = service._request_class()
00086 proxy = rospy.ServiceProxy(str(servicename), service)
00087 try:
00088 response = proxy(request)
00089 except rospy.ServiceException as e:
00090 qWarning('SetupDialog.get_loggers(): request:\n%s' % (type(request)))
00091 qWarning('SetupDialog.get_loggers() "%s":\n%s' % (servicename, e))
00092 return False
00093
00094 if response._slot_types[0] == 'roscpp/Logger[]':
00095 for logger in getattr(response, response.__slots__[0]):
00096 self._current_loggers.append(getattr(logger, 'name'))
00097 self._current_levels[getattr(logger, 'name')] = getattr(logger, 'level')
00098 else:
00099 qWarning(repr(response))
00100 return False
00101 return True
00102
00103 def send_logger_change_message(self, node, logger, level):
00104 """
00105 Sends a logger level change request to 'node'.
00106 :param node: name of the node to chaange, ''str''
00107 :param logger: name of the logger to change, ''str''
00108 :param level: name of the level to change, ''str''
00109 :returns: True if the response is valid, ''bool''
00110 :returns: False if the request raises an exception or would not change the cached state, ''bool''
00111 """
00112 servicename = node + '/set_logger_level'
00113 if self._current_levels[logger].lower() == level.lower():
00114 return False
00115
00116 service = rosservice.get_service_class_by_name(servicename)
00117 request = service._request_class()
00118 setattr(request, 'logger', logger)
00119 setattr(request, 'level', level)
00120 proxy = rospy.ServiceProxy(str(servicename), service)
00121 try:
00122 proxy(request)
00123 self._current_levels[logger] = level.upper()
00124 except rospy.ServiceException as e:
00125 qWarning('SetupDialog.level_changed(): request:\n%r' % (request))
00126 qWarning('SetupDialog.level_changed() "%s":\n%s' % (servicename, e))
00127 return False
00128 return True