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 roslib; roslib.load_manifest('tf2_tools')
00032 import rospy
00033 import tf2
00034 import yaml
00035 import subprocess
00036 from tf2_msgs.srv import FrameGraph
00037 import tf2_ros
00038 
00039 def main():
00040     rospy.init_node('view_frames')
00041     
00042     
00043     rospy.loginfo('Listening to tf data during 5 seconds...')
00044     rospy.sleep(0.00001)
00045     buffer = tf2_ros.Buffer()
00046     listener = tf2_ros.TransformListener(buffer)
00047     rospy.sleep(5.0)
00048 
00049     rospy.loginfo('Generating graph in frames.pdf file...')
00050     rospy.wait_for_service('~tf2_frames')
00051     srv = rospy.ServiceProxy('~tf2_frames', FrameGraph)
00052     data = yaml.load(srv().frame_yaml)
00053     with open('frames.gv', 'w') as f:
00054         f.write(generate_dot(data))
00055     subprocess.Popen('dot -Tpdf frames.gv -o frames.pdf'.split(' ')).communicate()
00056 
00057 def generate_dot(data):
00058     if len(data) == 0:
00059         return 'digraph G { "No tf data received" }'
00060 
00061     dot = 'digraph G {\n'
00062     for el in data: 
00063         map = data[el]
00064         dot += '"'+map['parent']+'" -> "'+el+'"'
00065         dot += '[label=" '
00066         dot += 'Broadcaster: '+map['broadcaster']+'\\n'
00067         dot += 'Average rate: '+str(map['rate'])+'\\n'
00068         dot += 'Buffer length: '+str(map['buffer_length'])+'\\n' 
00069         dot += 'Most recent transform: '+str(map['most_recent_transform'])+'\\n'
00070         dot += 'Oldest transform: '+str(map['oldest_transform'])+'\\n'
00071         dot += '"];\n'
00072         if not map['parent'] in data:
00073             root = map['parent']
00074     dot += 'edge [style=invis];\n'
00075     dot += ' subgraph cluster_legend { style=bold; color=black; label ="view_frames Result";\n'
00076     dot += '"Recorded at time: '+str(rospy.Time.now().to_sec())+'"[ shape=plaintext ] ;\n'
00077     dot += '}->"'+root+'";\n}'
00078     return dot
00079 
00080 
00081 if __name__ == '__main__':
00082     main()