def generate_type_info_msg(self): """ Basic connection details are provided by get system state from the master, which is a one shot call to give you information about every connection possible. it does not however provide type info information and the only way of retrieving that from the master is making one xmlrpc call to the master for every single connection. This gets expensive, so generating this information is usually delayed until we need it and done via this method. """ if self.type_info is None: if self.type == PUBLISHER or self.type == SUBSCRIBER: try: self.type_info = rostopic.get_topic_type( self.name)[0] # message type self.type_msg = self.type_info except rostopic.ROSTopicIOException as topic_exc: rospy.logwarn(topic_exc) elif self.type == SERVICE: try: self.type_info = rosservice.get_service_uri(self.name) self.type_msg = rosservice.get_service_type(self.name) except rosservice.ROSServiceIOException as service_exc: rospy.logwarn(service_exc) elif self.type == ACTION_SERVER or self.type == ACTION_CLIENT: try: goal_topic = self.name + '/goal' goal_topic_type = rostopic.get_topic_type(goal_topic) self.type_info = re.sub( 'ActionGoal$', '', goal_topic_type[0]) # Base type for action self.type_msg = self.type_info except rostopic.ROSTopicIOException as topic_exc: rospy.logwarn(topic_exc.msg) return self # chaining
def get_service_host(service): """ Returns the name of the machine that is hosting the given service, or empty string """ uri = get_service_uri(service) if uri == None: uri = "" else: uri = uri[9:] uri = uri[:uri.find(':')] return uri
def generateReportSrviceCalls(service,serviceArguments, serviceArgumentsValues,serviceReturns,serviceReturnsValues, client): x = rosservice.get_service_headers(service,rosservice.get_service_uri(service)) toReturn = {'srv':str(x['type']), 'client':client, 'server':str(rosservice.get_service_node(service)), 'service_name': service} reqSubReport = [] respSubReport = {} for x in range (0,len(serviceArguments)): reqSubReport.append(str(serviceArgumentsValues[x])) # for x in range (0, len(serviceReturns)): # if service in serviceExpeptions: # respSubReport['ExtendedReport'] = 'ExtendedReport' # break # respSubReport[str(serviceReturns[x])] = str(serviceReturnsValues[x]) toReturn['req'] = ','.join(reqSubReport) #toReturn['resp'] = respSubReport return toReturn