dotcode_tf.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2008, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 
33 from __future__ import with_statement, print_function
34 
35 import time
36 import rospy
37 import yaml
38 
39 
41 
42  def __init__(self, initial_listen_duration=1):
43  """
44  :param initial_listen_duration: how many secs to listen to tf initially.
45  """
46  self.last_drawargs = None
47  self.dotcode = None
48  self.firstcall = True
49  self.listen_duration = initial_listen_duration
50  self.rank = None
51  self.rankdir = None
52  self.ranksep = None
53  self.graph = None
54  self.dotcode_factory = None
55 
56  def generate_dotcode(self,
57  dotcode_factory,
58  tf2_frame_srv,
59  timer=rospy.Time,
60  yaml_parser=yaml,
61  rank='same', # None, same, min, max, source, sink
62  ranksep=0.2, # vertical distance between layers
63  rankdir='TB', # direction of layout (TB top > bottom, LR left > right)
64  force_refresh=False):
65  """
66  :param force_refresh: if False, may return same dotcode as last time
67  """
68  if self.firstcall is True:
69  self.firstcall = False
70  force_refresh = True
71 
72  drawing_args = {
73  'dotcode_factory': dotcode_factory,
74  "rank": rank,
75  "rankdir": rankdir,
76  "ranksep": ranksep}
77 
78  selection_changed = False
79  if self.last_drawargs != drawing_args:
80  selection_changed = True
81  self.last_drawargs = drawing_args
82 
83  self.dotcode_factory = dotcode_factory
84  self.rank = rank
85  self.rankdir = rankdir
86  self.ranksep = ranksep
87 
88  # generate new dotcode
89  if force_refresh or self.dotcode is None or selection_changed:
90  if self.listen_duration > 0:
91  time.sleep(self.listen_duration)
92  # no need to listen more once we've listened for 1 sec?
93  self.listen_duration = 0
94 
95  yaml_data = tf2_frame_srv().frame_yaml
96  data = yaml_parser.load(yaml_data)
97  self.graph = self.generate(data, timer.now().to_sec())
98  self.dotcode = self.dotcode_factory.create_dot(self.graph)
99 
100  return self.dotcode
101 
102  def generate(self, data, timestamp):
103  graph = self.dotcode_factory.get_graph(rank=self.rank,
104  rankdir=self.rankdir,
105  ranksep=self.ranksep)
106 
107  if data is None or len(data) == 0:
108  self.dotcode_factory.add_node_to_graph(graph, "No tf data received")
109  return graph
110 
111  for frame_dict in data:
112  tf_frame_values = data[frame_dict]
113  if not tf_frame_values['parent'] in data:
114  root = tf_frame_values['parent']
115  self.dotcode_factory.add_node_to_graph(graph,
116  str(tf_frame_values['parent']),
117  shape='ellipse')
118  self.dotcode_factory.add_node_to_graph(
119  graph, frame_dict, shape='ellipse')
120 
121  edge_label = '"Broadcaster: %s\\n' % str(tf_frame_values['broadcaster'])
122  edge_label += 'Average rate: %s\\n' % str(tf_frame_values['rate'])
123  edge_label += 'Buffer length: %s\\n' % str(tf_frame_values['buffer_length'])
124  edge_label += 'Most recent transform: %s\\n' % str(tf_frame_values['most_recent_transform'])
125  edge_label += 'Oldest transform: %s"' % str(tf_frame_values['oldest_transform'])
126  self.dotcode_factory.add_edge_to_graph(graph,
127  str(tf_frame_values['parent']),
128  frame_dict,
129  label=edge_label)
130 
131  # create legend before root node
132  legend_label = '"Recorded at time: %s"' % str(timestamp)
133  self.dotcode_factory.add_node_to_graph(graph, legend_label)
134  self.dotcode_factory.add_edge_to_graph(graph,
135  legend_label,
136  root,
137  style='invis')
138 
139  # dot += ' subgraph cluster_legend { style=bold; color=black; label ="view_frames Result";\n'
140  # dot += '"Recorded at time: '+str(rospy.Time.now().to_sec())+'"[ shape=plaintext ] ;\n'
141  # dot += '}->"'+root+'"[style=invis];\n}'
142  return graph
def generate_dotcode(self, dotcode_factory, tf2_frame_srv, timer=rospy.Time, yaml_parser=yaml, rank='same', ranksep=0.2, rankdir='TB', force_refresh=False)
Definition: dotcode_tf.py:64
def __init__(self, initial_listen_duration=1)
Definition: dotcode_tf.py:42


rqt_tf_tree
Author(s): Thibault Kruse
autogenerated on Mon Feb 4 2019 03:56:43