Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031 import rospy
00032 import tf2_py as tf2
00033 import yaml
00034 import subprocess
00035 from tf2_msgs.srv import FrameGraph
00036 import tf2_ros
00037
00038 def main():
00039 rospy.init_node('view_frames')
00040
00041
00042 rospy.loginfo('Listening to tf data during 5 seconds...')
00043 rospy.sleep(0.00001)
00044 buffer = tf2_ros.Buffer()
00045 listener = tf2_ros.TransformListener(buffer)
00046 rospy.sleep(5.0)
00047
00048 rospy.loginfo('Generating graph in frames.pdf file...')
00049 rospy.wait_for_service('~tf2_frames')
00050 srv = rospy.ServiceProxy('~tf2_frames', FrameGraph)
00051 data = yaml.load(srv().frame_yaml)
00052 with open('frames.gv', 'w') as f:
00053 f.write(generate_dot(data))
00054 subprocess.Popen('dot -Tpdf frames.gv -o frames.pdf'.split(' ')).communicate()
00055
00056 def generate_dot(data):
00057 if len(data) == 0:
00058 return 'digraph G { "No tf data received" }'
00059
00060 dot = 'digraph G {\n'
00061 for el in data:
00062 map = data[el]
00063 dot += '"'+map['parent']+'" -> "'+str(el)+'"'
00064 dot += '[label=" '
00065 dot += 'Broadcaster: '+map['broadcaster']+'\\n'
00066 dot += 'Average rate: '+str(map['rate'])+'\\n'
00067 dot += 'Buffer length: '+str(map['buffer_length'])+'\\n'
00068 dot += 'Most recent transform: '+str(map['most_recent_transform'])+'\\n'
00069 dot += 'Oldest transform: '+str(map['oldest_transform'])+'\\n'
00070 dot += '"];\n'
00071 if not map['parent'] in data:
00072 root = map['parent']
00073 dot += 'edge [style=invis];\n'
00074 dot += ' subgraph cluster_legend { style=bold; color=black; label ="view_frames Result";\n'
00075 dot += '"Recorded at time: '+str(rospy.Time.now().to_sec())+'"[ shape=plaintext ] ;\n'
00076 dot += '}->"'+root+'";\n}'
00077 return dot
00078
00079
00080 if __name__ == '__main__':
00081 main()