1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35 """
36 Convience methods for manipulating XML-RPC APIs
37 """
38
39 try:
40 from xmlrpc.client import ServerProxy
41 except ImportError:
42 from xmlrpclib import ServerProxy
43
44 import rosgraph
45 import rosgraph.network
46
47 _ID = '/roslaunch_netapi'
49 """
50 @return: list of roslaunch XML-RPC URIs for roscore that's in
51 the current environment, or None if roscore cannot be contacted.
52 @rtype: [str]
53 """
54 try:
55 m = rosgraph.Master(_ID)
56 vals = m.getParam('/roslaunch/uris')
57 return vals.values()
58 except rosgraph.MasterException:
59 return None
60
62 - def __init__(self, name, respawn_count, is_alive, roslaunch_uri):
63 self.is_alive = is_alive
64 self.respawn_count = respawn_count
65 self.name = name
66
67 self.roslaunch_uri = roslaunch_uri
68 self.machine, _ = rosgraph.network.parse_http_host_and_port(roslaunch_uri)
69
71 """
72 @param roslaunch_uris: (optional) list of XML-RPCS. If none
73 are provided, will look up URIs dynamically
74 @type roslaunch_uris: [str]
75 @return: list of roslaunch processes
76 @rtype: [L{NetProcess}]
77 """
78 if not roslaunch_uris:
79 roslaunch_uris = get_roslaunch_uris()
80 if not roslaunch_uris:
81 return []
82
83 procs = []
84 for uri in roslaunch_uris:
85 try:
86 r = ServerProxy(uri)
87 code, msg, val = r.list_processes()
88 if code == 1:
89 active, dead = val
90 procs.extend([NetProcess(a[0], a[1], True, uri) for a in active])
91 procs.extend([NetProcess(d[0], d[1], False, uri) for d in dead])
92 except:
93
94
95
96 pass
97 return procs
98