12 import rocon_console.console
as console
13 from gateway_msgs.msg
import ConnectionType
37 if __name__ ==
'__main__':
38 rospy.init_node(
'bench_master_api')
39 master = rosgraph.Master(rospy.get_name())
40 connection_cache = rocon_gateway.ConnectionCache(master.getSystemState)
42 names = [
'start_time',
'get_system_state',
'extract_action_servers',
'extract_action_clients',
'get_pubs',
'get_subs',
'get_services',
'get_action_servers',
'get_action_clients']
45 while not rospy.is_shutdown():
48 times[
'start_time'] = rospy.get_time()
49 publishers, subscribers, services = connection_cache._get_system_state()
50 times[
'get_system_state'] = rospy.get_time()
51 action_servers, publishers, subscribers = connection_cache._get_action_servers(publishers, subscribers)
52 times[
'extract_action_servers'] = rospy.get_time()
53 action_clients, publishers, subscribers = connection_cache._get_action_clients(publishers, subscribers)
54 times[
'extract_action_clients'] = rospy.get_time()
55 connections[ConnectionType.PUBLISHER] = connection_cache._get_connections_from_pub_sub_list(publishers, ConnectionType.PUBLISHER)
56 times[
'get_pubs'] = rospy.get_time()
57 connections[ConnectionType.SUBSCRIBER] = connection_cache._get_connections_from_pub_sub_list(subscribers, ConnectionType.SUBSCRIBER)
58 times[
'get_subs'] = rospy.get_time()
59 connections[ConnectionType.SERVICE] = connection_cache._get_connections_from_service_list(services, ConnectionType.SERVICE)
60 times[
'get_services'] = rospy.get_time()
61 connections[ConnectionType.ACTION_SERVER] = connection_cache._get_connections_from_action_list(action_servers, ConnectionType.ACTION_SERVER)
62 times[
'get_action_servers'] = rospy.get_time()
63 connections[ConnectionType.ACTION_CLIENT] = connection_cache._get_connections_from_action_list(action_clients, ConnectionType.ACTION_CLIENT)
64 times[
'get_action_clients'] = rospy.get_time()
65 print(console.bold +
"Benchmarks" + console.reset)
66 for i
in range(1, len(names)):
67 print(console.cyan +
" %s: " % names[i] + console.yellow +
"%s" % (times[names[i]] - times[names[i-1]]) + console.reset)
68 print(console.green +
" total_time: " + console.magenta +
"%s" % (times[names[-1]] - times[names[0]]) + console.reset)
69 except Exception
as e:
70 print(console.red +
"Lost contact with the master [%s][%s]" % (str(e), type(e)) + console.reset)