Refactorings, better console output.
* Removed spam-like warnings (mostly replaced by printing a single warning counter) * Removed inst_runtime_interval() from latency_graph.py as it was out of that file's responsibilities. Moved into TrCallbackInstance directly * Fixed coloring of latency graph (planning was misspelled)
This commit is contained in:
parent
e9a00d51c9
commit
130c99e56f
3 changed files with 106 additions and 75 deletions
|
@ -26,6 +26,8 @@
|
|||
"\n",
|
||||
"from misc.utils import cached, parse_as\n",
|
||||
"\n",
|
||||
"plt.rcParams['figure.dpi'] = 300\n",
|
||||
"\n",
|
||||
"%matplotlib inline"
|
||||
],
|
||||
"metadata": {
|
||||
|
@ -58,6 +60,7 @@
|
|||
"# Path to trace directory (e.g. ~/.ros/my-trace/ust) or to a converted trace file.\n",
|
||||
"# Using the path \"/ust\" at the end is optional but greatly reduces processing time\n",
|
||||
"# if kernel traces are also present.\n",
|
||||
"# TR_PATH = \"/home/max/Downloads/iteration2_worker1/aw_replay/tracing/scenario-trace/ust\"\n",
|
||||
"TR_PATH = \"data/trace-awsim-x86/ust\"\n",
|
||||
"\n",
|
||||
"# Path to the folder all artifacts from this notebook are saved to.\n",
|
||||
|
@ -83,9 +86,9 @@
|
|||
"\n",
|
||||
"# Whether to compute data flow graphs.\n",
|
||||
"# If you are only interested in E2E latencies, set this to False\n",
|
||||
"DFG_ENABLED = False\n",
|
||||
"DFG_ENABLED = True\n",
|
||||
"# Whether to plot data flow graphs (ignored if DFG_ENABLED is False)\n",
|
||||
"DFG_PLOT = False\n",
|
||||
"DFG_PLOT = True\n",
|
||||
"\n",
|
||||
"# The maximum node namespace hierarchy level to be plotted.\n",
|
||||
"# Top-level (1): e.g. /sensing, /control, etc.\n",
|
||||
|
@ -116,10 +119,10 @@
|
|||
"\n",
|
||||
"# All topics containing any of these RegEx patterns are considered output topics in E2E latency calculations\n",
|
||||
"# E.g. r\"^/control/\" will cover all control topics\n",
|
||||
"E2E_OUTPUT_TOPIC_PATTERNS = [r\"^/control/.*?/control_cmd\"]\n",
|
||||
"E2E_OUTPUT_TOPIC_PATTERNS = [r\"emergency/control_cmd\"]\n",
|
||||
"# All topics containing any of these RegEx patterns are considered input topics in E2E latency calculations\n",
|
||||
"# E.g. r\"^/sensing/\" will cover all sensing topics\n",
|
||||
"E2E_INPUT_TOPIC_PATTERNS = [r\"^/vehicle/status/\", r\"^/sensing/\"]\n",
|
||||
"E2E_INPUT_TOPIC_PATTERNS = [r\"^/vehicle/status/\", r\"^/sensing/(lidar/[^c]|[^l])\"]\n",
|
||||
"\n",
|
||||
"# E2E paths are uniquely identified by a string like \"/topic/1 -> void(Node1)(args1) -> /topic/2 -> void(Node2)(args2) -> void(Node2)(args3) -> ...\".\n",
|
||||
"# Certain patterns only occur in initial setup or in scenario switching and can be excluded via RegEx patterns here.\n",
|
||||
|
@ -192,7 +195,6 @@
|
|||
"execution_count": null,
|
||||
"outputs": [],
|
||||
"source": [
|
||||
"\n",
|
||||
"def _load_traces():\n",
|
||||
" file = load_file(TR_PATH)\n",
|
||||
" handler = Ros2Handler.process(file)\n",
|
||||
|
@ -229,13 +231,13 @@
|
|||
"for t in sorted(topics, key=lambda t: t.name):\n",
|
||||
" for f in E2E_INPUT_TOPIC_PATTERNS:\n",
|
||||
" if re.search(f, t.name):\n",
|
||||
" print(f\"--[ENTKÄFERN] {f} :ß: {t.name}\")\n",
|
||||
" print(f\"--[ENTKÄFERN] {f:<30s}:{t.name:.<89s} | {sum(map(lambda p: len(p.instances), t.publishers))}\")\n",
|
||||
"\n",
|
||||
"print(\"\\n[ENTKÄFERN] OUTPUT TOPICS\")\n",
|
||||
"for t in sorted(topics, key=lambda t: t.name):\n",
|
||||
" for f in E2E_OUTPUT_TOPIC_PATTERNS:\n",
|
||||
" if re.search(f, t.name):\n",
|
||||
" print(f\"--[ENTKÄFERN] {f} :ß: {t.name}\")"
|
||||
" print(f\"--[ENTKÄFERN] {f:<30s}:{t.name:.<89s} | {sum(map(lambda p: len(p.instances), t.publishers))}\")"
|
||||
],
|
||||
"metadata": {
|
||||
"collapsed": false
|
||||
|
@ -255,7 +257,6 @@
|
|||
"execution_count": null,
|
||||
"outputs": [],
|
||||
"source": [
|
||||
"\n",
|
||||
"from latency_graph import latency_graph as lg\n",
|
||||
"\n",
|
||||
"\n",
|
||||
|
@ -274,7 +275,6 @@
|
|||
"execution_count": null,
|
||||
"outputs": [],
|
||||
"source": [
|
||||
"\n",
|
||||
"%%skip_if_false DFG_ENABLED\n",
|
||||
"%%skip_if_false DFG_PLOT\n",
|
||||
"\n",
|
||||
|
@ -297,11 +297,11 @@
|
|||
"node_namespace_mapping = {\n",
|
||||
" 'perception': 'perception',\n",
|
||||
" 'sensing': 'sensing',\n",
|
||||
" 'plannitokenizeng': 'planning',\n",
|
||||
" 'planning': 'planning',\n",
|
||||
" 'control': 'control',\n",
|
||||
" 'awapi': None,\n",
|
||||
" 'autoware_api': None,\n",
|
||||
" 'map': None,\n",
|
||||
" 'awapi': 'system',\n",
|
||||
" 'autoware_api': 'system',\n",
|
||||
" 'map': 'system',\n",
|
||||
" 'system': 'system',\n",
|
||||
" 'localization': 'localization',\n",
|
||||
" 'robot_state_publisher': None,\n",
|
||||
|
@ -370,7 +370,6 @@
|
|||
"execution_count": null,
|
||||
"outputs": [],
|
||||
"source": [
|
||||
"\n",
|
||||
"%%skip_if_false DFG_ENABLED\n",
|
||||
"%%skip_if_false DFG_PLOT\n",
|
||||
"\n",
|
||||
|
@ -384,7 +383,7 @@
|
|||
" if cur_lvl == DFG_MAX_HIER_LEVEL:\n",
|
||||
" return [node]\n",
|
||||
"\n",
|
||||
" if not node.children and cur_lvl < DFG_MAX_HIER_LEVEL:\n",
|
||||
" if not node.children:\n",
|
||||
" return [node]\n",
|
||||
"\n",
|
||||
" collected_nodes = []\n",
|
||||
|
@ -555,7 +554,7 @@
|
|||
" i_inst_latest = bisect_right(cb.callback_instances, inst.timestamp, key=lambda x: x.timestamp)\n",
|
||||
"\n",
|
||||
" for inst_before in cb.callback_instances[i_inst_latest::-1]:\n",
|
||||
" if lg.inst_runtime_interval(inst_before)[-1] < inst.timestamp:\n",
|
||||
" if inst_before.t_end < inst.timestamp:\n",
|
||||
" return inst_before\n",
|
||||
"\n",
|
||||
" return None\n",
|
||||
|
@ -606,11 +605,10 @@
|
|||
" i_inst_after = bisect_right(cb.callback_instances, msg.timestamp, key=lambda x: x.timestamp)\n",
|
||||
"\n",
|
||||
" for inst in cb.callback_instances[:i_inst_after]:\n",
|
||||
" inst_start, inst_end = lg.inst_runtime_interval(inst)\n",
|
||||
" if msg.timestamp > inst_end:\n",
|
||||
" if msg.timestamp > inst.t_end:\n",
|
||||
" continue\n",
|
||||
"\n",
|
||||
" assert inst_start <= msg.timestamp <= inst_end\n",
|
||||
" assert inst.t_start <= msg.timestamp <= inst.t_end\n",
|
||||
"\n",
|
||||
" cb_inst_candidates.append(inst)\n",
|
||||
"\n",
|
||||
|
@ -674,7 +672,6 @@
|
|||
"execution_count": null,
|
||||
"outputs": [],
|
||||
"source": [
|
||||
"\n",
|
||||
"%%skip_if_false E2E_ENABLED\n",
|
||||
"\n",
|
||||
"end_topics = [t for t in _tracing_context.topics if any(re.search(f, t.name) for f in E2E_OUTPUT_TOPIC_PATTERNS)]\n",
|
||||
|
@ -710,12 +707,10 @@
|
|||
"execution_count": null,
|
||||
"outputs": [],
|
||||
"source": [
|
||||
"\n",
|
||||
"%%skip_if_false E2E_ENABLED\n",
|
||||
"%%skip_if_false BW_ENABLED\n",
|
||||
"\n",
|
||||
"\n",
|
||||
"\n",
|
||||
"def parse_bytes(string):\n",
|
||||
" match string[-1]:\n",
|
||||
" case 'K':\n",
|
||||
|
@ -758,7 +753,7 @@
|
|||
" msg_sizes[topic] = {'bw': parse_bytes(m.group(\"bw\")),\n",
|
||||
" 'min': parse_bytes(m.group(\"min\")),\n",
|
||||
" 'mean': parse_bytes(m.group(\"mean\")),\n",
|
||||
" 'max': parse_bytes(m.group(\"max\"))}\n"
|
||||
" 'max': parse_bytes(m.group(\"max\"))}"
|
||||
],
|
||||
"metadata": {
|
||||
"collapsed": false
|
||||
|
@ -828,23 +823,28 @@
|
|||
"\n",
|
||||
"\n",
|
||||
"e2ess = []\n",
|
||||
"e2ess_trees = []\n",
|
||||
"e2e_pathss = []\n",
|
||||
"for tree in trees:\n",
|
||||
" try:\n",
|
||||
" e2es, e2e_paths = zip(*relevant_e2es(tree, E2E_INPUT_TOPIC_PATTERNS))\n",
|
||||
" except ValueError as e:\n",
|
||||
" print(e)\n",
|
||||
" print(end='!')\n",
|
||||
" continue\n",
|
||||
" e2ess.append(e2es)\n",
|
||||
" e2ess_trees.append(tree)\n",
|
||||
" e2e_pathss.append(e2e_paths)\n",
|
||||
"\n",
|
||||
"print()\n",
|
||||
"print(f\"[ENTKÄFERN] IN-TOPICS FOUND in {len(e2ess)}/{len(trees)} trees\")\n",
|
||||
"in_topics_found = \"\\n \".join(map(lambda pair: f\"{pair[0]:.<110s} {pair[1]:>10d}\", in_topics_found.items()))\n",
|
||||
"print(f\" {in_topics_found}\")\n",
|
||||
"\n",
|
||||
"print(f\"[ENTKÄFERN] LEAF TOPICS FOUND\")\n",
|
||||
"leaf_topics_found = \"\\n \".join(map(lambda pair: f\"{pair[0]:.<110s} {pair[1]:>10d}\", leaf_topics_found.items()))\n",
|
||||
"print(f\" {leaf_topics_found}\")"
|
||||
"print(f\" {leaf_topics_found}\")\n",
|
||||
"\n",
|
||||
"trees = e2ess_trees # Filter non-E2E trees"
|
||||
],
|
||||
"metadata": {
|
||||
"collapsed": false
|
||||
|
@ -855,12 +855,11 @@
|
|||
"execution_count": null,
|
||||
"outputs": [],
|
||||
"source": [
|
||||
"\n",
|
||||
"%%skip_if_false E2E_ENABLED\n",
|
||||
"%%skip_if_false E2E_PLOT\n",
|
||||
"\n",
|
||||
"\n",
|
||||
"fig, ax = plt.subplots(figsize=(18, 9), num=\"e2e_plot\")\n",
|
||||
"fig, ax = plt.subplots(num=\"e2e_plot\")\n",
|
||||
"DS = 1\n",
|
||||
"times = [tree.head.timestamp - trees[0].head.timestamp for tree in trees[::DS]]\n",
|
||||
"\n",
|
||||
|
@ -905,7 +904,6 @@
|
|||
"execution_count": null,
|
||||
"outputs": [],
|
||||
"source": [
|
||||
"\n",
|
||||
"%%skip_if_false E2E_ENABLED\n",
|
||||
"\n",
|
||||
"def critical_path(self):\n",
|
||||
|
@ -971,7 +969,6 @@
|
|||
"execution_count": null,
|
||||
"outputs": [],
|
||||
"source": [
|
||||
"\n",
|
||||
"%%skip_if_false E2E_ENABLED\n",
|
||||
"%%skip_if_false E2E_PLOT\n",
|
||||
"\n",
|
||||
|
@ -981,7 +978,7 @@
|
|||
" dictionary[key].append(value)\n",
|
||||
"\n",
|
||||
"\n",
|
||||
"fig, (ax, ax_rel) = plt.subplots(2, 1, sharex=True, figsize=(60, 30), num=\"crit_plot\")\n",
|
||||
"fig, (ax, ax_rel) = plt.subplots(2, 1, sharex=True, num=\"crit_plot\")\n",
|
||||
"ax.set_prop_cycle(cycler('color', [plt.cm.nipy_spectral(i / 4) for i in range(5)]))\n",
|
||||
"ax_rel.set_prop_cycle(cycler('color', [plt.cm.nipy_spectral(i / 4) for i in range(5)]))\n",
|
||||
"\n",
|
||||
|
@ -1068,17 +1065,17 @@
|
|||
"%%skip_if_false E2E_ENABLED\n",
|
||||
"%%skip_if_false E2E_PLOT\n",
|
||||
"\n",
|
||||
"fig, ax = plt.subplots(figsize=(60, 15), num=\"crit_pdf\")\n",
|
||||
"fig, ax = plt.subplots(num=\"crit_pdf\")\n",
|
||||
"ax.set_prop_cycle(cycler('color', [plt.cm.nipy_spectral(i / 4) for i in range(5)]))\n",
|
||||
"\n",
|
||||
"kde = stats.gaussian_kde(timestep_mags)\n",
|
||||
"xs = np.linspace(timestep_mags.min(), timestep_mags.max(), 1000)\n",
|
||||
"ax.plot(xs, kde(xs), label=\"End-to-End Latency\")\n",
|
||||
"perc = 90\n",
|
||||
"perc = 50\n",
|
||||
"ax.axvline(np.percentile(timestep_mags, perc), label=f\"{perc}th percentile\")\n",
|
||||
"\n",
|
||||
"ax2 = ax.twinx()\n",
|
||||
"ax2.hist(timestep_mags, 200)\n",
|
||||
"ax2.hist(timestep_mags, 50)\n",
|
||||
"ax2.set_ylim(0, ax2.get_ylim()[1])\n",
|
||||
"\n",
|
||||
"ax.set_title(\"Time Distribution for E2E Breakdown\")\n",
|
||||
|
@ -1099,7 +1096,6 @@
|
|||
"execution_count": null,
|
||||
"outputs": [],
|
||||
"source": [
|
||||
"\n",
|
||||
"%%skip_if_false E2E_ENABLED\n",
|
||||
"%%skip_if_false E2E_PLOT\n",
|
||||
"\n",
|
||||
|
@ -1257,7 +1253,7 @@
|
|||
" return height\n",
|
||||
"\n",
|
||||
"\n",
|
||||
"fig, ax = plt.subplots(figsize=(36, 20), num=\"path_viz\")\n",
|
||||
"fig, ax = plt.subplots(num=\"path_viz\")\n",
|
||||
"ax.set_ylim(0, len(e2es))\n",
|
||||
"\n",
|
||||
"y_labels = []\n",
|
||||
|
@ -1299,32 +1295,31 @@
|
|||
"execution_count": null,
|
||||
"outputs": [],
|
||||
"source": [
|
||||
"\n",
|
||||
"%%skip_if_false E2E_ENABLED\n",
|
||||
"\n",
|
||||
"\n",
|
||||
"def _owner(inst):\n",
|
||||
" match inst:\n",
|
||||
" case TrCallbackInstance(callback_obj=cb_obj):\n",
|
||||
" cb_obj: TrCallbackObject\n",
|
||||
" if cb_obj and cb_obj.callback_symbol:\n",
|
||||
" sym = repr(sanitize(cb_obj.callback_symbol.symbol))\n",
|
||||
" else:\n",
|
||||
" sym = str(cb_obj.id)\n",
|
||||
" return sym\n",
|
||||
" case TrPublishInstance(publisher=pub):\n",
|
||||
" pub: TrPublisher\n",
|
||||
" topic = pub.topic_name\n",
|
||||
" return topic\n",
|
||||
" case _:\n",
|
||||
" raise ValueError()\n",
|
||||
"\n",
|
||||
"\n",
|
||||
"critical_paths = {}\n",
|
||||
"print(len(relevant_trees))\n",
|
||||
"for tree in tqdm(relevant_trees):\n",
|
||||
" crit = critical_path(tree)\n",
|
||||
"\n",
|
||||
"\n",
|
||||
" def _owner(inst):\n",
|
||||
" match inst:\n",
|
||||
" case TrCallbackInstance(callback_obj=cb_obj):\n",
|
||||
" cb_obj: TrCallbackObject\n",
|
||||
" if cb_obj and cb_obj.callback_symbol:\n",
|
||||
" sym = repr(sanitize(cb_obj.callback_symbol.symbol))\n",
|
||||
" else:\n",
|
||||
" sym = str(cb_obj.id)\n",
|
||||
" return sym\n",
|
||||
" case TrPublishInstance(publisher=pub):\n",
|
||||
" pub: TrPublisher\n",
|
||||
" topic = pub.topic_name\n",
|
||||
" return topic\n",
|
||||
" case _:\n",
|
||||
" raise ValueError()\n",
|
||||
"\n",
|
||||
"\n",
|
||||
" key = tuple(map(_owner, crit[::-1]))\n",
|
||||
" if key not in critical_paths:\n",
|
||||
" critical_paths[key] = []\n",
|
||||
|
@ -1387,6 +1382,24 @@
|
|||
"name": "#%%%%skip_if_false E2E_ENABLED\n"
|
||||
}
|
||||
}
|
||||
},
|
||||
{
|
||||
"cell_type": "code",
|
||||
"execution_count": null,
|
||||
"outputs": [],
|
||||
"source": [],
|
||||
"metadata": {
|
||||
"collapsed": false
|
||||
}
|
||||
},
|
||||
{
|
||||
"cell_type": "code",
|
||||
"execution_count": null,
|
||||
"outputs": [],
|
||||
"source": [],
|
||||
"metadata": {
|
||||
"collapsed": false
|
||||
}
|
||||
}
|
||||
],
|
||||
"metadata": {
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue