{ "cells": [ { "cell_type": "code", "execution_count": null, "metadata": { "pycharm": { "name": "#%%\n" } }, "outputs": [], "source": [ "import glob\n", "import json\n", "import os\n", "import pickle\n", "import re\n", "import sys\n", "\n", "import numpy as np\n", "import pandas as pd\n", "from matplotlib import pyplot as plt\n", "\n", "from clang_interop.cl_types import ClContext\n", "from clang_interop.process_clang_output import process_clang_output\n", "\n", "sys.path.append(\"../autoware/build/tracetools_read/\")\n", "sys.path.append(\"../autoware/build/tracetools_analysis/\")\n", "from tracetools_read.trace import *\n", "from tracetools_analysis.loading import load_file\n", "from tracetools_analysis.processor.ros2 import Ros2Handler\n", "from tracetools_analysis.utils.ros2 import Ros2DataModelUtil\n", "\n", "from tracing_interop.tr_types import TrTimer, TrTopic, TrPublisher, TrPublishInstance, TrCallbackInstance, \\\n", "TrCallbackSymbol, TrCallbackObject, TrSubscriptionObject, TrContext\n", "from misc.utils import ProgressPrinter, cached\n", "\n", "%load_ext pyinstrument\n", "%matplotlib inline" ] }, { "cell_type": "code", "execution_count": null, "metadata": { "pycharm": { "name": "#%%\n" } }, "outputs": [], "source": [ "TR_PATH = os.path.expanduser(\"data/awsim-trace/ust\")\n", "CL_PATH = os.path.expanduser(\"~/Projects/llvm-project/clang-tools-extra/ros2-internal-dependency-checker/output\")" ] }, { "cell_type": "markdown", "source": [ "# Organize Trace Data" ], "metadata": { "collapsed": false, "pycharm": { "name": "#%% md\n" } } }, { "cell_type": "code", "execution_count": null, "outputs": [], "source": [ "def _load_traces():\n", " file = load_file(TR_PATH)\n", " handler = Ros2Handler.process(file)\n", " return TrContext(handler)\n", "\n", "\n", "_tracing_context = cached(\"tr_objects\", _load_traces, [TR_PATH])\n", "_tr_globals = [\"nodes\", \"publishers\", \"subscriptions\", \"timers\", \"timer_node_links\", \"subscription_objects\",\n", " \"callback_objects\", \"callback_symbols\", \"publish_instances\", \"callback_instances\", \"topics\"]\n", "\n", "# Help the IDE recognize those identifiers\n", "nodes = publishers = subscriptions = timers = timer_node_links = subscription_objects = callback_objects = callback_symbols = publish_instances = callback_instances = topics = None\n", "\n", "for name in _tr_globals:\n", " globals()[name] = getattr(_tracing_context, name)\n", "\n", "print(\"Done.\")\n" ], "metadata": { "collapsed": false, "pycharm": { "name": "#%%\n" } } }, { "cell_type": "markdown", "source": [ "# E2E Latency Calculation" ], "metadata": { "collapsed": false, "pycharm": { "name": "#%% md\n" } } }, { "cell_type": "code", "execution_count": null, "outputs": [], "source": [ "from latency_graph import latency_graph as lg\n", "\n", "lat_graph = lg.LatencyGraph(_tracing_context)\n", "\n", "import pickle\n", "\n", "with open(\"lat_graph.pkl\", \"wb\") as f:\n", " pickle.dump(lat_graph, f)\n", "#with open(\"lat_graph.pkl\", \"rb\") as f:\n", "# lat_graph = pickle.load(f)" ], "metadata": { "collapsed": false, "pycharm": { "name": "#%%\n" } } }, { "cell_type": "code", "execution_count": null, "outputs": [], "source": [ "len(lat_graph.edges)" ], "metadata": { "collapsed": false, "pycharm": { "name": "#%%\n" } } }, { "cell_type": "code", "execution_count": null, "outputs": [], "source": [ "from matching.subscriptions import sanitize\n", "from typing import Iterable, Sized\n", "from tracing_interop.tr_types import TrNode, TrCallbackObject, TrCallbackSymbol, TrSubscriptionObject\n", "\n", "#################################################\n", "# Plot DFG\n", "#################################################\n", "\n", "# Compare with: https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/node-diagram/\n", "node_colors = {\n", " \"sensing\": {\"fill\": \"#e1d5e7\", \"stroke\": \"#9673a6\"},\n", " \"localization\": {\"fill\": \"#dae8fc\", \"stroke\": \"#6c8ebf\"},\n", " \"perception\": {\"fill\": \"#d5e8d4\", \"stroke\": \"#82b366\"},\n", " \"planning\": {\"fill\": \"#fff2cc\", \"stroke\": \"#d6b656\"},\n", " \"control\": {\"fill\": \"#ffe6cc\", \"stroke\": \"#d79b00\"},\n", " \"system\": {\"fill\": \"#f8cecc\", \"stroke\": \"#b85450\"},\n", " \"vehicle_interface\": {\"fill\": \"#b0e3e6\", \"stroke\": \"#0e8088\"},\n", " None: {\"fill\": \"#f5f5f5\", \"stroke\": \"#666666\"}\n", "}\n", "\n", "node_namespace_mapping = {\n", " 'perception': 'perception',\n", " 'sensing': 'sensing',\n", " 'planning': 'planning',\n", " 'control': 'control',\n", " 'awapi': None,\n", " 'autoware_api': None,\n", " 'map': None,\n", " 'system': 'system',\n", " 'localization': 'localization',\n", " 'robot_state_publisher': None,\n", " 'aggregator_node': None,\n", " 'pointcloud_container': 'sensing',\n", "}\n", "\n", "import graphviz as gv\n", "\n", "g = gv.Digraph('G', filename=\"latency_graph.gv\",\n", " node_attr={'shape': 'plain'},\n", " graph_attr={'pack': '1'})\n", "g.graph_attr['rankdir'] = 'LR'\n", "\n", "def plot_hierarchy(gv_parent, lg_node: lg.LGHierarchyLevel, **subgraph_kwargs):\n", " if lg_node.name == \"[NONE]\":\n", " return\n", "\n", " print(f\"{' ' * lg_node.full_name.count('/')}Processing {lg_node.name}: {len(lg_node.callbacks)}\")\n", " with gv_parent.subgraph(name=f\"cluster_{lg_node.full_name.replace('/', '__')}\", **subgraph_kwargs) as c:\n", " c.attr(label=lg_node.name)\n", " for cb in lg_node.callbacks:\n", " if isinstance(cb, lg.LGTrCallback):\n", " tr_cb = cb.cb\n", " try:\n", " sym = _tracing_context.callback_symbols.by_id.get(tr_cb.callback_object)\n", " pretty_sym = repr(sanitize(sym.symbol))\n", " except KeyError:\n", " pretty_sym = cb.name\n", " except TypeError:\n", " pretty_sym = cb.name\n", " else:\n", " pretty_sym = cb.name\n", "\n", " pretty_sym = pretty_sym.replace(\"&\", \"&\").replace(\"<\", \"<\").replace(\">\", \">\")\n", "\n", " c.node(cb.id(),\n", " f'<
{pretty_sym} |