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 Handles service calls for getting lists of nodes and loggers
00043 Also handles sending requests to change logger levels
00044 """
00045 def __init__(self):
00046 super(LoggerLevelServiceCaller, self).__init__()
00047
00048 def get_levels(self):
00049 return [self.tr('Debug'), self.tr('Info'), self.tr('Warn'), self.tr('Error'), self.tr('Fatal')]
00050
00051 def get_loggers(self, node):
00052 if self._refresh_loggers(node):
00053 return self._current_loggers
00054 else:
00055 return []
00056
00057 def get_node_names(self):
00058 """
00059 Gets a list of available services via a ros service call.
00060 :returns: a list of all nodes that provide the set_logger_level service, ''list(str)''
00061 """
00062 set_logger_level_nodes = []
00063 nodes = rosnode.get_node_names()
00064 for name in sorted(nodes):
00065 for service in rosservice.get_service_list(name):
00066 if service == name + '/set_logger_level':
00067 set_logger_level_nodes.append(name)
00068 return set_logger_level_nodes
00069
00070 def _refresh_loggers(self, node):
00071 """
00072 Stores a list of loggers available for passed in node
00073 :param node: name of the node to query, ''str''
00074 """
00075 self._current_loggers = []
00076 self._current_levels = {}
00077 servicename = node + '/get_loggers'
00078 try:
00079 service = rosservice.get_service_class_by_name(servicename)
00080 except rosservice.ROSServiceIOException as e:
00081 qWarning('During get_service_class_by_name "%s":\n%s' % (servicename, e))
00082 return False
00083 request = service._request_class()
00084 proxy = rospy.ServiceProxy(str(servicename), service)
00085 try:
00086 response = proxy(request)
00087 except rospy.ServiceException as e:
00088 qWarning('SetupDialog.get_loggers(): request:\n%s' % (type(request)))
00089 qWarning('SetupDialog.get_loggers() "%s":\n%s' % (servicename, e))
00090 return False
00091
00092 if response._slot_types[0] == 'roscpp/Logger[]':
00093 for logger in getattr(response, response.__slots__[0]):
00094 self._current_loggers.append(getattr(logger, 'name'))
00095 self._current_levels[getattr(logger, 'name')] = getattr(logger, 'level')
00096 else:
00097 qWarning(repr(response))
00098 return False
00099 return True
00100
00101 def send_logger_change_message(self, node, logger, level):
00102 """
00103 Sends a logger level change request to 'node'.
00104 :param node: name of the node to chaange, ''str''
00105 :param logger: name of the logger to change, ''str''
00106 :param level: name of the level to change, ''str''
00107 :returns: True if the response is valid, ''bool''
00108 :returns: False if the request raises an exception or would not change the cached state, ''bool''
00109 """
00110 servicename = node + '/set_logger_level'
00111 if self._current_levels[logger].lower() == level.lower():
00112 return False
00113
00114 service = rosservice.get_service_class_by_name(servicename)
00115 request = service._request_class()
00116 setattr(request, 'logger', logger)
00117 setattr(request, 'level', level)
00118 proxy = rospy.ServiceProxy(str(servicename), service)
00119 try:
00120 proxy(request)
00121 self._current_levels[logger] = level.upper()
00122 except rospy.ServiceException as e:
00123 qWarning('SetupDialog.level_changed(): request:\n%r' % (request))
00124 qWarning('SetupDialog.level_changed() "%s":\n%s' % (servicename, e))
00125 return False
00126 return True