33 from __future__
import with_statement, print_function
44 :param initial_listen_duration: how many secs to listen to tf initially. 66 :param force_refresh: if False, may return same dotcode as last time 73 'dotcode_factory': dotcode_factory,
78 selection_changed =
False 80 selection_changed =
True 89 if force_refresh
or self.
dotcode is None or selection_changed:
95 yaml_data = tf2_frame_srv().frame_yaml
96 data = yaml_parser.load(yaml_data)
98 self.
dotcode = self.dotcode_factory.create_dot(self.
graph)
103 graph = self.dotcode_factory.get_graph(rank=self.
rank,
107 if data
is None or len(data) == 0:
108 self.dotcode_factory.add_node_to_graph(graph,
"No tf data received")
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']),
118 self.dotcode_factory.add_node_to_graph(
119 graph, frame_dict, shape=
'ellipse')
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']),
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,
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)
def generate(self, data, timestamp)
def __init__(self, initial_listen_duration=1)