-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathdata.py
477 lines (397 loc) · 17.1 KB
/
data.py
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
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
#!/usr/bin/env python
import argparse
import rospy
import rostopic
from std_msgs.msg import String
from collections import defaultdict
import json
import requests
import rospy
import rostopic
from std_msgs.msg import String
import rosnode
import os
import sys
import rosservice
import xmlrpclib
import subprocess
import re
import roslib; roslib.load_manifest('nodelet')
import rospy
from datetime import datetime
from nodelet.srv import *
from std_msgs.msg import String
import yaml
currentService = ""
currentReported = []
serviceExpeptions = []
noServiceIntermediator = []
oldnoServiceIntermediator = []
URL = "http://127.0.0.1:8000/data"
def accumulate_action_topics(self, nodes_in, edges_in, node_connections):
'''takes topic nodes, edges and node connections.
Returns topic nodes where action topics have been removed,
edges where the edges to action topics have been removed, and
a map with the connection to each virtual action topic node'''
removal_nodes = []
action_nodes = {}
# do not manipulate incoming structures
nodes = copy.copy(nodes_in)
edges = copy.copy(edges_in)
for n in nodes:
if str(n).endswith('/feedback'):
prefix = str(n)[:-len('/feedback')].strip()
action_topic_nodes = []
action_topic_edges_out = set()
action_topic_edges_in = set()
for suffix in ['/status', '/result', '/goal', '/cancel', '/feedback']:
for n2 in nodes:
if str(n2).strip() == prefix + suffix:
action_topic_nodes.append(n2)
if n2 in node_connections:
action_topic_edges_out.update(node_connections[n2].outgoing)
action_topic_edges_in.update(node_connections[n2].incoming)
if len(action_topic_nodes) == 5:
# found action
removal_nodes.extend(action_topic_nodes)
for e in action_topic_edges_out:
if e in edges:
edges.remove(e)
for e in action_topic_edges_in:
if e in edges:
edges.remove(e)
action_nodes[prefix] = {'topics': action_topic_nodes,
'outgoing': action_topic_edges_out,
'incoming': action_topic_edges_in}
for n in removal_nodes:
nodes.remove(n)
return nodes, edges, action_nodes
def response(req):
sentinel = False
x = req._connection_header
currentService = str(x['service']) + "_prime"
client = str(x['callerid'])
srv = subprocess.Popen("rosservice type " +currentService + " | rossrv show", shell=True, stdout=subprocess.PIPE).stdout.read()
serviceArguments = []
serviceArgumentsValues = []
serviceReturns = []
serviceReturnsValues = []
for line in srv.split('\n'):
if line == '---':
sentinel = True
continue
if sentinel == True and line != '':
if '/' in line.split(' ')[0]:
serviceExpeptions.append(currentService)
continue
serviceReturns.append(line.split(' ')[-1])
else:
if line != '':
serviceArguments.append(line.split(' ')[-1])
hasNoArguments = True
if str(rosservice.get_service_args(currentService)) != "":
hasNoArguments = False
for x in serviceArguments:
exec ('serviceArgumentsValues.append(req.'+ str(x) +')')
Response = rospy.ServiceProxy(currentService, rosservice.get_service_class_by_name(currentService))
toChange = ['.', ':', ' ']
time = str(datetime.now())
time = time.translate(None, '-'.join(toChange))
if hasNoArguments == False:
exec generateReturn(serviceArgumentsValues)
for x in serviceReturns:
if re.match("^[A-Za-z0-9_-]*$", x) and x != '':
if currentService in serviceExpeptions:
serviceReturnsValues.append(currentService)
break
exec('serviceReturnsValues.append(toReturn.'+ str(x) +')')
else:
toReturn = Response()
for x in serviceReturns:
if re.match("^[A-Za-z0-9_-]*$", x) and x != '':
if currentService in serviceExpeptions:
serviceReturnsValues.append(currentService)
break
exec('serviceReturnsValues.append(toReturn.'+ str(x) +')')
report = str(generateReportSrviceCalls(currentService,serviceArguments,serviceArgumentsValues,serviceReturns,serviceReturnsValues,client))
currentReported.append(report)
return toReturn
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
def generateReturn(serviceArgumentsValues):
count = 0
toExecute = 'toReturn = Response('
for x in serviceArgumentsValues:
count = count +1
if count == len(serviceArgumentsValues):
toExecute += str(x)+')'
else:
toExecute+= str(x)+','
return toExecute
def newServiceHandler(service):
primeState = False
non_prime = "OPERATOR___"
if service.split('_')[-1] == 'prime':
primeState = True
non_prime = non_prime + service.split('_prime')[0]
s = rospy.Service(non_prime,rosservice.get_service_class_by_name(str(service)),response)
else:
noServiceIntermediator.append(service)
return 'Passed'
def get_current_state(ignore_nodes, ignore_services, ignore_topics):
caller_ide = "/acme_data_collector"
m = xmlrpclib.ServerProxy(os.environ['ROS_MASTER_URI'])
code, msg, val = m.getSystemState(caller_ide)
if code == 1:
pubs, subs, srvs = val
else:
print "Call to ROS Master failed", code, msg
sys.exit()
srvs = [srv for srv in srvs if not srv[0] in ignore_services and not set(srv[1]).issubset(ignore_nodes)]
pubs = [pub for pub in pubs if not pub[0] in ignore_topics and not set(pub[1]).issubset(ignore_nodes)]
subs = [sub for sub in subs if not sub[0] in ignore_topics and not set(pub[1]).issubset(ignore_nodes)]
return pubs, subs, srvs
def get_current_services(ignore_services, ignore_nodes):
caller_ide = '/handler'
m = xmlrpclib.ServerProxy(os.environ['ROS_MASTER_URI'])
code, msg, val = m.getSystemState(caller_ide)
if(code ==1):
pubs, subs, srvs = val
else:
print "call failed", code, msg
srvs = [srv for srv in srvs if not srv[0] in ignore_services and not set(srv[1]).issubset(ignore_nodes)]
return srvs
def parse_info_sub(info, ignore_topics, ignore_nodes):
reached_sub = False
subscribers = []
for l in info.splitlines():
if reached_sub and not l:
break
elif reached_sub:
parts = l.split(' ')
if len(parts) < 3:
rospy.loginfo("Something is wrong here!")
continue
if parts[2] not in ignore_nodes:
subscribers.append(parts[2])
elif l.startswith('Subscribers:'):
reached_sub = True
return subscribers
def parse_info_pub(info, ignore_topics, ignore_nodes):
reached_pub = False
publishers = []
for l in info.splitlines():
if reached_pub and (not l or l.startswith('Subscribers:')):
break
elif reached_pub:
parts = l.split(' ')
if len(parts) < 3:
rospy.loginfo("Something is wrong here!")
continue
if parts[2] not in ignore_nodes:
publishers.append(parts[2])
elif l.startswith('Publishers:'):
reached_pub = True
return publishers
def sendPub(new_publish):
p = {}
for topic in new_publish.keys():
p[topic] = list(new_publish[topic])
y = defaultdict(list)
for key, values in p.iteritems():
for value in values:
y[value].append(key)
for key in y.keys():
new_key = key.replace("/", "__")
y[new_key] = [item.replace("/", "__") for item in y.pop(key)]
return y
def sendSub(new_publish):
p = {}
for topic in new_publish.keys():
p[topic] = list(new_publish[topic])
y = defaultdict(list)
for key, values in p.iteritems():
for value in values:
y[value].append(key)
for key in y.keys():
new_key = key.replace("/", "__")
y[new_key] = [item.replace("/", "__") for item in y.pop(key)]
return y
def send_topics(topics):
topics_dict = {}
for topic, typ in topics:
topics_dict[topic.replace("/", "__")] = typ
return topics_dict
def send_nodes(nodes):
x = {"nodes":[]}
for item in nodes:
if "nodelet_manager" in item:
x[item] = rospy.ServiceProxy(item + "/list", NodeletList).call(NodeletListRequest()).nodelets
flattened = [val for sublist in x.values() for val in sublist] + x.keys()
for item in nodes:
if item not in flattened:
x["nodes"].append(item)
y = {}
for key in x.keys():
new_key = key.replace("/", "__")
y[new_key] = [item.replace("/", "__") for item in x[key]]
return y
def arch(filters):
try:
rospy.init_node('acme_data_collector')
filters.ignore_node.append('acme_data_collector') # Add this node to the set of things to ignore
currentServices = []
loggerCount = 0
last_topics = []
last_nodes = []
last_publish = {}
last_publish1 = {}
currentTopics = []
loggerCount = 0
global currentReported
global serviceExpeptions
global noServiceIntermediator
global oldnoServiceIntermediator
# append list to add / to every node
filters.ignore_node = map((lambda x : '/' + x), filters.ignore_node)
service_dict = {}
old_service_dict = {}
length = 0
updated = False
oldReported = list()
shortcircuit = False
rate = 1.0/float(filters.rate) #The Hz for the rate
r = rospy.Rate(rate)
while not rospy.is_shutdown() and not shortcircuit:
shortcircuit = filters.once
pubs, subs, srvs = get_current_state(filters.ignore_node, filters.ignore_service, filters.ignore_topic)
pubs = [pub[0] for pub in pubs]
subs = [sub[0] for sub in subs]
new_topics = [topic for topic in rospy.get_published_topics() if topic[0] in pubs or topic[0] in subs]
new_nodes = rosnode.get_node_names()
new_publish = {}
new_publish1 = {}
inc_topics = [item for item in new_topics if item not in last_topics and item not in filters.ignore_topic]
inc_nodes = [item for item in new_nodes if item not in last_nodes and item not in filters.ignore_node]
inc_service_dict = {}
inc_publish = {}
inc_publish1 = {}
inc_service_dict = {}
inc_reported = {}
for topic, typ in new_topics:
info = rostopic.get_info_text(topic)
subscribers = parse_info_sub(info, filters.ignore_topic, filters.ignore_node)
publishers = parse_info_pub(info, filters.ignore_topic, filters.ignore_node)
new_publish[topic] = set(subscribers)
new_publish1[topic] = set(publishers)
if (topic not in last_publish.keys()) or set(subscribers) != last_publish[topic]:
inc_publish[topic] = set(subscribers)
if (topic not in last_publish1.keys()) or set(publishers) != last_publish1[topic]:
inc_publish1[topic] = set(publishers)
try:
for newService, Provider in srvs:
if not newService in currentServices and not newService in filters.ignore_service:
currentServices.append(newService)
newServiceHandler(newService)
service_dict[newService] = [rosservice.get_service_type(newService), rosservice.get_service_args(newService)]
if (newService not in old_service_dict.keys()) or service_dict[newService] != old_service_dict[newService]:
inc_service_dict[newService] = [rosservice.get_service_type(newService), rosservice.get_service_args(newService)]
except Exception as e:
print e
pass
if old_service_dict != service_dict:
old_service_dict = dict(service_dict)
updated = True
inc_reported = [item for item in currentReported if item not in oldReported]
oldReported = list(currentReported)
if len(inc_reported) != 0:
updated = True
if noServiceIntermediator != oldnoServiceIntermediator:
oldnoServiceIntermediator = list(noServiceIntermediator)
print
print
print 'Services calls not being reported for these services: ' + str(noServiceIntermediator)
if inc_topics or inc_nodes or inc_publish or inc_publish1 != inc_service_dict or inc_reported:
y = {}
y["topics"] = send_topics(inc_topics)
y["nodes"] = send_nodes(inc_nodes)
y["pub"] = sendPub(inc_publish)
y["sub"] = sendSub(inc_publish1)
y["service"] = inc_service_dict
y["calls"] = inc_reported
last_nodes = list(new_nodes)
last_topics = list(new_topics)
last_publish = dict(new_publish)
last_publish1 = dict(new_publish1)
updated = False
if filters.file is not None:
output = open(filters.file, 'wb')
output.write(json.dumps(y, indent=4))
output.close()
else:
requests.get(URL, data=json.dumps(y))
r.sleep()
except Exception as e:
print e
pass
def preprocess_ignores(args):
if not hasattr(args, 'ignore_node') or args.ignore_node is None:
args.ignore_node=[]
if not hasattr(args, 'ignore_topic') or args.ignore_topic is None:
args.ignore_topic=[]
if not hasattr(args, 'ignore_service') or args.ignore_service is None:
args.ignore_service=[]
if not hasattr(args,'ignore_action') or args.ignore_action is None:
args.ignore_action=[]
def process_ignores(args):
with open(args.ignore, 'r') as stream:
ignore = yaml.load(stream)
if "nodes" in ignore:
args.ignore_node.extend(ignore["nodes"])
if "topics" in ignore:
args.ignore_topic.extend(ignore["topics"])
if "services" in ignore:
args.ignore_service.extend(ignore["services"])
if "actions" in ignore:
args.ignore_action.extend(ignore["actions"])
if __name__ == '__main__':
parser = argparse.ArgumentParser()
parser.add_argument('-u', '--url', type=str, default=URL, help="The URL to send the JSON data")
parser.add_argument('-f', '--file',type=str, help="Output to this file, instead of sending to URL")
parser.add_argument('-n', '--ignore-node', type=str, action='append', help="Ignore a node with this name")
parser.add_argument('-t', '--ignore-topic', type=str, action='append', help='Ignore a topic with this name')
parser.add_argument('-s', '--ignore-service', type=str, action='append', help='Ignore a service with this name')
parser.add_argument('-a', '--ignore-action', type=str, action='append', help='Ignore an action with this name')
parser.add_argument('-i', '--ignore', type=str, help='The YAML file containing sections of topic, service, node, and action to ignore')
parser.add_argument('-1', '--once', action='store_true', help='Only produce the information once')
parser.add_argument('-r', '--rate', default=10, type=int, help='The loop rate (seconds)')
args = parser.parse_args()
if args.url is not None:
URL = args.url
if args.file is not None:
args.file = os.path.expandvars(args.file)
preprocess_ignores(args)
if args.ignore is not None:
args.ignore = os.path.expandvars(args.ignore)
if not os.path.isfile(args.ignore):
print("The ignore file does not exist! " %args.ignore);
sys.exit(1)
process_ignores(args)
try:
arch(args)
except rospy.ROSInterruptException:
print e
pass