E2E calculation per output message, plotting of E2E over time, E2E breakdown charts, E2E message flow charts
This commit is contained in:
parent
241a7c3bf2
commit
8eee45c79a
7 changed files with 1212 additions and 339 deletions
|
@ -1,58 +1,34 @@
|
|||
from bisect import bisect_left, bisect
|
||||
from dataclasses import dataclass
|
||||
from itertools import combinations
|
||||
from multiprocessing import Pool
|
||||
from typing import Optional, Set, List, Iterable, Dict, Tuple
|
||||
|
||||
import numpy as np
|
||||
from tqdm.notebook import tqdm
|
||||
from tqdm.contrib import concurrent
|
||||
|
||||
from matching.subscriptions import sanitize
|
||||
from tracing_interop.tr_types import TrContext, TrCallbackObject, TrCallbackSymbol, TrNode, TrPublisher, TrSubscription, \
|
||||
TrTimer, TrPublishInstance, TrSubscriptionObject, TrTopic, TrCallbackInstance
|
||||
TrTimer, TrPublishInstance, TrSubscriptionObject, TrTopic, TrCallbackInstance, Timestamp
|
||||
|
||||
|
||||
TOPIC_FILTERS = ["/parameter_events", "/tf_static", "/robot_description", "diagnostics"]
|
||||
|
||||
|
||||
def _map_cb_times(args):
|
||||
cb_id, inst_times, pub_timestamps = args
|
||||
pub_cb_overlaps = {i: set() for i in range(len(pub_timestamps))}
|
||||
|
||||
inst_times.sort(key=lambda tup: tup[0]) # tup[0] is start time
|
||||
|
||||
inst_iter = iter(inst_times)
|
||||
pub_iter = iter(enumerate(pub_timestamps))
|
||||
|
||||
inst_start, inst_end = next(inst_iter, (None, None))
|
||||
i, t = next(pub_iter, (None, None))
|
||||
while inst_start is not None and i is not None:
|
||||
if inst_start <= t <= inst_end:
|
||||
pub_cb_overlaps[i].add(cb_id)
|
||||
|
||||
if t <= inst_end:
|
||||
i, t = next(pub_iter, (None, None))
|
||||
else:
|
||||
inst_start, inst_end = next(inst_iter, (None, None))
|
||||
|
||||
return pub_cb_overlaps
|
||||
TOPIC_FILTERS = ["/parameter_events", "/tf_static", "/robot_description", "diagnostics", "/rosout"]
|
||||
|
||||
|
||||
def _get_cb_owner_node(cb: TrCallbackObject) -> TrNode | None:
|
||||
match cb.owner:
|
||||
case TrTimer(nodes=nodes):
|
||||
owner_nodes = nodes
|
||||
case TrTimer(node=node):
|
||||
owner_node = node
|
||||
case TrSubscriptionObject(subscription=sub):
|
||||
owner_nodes = [sub.node]
|
||||
owner_node = sub.node
|
||||
case _:
|
||||
owner_nodes = []
|
||||
owner_node = None
|
||||
|
||||
if len(owner_nodes) > 1:
|
||||
raise RuntimeError(f"CB has owners {', '.join(map(lambda n: n.path, owner_nodes))}")
|
||||
elif not owner_nodes:
|
||||
if not owner_node:
|
||||
print("[WARN] CB has no owners")
|
||||
return None
|
||||
|
||||
return owner_nodes[0]
|
||||
return owner_node
|
||||
|
||||
|
||||
def _hierarchize(lg_nodes: Iterable['LGHierarchyLevel']):
|
||||
|
@ -79,33 +55,25 @@ def _hierarchize(lg_nodes: Iterable['LGHierarchyLevel']):
|
|||
|
||||
|
||||
def inst_runtime_interval(cb_inst: TrCallbackInstance):
|
||||
inst_t_min = cb_inst.timestamp.timestamp()
|
||||
inst_t_max = inst_t_min + cb_inst.duration.total_seconds()
|
||||
return inst_t_min, inst_t_max
|
||||
start_time = cb_inst.timestamp
|
||||
end_time = start_time + cb_inst.duration
|
||||
return start_time, end_time
|
||||
|
||||
|
||||
def _get_publishing_cbs(cbs: Set[TrCallbackObject], pub: TrPublisher):
|
||||
"""
|
||||
Counts number of publication instances that lie within one of the cb_intervals.
|
||||
"""
|
||||
pub_timestamps = [inst.timestamp * 1e-9 for inst in pub.instances]
|
||||
pub_insts = pub.instances
|
||||
pub_cb_overlaps = {i: set() for i in range(len(pub_insts))}
|
||||
|
||||
# Algorithm: Two-pointer method
|
||||
# With both the pub_timestamps and cb_intervals sorted ascending,
|
||||
# we can cut down the O(m*n) comparisons to O(m+n).
|
||||
pub_timestamps.sort()
|
||||
|
||||
cb_id_to_cb = {cb.id: cb for cb in cbs}
|
||||
_map_args = [(cb.id, [inst_runtime_interval(inst) for inst in cb.callback_instances], pub_timestamps) for cb in cbs]
|
||||
|
||||
with Pool() as p:
|
||||
cb_wise_overlaps = p.map(_map_cb_times, _map_args)
|
||||
|
||||
pub_cb_overlaps = {i: set() for i in range(len(pub_timestamps))}
|
||||
for overlap_dict in cb_wise_overlaps:
|
||||
for i, cb_ids in overlap_dict.items():
|
||||
cbs = [cb_id_to_cb[cb_id] for cb_id in cb_ids]
|
||||
pub_cb_overlaps[i].update(cbs)
|
||||
for cb in cbs:
|
||||
cb_intervals = map(inst_runtime_interval, cb.callback_instances)
|
||||
for t_start, t_end in cb_intervals:
|
||||
i_overlap_begin = bisect_left(pub_insts, t_start, key=lambda x: x.timestamp)
|
||||
i_overlap_end = bisect(pub_insts, t_end, key=lambda x: x.timestamp)
|
||||
for i in range(i_overlap_begin, i_overlap_end):
|
||||
pub_cb_overlaps[i].add(cb)
|
||||
|
||||
pub_cbs = set()
|
||||
cb_cb_overlaps = set()
|
||||
|
@ -168,21 +136,24 @@ def _get_cb_topic_deps(nodes_to_cbs: Dict[TrNode, Set[TrCallbackObject]]):
|
|||
# For topics published to during the runtime of the callback's instances,
|
||||
# assume that they are published by the callback
|
||||
cbs_publishing_topic: Dict[TrTopic, Set[TrCallbackObject]] = {}
|
||||
p = tqdm(desc="Processing node publications", total=len(nodes_to_cbs))
|
||||
for node, cbs in nodes_to_cbs.items():
|
||||
p.update()
|
||||
cb_publishers: Dict[TrCallbackObject, Set[TrPublisher]] = {}
|
||||
for node, cbs in tqdm(nodes_to_cbs.items(), desc="Processing node publications"):
|
||||
if node is None:
|
||||
continue
|
||||
for pub in node.publishers:
|
||||
if any(f in pub.topic_name for f in TOPIC_FILTERS):
|
||||
continue
|
||||
pub_cbs = _get_publishing_cbs(cbs, pub)
|
||||
for cb in pub_cbs:
|
||||
if cb not in cb_publishers:
|
||||
cb_publishers[cb] = set()
|
||||
cb_publishers[cb].add(pub)
|
||||
if pub.topic not in cbs_publishing_topic:
|
||||
cbs_publishing_topic[pub.topic] = set()
|
||||
|
||||
cbs_publishing_topic[pub.topic].update(pub_cbs)
|
||||
|
||||
return cbs_subbed_to_topic, cbs_publishing_topic
|
||||
return cbs_subbed_to_topic, cbs_publishing_topic, cb_publishers
|
||||
|
||||
|
||||
@dataclass
|
||||
|
@ -224,6 +195,7 @@ class LGHierarchyLevel:
|
|||
class LGEdge:
|
||||
start: LGCallback
|
||||
end: LGCallback
|
||||
topic: TrTopic
|
||||
|
||||
|
||||
@dataclass
|
||||
|
@ -231,6 +203,9 @@ class LatencyGraph:
|
|||
top_node: LGHierarchyLevel
|
||||
edges: List[LGEdge]
|
||||
|
||||
cb_pubs: Dict[TrCallbackObject, Set[TrPublisher]]
|
||||
pub_cbs: Dict[TrPublisher, Set[TrCallbackObject]]
|
||||
|
||||
def __init__(self, tr: TrContext):
|
||||
##################################################
|
||||
# Annotate nodes with their callbacks
|
||||
|
@ -238,9 +213,7 @@ class LatencyGraph:
|
|||
|
||||
# Note that nodes can also be None!
|
||||
nodes_to_cbs = {}
|
||||
p = tqdm(desc="Finding CB nodes", total=len(tr.callback_objects))
|
||||
for cb in tr.callback_objects.values():
|
||||
p.update()
|
||||
for cb in tqdm(tr.callback_objects, desc="Finding CB nodes"):
|
||||
node = _get_cb_owner_node(cb)
|
||||
|
||||
if node not in nodes_to_cbs:
|
||||
|
@ -251,31 +224,23 @@ class LatencyGraph:
|
|||
# Find in/out topics for each callback
|
||||
##################################################
|
||||
|
||||
cbs_subbed_to_topic, cbs_publishing_topic = _get_cb_topic_deps(nodes_to_cbs)
|
||||
cbs_subbed_to_topic, cbs_publishing_topic, cb_pubs = _get_cb_topic_deps(nodes_to_cbs)
|
||||
pub_cbs = {}
|
||||
for cb, pubs in cb_pubs.items():
|
||||
for pub in pubs:
|
||||
if pub not in pub_cbs:
|
||||
pub_cbs[pub] = set()
|
||||
pub_cbs[pub].add(cb)
|
||||
|
||||
##################################################
|
||||
# Map topics to their messages
|
||||
##################################################
|
||||
|
||||
topics_to_messages = {}
|
||||
p = tqdm(desc="Mapping messages to topics", total=len(tr.publish_instances))
|
||||
for pub_inst in tr.publish_instances:
|
||||
p.update()
|
||||
try:
|
||||
topic = pub_inst.publisher.topic
|
||||
except KeyError:
|
||||
continue
|
||||
|
||||
if topic not in topics_to_messages:
|
||||
topics_to_messages[topic] = []
|
||||
topics_to_messages[topic].append(pub_inst)
|
||||
self.cb_pubs = cb_pubs
|
||||
self.pub_cbs = pub_cbs
|
||||
|
||||
##################################################
|
||||
# Define nodes and edges on lowest level
|
||||
##################################################
|
||||
|
||||
input = LGCallback("INPUT", [], [topic for topic in tr.topics.values() if not topic.publishers])
|
||||
output = LGCallback("OUTPUT", [topic for topic in tr.topics.values() if not topic.subscriptions], [])
|
||||
input = LGCallback("INPUT", [], [topic for topic in tr.topics if not topic.publishers])
|
||||
output = LGCallback("OUTPUT", [topic for topic in tr.topics if not topic.subscriptions], [])
|
||||
|
||||
in_node = LGHierarchyLevel(None, [], "INPUT", [input])
|
||||
out_node = LGHierarchyLevel(None, [], "OUTPUT", [output])
|
||||
|
@ -284,17 +249,17 @@ class LatencyGraph:
|
|||
|
||||
tr_to_lg_cb = {}
|
||||
|
||||
p = tqdm("Building graph nodes", total=sum(map(len, nodes_to_cbs.values())))
|
||||
p = tqdm(desc="Building graph nodes", total=sum(map(len, nodes_to_cbs.values())))
|
||||
for node, cbs in nodes_to_cbs.items():
|
||||
node_callbacks = []
|
||||
|
||||
for cb in cbs:
|
||||
p.update()
|
||||
try:
|
||||
sym = cb.callback_symbol
|
||||
|
||||
sym = cb.callback_symbol
|
||||
if sym is not None:
|
||||
pretty_sym = sanitize(sym.symbol)
|
||||
except KeyError:
|
||||
sym = None
|
||||
else:
|
||||
pretty_sym = cb.id
|
||||
in_topics = [topic for topic, cbs in cbs_subbed_to_topic.items() if cb in cbs]
|
||||
out_topics = [topic for topic, cbs in cbs_publishing_topic.items() if cb in cbs]
|
||||
|
@ -306,15 +271,13 @@ class LatencyGraph:
|
|||
lg_nodes.append(lg_node)
|
||||
|
||||
edges = []
|
||||
p = tqdm("Building graph edges", total=len(tr.topics))
|
||||
for topic in tr.topics.values():
|
||||
p.update()
|
||||
for topic in tqdm(tr.topics, desc="Building graph edges"):
|
||||
sub_cbs = cbs_subbed_to_topic[topic] if topic in cbs_subbed_to_topic else []
|
||||
pub_cbs = cbs_publishing_topic[topic] if topic in cbs_publishing_topic else []
|
||||
|
||||
for sub_cb in sub_cbs:
|
||||
for pub_cb in pub_cbs:
|
||||
lg_edge = LGEdge(tr_to_lg_cb[pub_cb], tr_to_lg_cb[sub_cb])
|
||||
lg_edge = LGEdge(tr_to_lg_cb[pub_cb], tr_to_lg_cb[sub_cb], topic)
|
||||
edges.append(lg_edge)
|
||||
|
||||
self.edges = edges
|
||||
|
@ -324,6 +287,3 @@ class LatencyGraph:
|
|||
##################################################
|
||||
|
||||
self.top_node = _hierarchize(lg_nodes)
|
||||
|
||||
def to_gv(self):
|
||||
pass
|
||||
|
|
31
latency_graph/message_tree.py
Normal file
31
latency_graph/message_tree.py
Normal file
|
@ -0,0 +1,31 @@
|
|||
from dataclasses import dataclass
|
||||
from typing import List
|
||||
|
||||
from tracing_interop.tr_types import TrPublishInstance, TrCallbackInstance
|
||||
|
||||
|
||||
@dataclass
|
||||
class DepTree:
|
||||
head: TrCallbackInstance | TrPublishInstance
|
||||
deps: List['DepTree']
|
||||
|
||||
def depth(self):
|
||||
return 1 + max(map(DepTree.depth, self.deps), default=0)
|
||||
|
||||
def size(self):
|
||||
return 1 + sum(map(DepTree.size, self.deps))
|
||||
|
||||
def fanout(self):
|
||||
if not self.deps:
|
||||
return 1
|
||||
|
||||
return sum(map(DepTree.fanout, self.deps))
|
||||
|
||||
def e2e_lat(self):
|
||||
return self.head.timestamp - self.critical_path()[-1].timestamp
|
||||
|
||||
def critical_path(self):
|
||||
if not self.deps:
|
||||
return [self.head]
|
||||
|
||||
return [self.head, *min(map(DepTree.critical_path, self.deps), key=lambda ls: ls[-1].timestamp)]
|
Loading…
Add table
Add a link
Reference in a new issue