Package rocon_conductor_graph :: Module conductor_graph_info
[frames] | no frames]

Source Code for Module rocon_conductor_graph.conductor_graph_info

  1  #!/usr/bin/env python 
  2  # 
  3   
  4   
  5  import rospy 
  6  import rosgraph 
  7  from rosgraph.impl.graph import Edge, EdgeList 
  8  from concert_msgs.msg import ConcertClients 
  9  from rocon_app_manager_msgs.srv import GetPlatformInfo, Status, Invite, StartApp, StopApp 
 10  from rocon_app_manager_msgs.msg import PlatformInfo 
 11   
 12  import random 
 13  from std_msgs.msg import String 
 14  ############################################################################## 
 15  # Graph 
 16  ############################################################################## 
 17   
18 -class ConductorGraphInfo(object):
19
20 - def __init__(self):
21 ''' 22 Creates the polling topics necessary for updating statistics 23 about the running gateway-hub network. 24 ''' 25 self._last_update = 0 26 self._gateway_namespace = None 27 self._concert_conductor_name = "concert_conductor" 28 self.gateway_nodes = [] # Gateway nodes 29 self.gateway_edges = [] # Gateway-Gateway edges 30 31 # Rubbish to clear out once rocon_gateway_graph is integrated 32 self.bad_nodes = [] 33 34 rospy.Subscriber("/concert/list_concert_clients", ConcertClients, self.update_client_list) 35 self._client_info_list = {}
36 37 38
39 - def update_client_list(self, data):
40 41 print "update_client_list" 42 43 #update dotgraph info 44 self.gateway_nodes = [] 45 self.gateway_nodes.append(self._concert_conductor_name) 46 self.gateway_edges = EdgeList() 47 48 for k in data.clients: 49 self.gateway_nodes.append(k.name) 50 if k.client_status == 'connected': 51 self.gateway_edges.add(Edge(self._concert_conductor_name,k.name,k.client_status)) 52 53 #update app widget info 54 for k in data.clients: 55 #temp function for assigning connection strength 56 connection_strength = self.set_random_connection_strength() 57 58 #uuid 59 service = k.gateway_name+'/'+'platform_info' 60 service_handle = rospy.ServiceProxy(service, GetPlatformInfo) 61 call_result = service_handle() 62 if k.gateway_name.count(call_result.platform_info.name)>0: 63 uuid = k.gateway_name.replace(call_result.platform_info.name,'') 64 else: 65 uuid ="None" 66 67 #html 68 app_context = "<html>" 69 app_context += "<p>-------------------------------------------</p>" 70 app_context += "<p><b>name: </b>" +k.name+"</p>" 71 app_context += "<p><b>gateway_name: </b>" +k.gateway_name+"</p>" 72 app_context += "<p><b>platform: </b>" +k.platform+"</p>" 73 app_context += "<p><b>system: </b>" +k.system+"</p>" 74 app_context += "<p><b>robot: </b>" +k.robot+"</p>" 75 app_context += "<p><b>client_status: </b>" +k.client_status+"</p>" 76 app_context += "<p><b>connection_strengh: </b>" +connection_strength+"</p>" 77 app_context +="</html>" 78 app_name = k.name 79 80 if self._client_info_list.has_key(app_name): 81 self._client_info_list[app_name]["isNew"] = False 82 else: 83 self._client_info_list[app_name]={} 84 self._client_info_list[app_name]["isNew"] = True 85 86 self._client_info_list[app_name]["isCheck"]=True 87 self._client_info_list[app_name]["app_name"]=app_name 88 self._client_info_list[app_name]["gateway_name"]=k.gateway_name 89 self._client_info_list[app_name]["app_context"]=app_context 90 self._client_info_list[app_name]["connection_strength"]=connection_strength 91 self._client_info_list[app_name]["uuid"]= uuid 92 93 for k in self._client_info_list.keys(): 94 if self._client_info_list[k]["isCheck"] == True: 95 self._client_info_list[k]["isCheck"] = False 96 else: 97 del self._client_info_list[k]
98 99
101 connection_strength = random.randrange(1,6) 102 if connection_strength == 1: 103 return 'very_strong' 104 elif connection_strength == 2: 105 return 'strong' 106 elif connection_strength == 3: 107 return 'normal' 108 elif connection_strength == 4: 109 return 'weak' 110 elif connection_strength == 5: 111 return 'very_weak'
112