35 from tf2_msgs.srv
import FrameGraph
39 rospy.init_node(
'view_frames')
42 rospy.loginfo(
'Listening to tf data during 5 seconds...')
48 rospy.loginfo(
'Generating graph in frames.pdf file...')
49 rospy.wait_for_service(
'~tf2_frames')
50 srv = rospy.ServiceProxy(
'~tf2_frames', FrameGraph)
51 data = yaml.load(srv().frame_yaml)
52 with open(
'frames.gv',
'w')
as f:
54 subprocess.Popen(
'dot -Tpdf frames.gv -o frames.pdf'.split(
' ')).communicate()
58 return 'digraph G { "No tf data received" }' 63 dot +=
'"'+map[
'parent']+
'" -> "'+str(el)+
'"' 65 dot +=
'Broadcaster: '+map[
'broadcaster']+
'\\n' 66 dot +=
'Average rate: '+str(map[
'rate'])+
'\\n' 67 dot +=
'Buffer length: '+str(map[
'buffer_length'])+
'\\n' 68 dot +=
'Most recent transform: '+str(map[
'most_recent_transform'])+
'\\n' 69 dot +=
'Oldest transform: '+str(map[
'oldest_transform'])+
'\\n' 71 if not map[
'parent']
in data:
73 dot +=
'edge [style=invis];\n' 74 dot +=
' subgraph cluster_legend { style=bold; color=black; label ="view_frames Result";\n' 75 dot +=
'"Recorded at time: '+str(rospy.Time.now().to_sec())+
'"[ shape=plaintext ] ;\n' 76 dot +=
'}->"'+root+
'";\n}' 80 if __name__ ==
'__main__':