37 from python_qt_binding.QtCore
import QObject, qWarning
43 Handles service calls for getting lists of nodes and loggers 44 Also handles sending requests to change logger levels 48 super(LoggerLevelServiceCaller, self).
__init__()
51 return [self.tr(
'Debug'), self.tr(
'Info'), self.tr(
'Warn'), self.tr(
'Error'), self.tr(
'Fatal')]
61 Gets a list of available services via a ros service call. 62 :returns: a list of all nodes that provide the set_logger_level service, ''list(str)'' 64 set_logger_level_nodes = []
65 nodes = rosnode.get_node_names()
66 for name
in sorted(nodes):
67 for service
in rosservice.get_service_list(name):
68 if service == name +
'/set_logger_level':
69 set_logger_level_nodes.append(name)
70 return set_logger_level_nodes
74 Stores a list of loggers available for passed in node 75 :param node: name of the node to query, ''str'' 79 servicename = node +
'/get_loggers' 81 service = rosservice.get_service_class_by_name(servicename)
82 except rosservice.ROSServiceIOException
as e:
83 qWarning(
'During get_service_class_by_name "%s":\n%s' % (servicename, e))
85 request = service._request_class()
86 proxy = rospy.ServiceProxy(str(servicename), service)
88 response = proxy(request)
89 except rospy.ServiceException
as e:
90 qWarning(
'SetupDialog.get_loggers(): request:\n%s' % (type(request)))
91 qWarning(
'SetupDialog.get_loggers() "%s":\n%s' % (servicename, e))
94 if response._slot_types[0] ==
'roscpp/Logger[]':
95 for logger
in getattr(response, response.__slots__[0]):
96 self._current_loggers.append(getattr(logger,
'name'))
97 self.
_current_levels[getattr(logger,
'name')] = getattr(logger,
'level')
99 qWarning(repr(response))
105 Sends a logger level change request to 'node'. 106 :param node: name of the node to chaange, ''str'' 107 :param logger: name of the logger to change, ''str'' 108 :param level: name of the level to change, ''str'' 109 :returns: True if the response is valid, ''bool'' 110 :returns: False if the request raises an exception or would not change the cached state, ''bool'' 112 servicename = node +
'/set_logger_level' 116 service = rosservice.get_service_class_by_name(servicename)
117 request = service._request_class()
118 setattr(request,
'logger', logger)
119 setattr(request,
'level', level)
120 proxy = rospy.ServiceProxy(str(servicename), service)
124 except rospy.ServiceException
as e:
125 qWarning(
'SetupDialog.level_changed(): request:\n%r' % (request))
126 qWarning(
'SetupDialog.level_changed() "%s":\n%s' % (servicename, e))
def get_loggers(self, node)
def send_logger_change_message(self, node, logger, level)
def _refresh_loggers(self, node)