2022-05-23 13:03:38 +02:00
|
|
|
{
|
|
|
|
"cells": [
|
|
|
|
{
|
|
|
|
"cell_type": "code",
|
2022-09-15 15:26:32 +02:00
|
|
|
"execution_count": null,
|
2022-05-23 13:03:38 +02:00
|
|
|
"outputs": [],
|
|
|
|
"source": [
|
|
|
|
"import os\n",
|
|
|
|
"import sys\n",
|
2022-09-15 18:04:45 +02:00
|
|
|
"import re\n",
|
|
|
|
"import math\n",
|
|
|
|
"from tqdm import tqdm\n",
|
2022-09-19 12:39:53 +02:00
|
|
|
"from bisect import bisect_right\n",
|
2022-09-15 18:04:45 +02:00
|
|
|
"from termcolor import colored\n",
|
|
|
|
"\n",
|
|
|
|
"import matplotlib.patches as mpatch\n",
|
|
|
|
"from scipy import stats\n",
|
|
|
|
"from cycler import cycler\n",
|
|
|
|
"\n",
|
|
|
|
"import glob\n",
|
2022-07-20 13:35:06 +02:00
|
|
|
"\n",
|
2022-05-23 13:03:38 +02:00
|
|
|
"import numpy as np\n",
|
|
|
|
"import pandas as pd\n",
|
|
|
|
"from matplotlib import pyplot as plt\n",
|
|
|
|
"\n",
|
2022-09-15 16:17:24 +02:00
|
|
|
"from misc.utils import cached, parse_as\n",
|
2022-08-29 22:17:52 +02:00
|
|
|
"\n",
|
2022-10-07 15:35:34 +09:00
|
|
|
"plt.rcParams['figure.dpi'] = 300\n",
|
|
|
|
"\n",
|
2022-09-14 14:08:47 +02:00
|
|
|
"%matplotlib inline"
|
2022-09-15 15:26:32 +02:00
|
|
|
],
|
2022-07-19 18:34:41 +02:00
|
|
|
"metadata": {
|
2022-09-20 12:44:04 +02:00
|
|
|
"collapsed": false
|
2022-09-15 15:26:32 +02:00
|
|
|
}
|
|
|
|
},
|
2022-10-13 19:13:39 +09:00
|
|
|
{
|
|
|
|
"cell_type": "markdown",
|
|
|
|
"source": [
|
|
|
|
"# User Settings"
|
|
|
|
],
|
|
|
|
"metadata": {
|
|
|
|
"collapsed": false
|
|
|
|
}
|
|
|
|
},
|
2022-09-15 15:26:32 +02:00
|
|
|
{
|
|
|
|
"cell_type": "code",
|
|
|
|
"execution_count": null,
|
2022-06-03 14:57:54 +02:00
|
|
|
"outputs": [],
|
2022-05-23 13:03:38 +02:00
|
|
|
"source": [
|
2022-09-12 19:24:26 +02:00
|
|
|
"##################################################\n",
|
|
|
|
"# User Settings\n",
|
|
|
|
"##################################################\n",
|
|
|
|
"# Change these to influence the execution of the\n",
|
|
|
|
"# notebook.\n",
|
|
|
|
"# You can override these from the command line\n",
|
|
|
|
"# by defining environment variables with the\n",
|
|
|
|
"# name of the constants below, prefixed with\n",
|
|
|
|
"# \"ANA_NB_\".\n",
|
|
|
|
"# For example, the environment variable\n",
|
|
|
|
"# \"ANA_NB_TR_PATH\" will override the \"TR_PATH\"\n",
|
|
|
|
"# setting below.\n",
|
|
|
|
"##################################################\n",
|
|
|
|
"\n",
|
|
|
|
"# The path to the build folder of a ROS2 workspace that contains the\n",
|
|
|
|
"# tracetools_read and tracetools_analysis folders.\n",
|
2022-09-15 16:17:24 +02:00
|
|
|
"TRACING_WS_BUILD_PATH = \"~/Projects/autoware/build\"\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"\n",
|
|
|
|
"# 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",
|
2022-10-07 15:35:34 +09:00
|
|
|
"# TR_PATH = \"/home/max/Downloads/iteration2_worker1/aw_replay/tracing/scenario-trace/ust\"\n",
|
2022-09-19 15:39:17 +02:00
|
|
|
"TR_PATH = \"data/trace-awsim-x86/ust\"\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"\n",
|
|
|
|
"# Path to the folder all artifacts from this notebook are saved to.\n",
|
|
|
|
"# This entails plots as well as data tables.\n",
|
|
|
|
"OUT_PATH = \"out/\"\n",
|
|
|
|
"\n",
|
2022-09-15 16:17:24 +02:00
|
|
|
"# Whether to cache the results of long computations per set of inputs\n",
|
2022-09-15 18:04:45 +02:00
|
|
|
"CACHING_ENABLED = False\n",
|
2022-09-15 16:17:24 +02:00
|
|
|
"\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"# Whether to annotate topics/publications with bandwidth/message size\n",
|
2022-09-14 14:08:47 +02:00
|
|
|
"BW_ENABLED = False\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"# Path to a results folder as output by ma-hw-perf-tools/messages/record.bash\n",
|
|
|
|
"# Used to annotate message sizes in E2E latency calculations\n",
|
|
|
|
"BW_PATH = \"../ma-hw-perf-tools/data/results\"\n",
|
|
|
|
"\n",
|
|
|
|
"# Whether to use dependencies extracted by the Clang-tools to supplement\n",
|
|
|
|
"# automatic node-internal data flow annotations.\n",
|
|
|
|
"# If in doubt, set to False.\n",
|
|
|
|
"CL_ENABLED = False\n",
|
|
|
|
"# Path to the output directory of the ROS2 dependency checker.\n",
|
|
|
|
"# Will only be used if CL_ENABLED is True.\n",
|
|
|
|
"CL_PATH = \"~/Projects/llvm-project/clang-tools-extra/ros2-internal-dependency-checker/output\"\n",
|
|
|
|
"\n",
|
|
|
|
"# Whether to compute data flow graphs.\n",
|
|
|
|
"# If you are only interested in E2E latencies, set this to False\n",
|
2022-10-07 15:35:34 +09:00
|
|
|
"DFG_ENABLED = True\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"# Whether to plot data flow graphs (ignored if DFG_ENABLED is False)\n",
|
2022-10-07 15:35:34 +09:00
|
|
|
"DFG_PLOT = True\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"\n",
|
|
|
|
"# The maximum node namespace hierarchy level to be plotted.\n",
|
|
|
|
"# Top-level (1): e.g. /sensing, /control, etc.\n",
|
|
|
|
"# Level 3: e.g. /sensing/lidar/pointcloud_processor\n",
|
|
|
|
"DFG_MAX_HIER_LEVEL = 100\n",
|
|
|
|
"\n",
|
|
|
|
"# RegEx pattern for nodes that shall be marked as system inputs\n",
|
|
|
|
"# These will be plotted with a start arrow as known from automata diagrams\n",
|
|
|
|
"DFG_INPUT_NODE_PATTERNS = [r\"^/sensing\"]\n",
|
|
|
|
"# RegEx pattern for nodes that shall be marked as system outputs\n",
|
|
|
|
"# These will be plotted with a double border\n",
|
2022-09-15 18:04:45 +02:00
|
|
|
"DFG_OUTPUT_NODE_PATTERNS = [r\"^/awapi\", r\"^/control/external_cmd_converter\", \"emergency\"]\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"# RegEx for nodes which shall not be plotted in the DFG\n",
|
|
|
|
"DFG_EXCL_NODE_PATTERNS = [r\"^/rviz2\", r\"transform_listener_impl\"]\n",
|
|
|
|
"\n",
|
|
|
|
"# Whether to compute E2E latencies.\n",
|
|
|
|
"E2E_ENABLED = True\n",
|
|
|
|
"# Whether to plot end-to-end latency information (ignored if E2E_ENABLED is False)\n",
|
2022-09-19 15:39:17 +02:00
|
|
|
"E2E_PLOT = True\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"# The index of the output message that shall be used in plots that visualize a specific\n",
|
|
|
|
"# message dependency tree. This index has to be 0 <= n < #output messages\n",
|
2022-09-19 15:39:17 +02:00
|
|
|
"E2E_PLOT_TIMESTAMP = 1000\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"# E2E latency threshold. Every E2E latency higher than this is discarded.\n",
|
|
|
|
"# Set this as low as comfortably possible to speed up calculations.\n",
|
|
|
|
"# WARNING: If you set this too low (i.e. to E2E latencies that plausibly can happen)\n",
|
|
|
|
"# your results will be wrong)\n",
|
|
|
|
"E2E_TIME_LIMIT_S = 2\n",
|
|
|
|
"\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",
|
2022-10-07 15:35:34 +09:00
|
|
|
"E2E_OUTPUT_TOPIC_PATTERNS = [r\"emergency/control_cmd\"]\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"# 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",
|
2022-10-07 15:35:34 +09:00
|
|
|
"E2E_INPUT_TOPIC_PATTERNS = [r\"^/vehicle/status/\", r\"^/sensing/(lidar/[^c]|[^l])\"]\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"\n",
|
2022-09-20 15:42:24 +02:00
|
|
|
"# 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",
|
|
|
|
"E2E_EXCLUDED_PATH_PATTERNS = [r\"NDTScanMatcher\"]\n",
|
|
|
|
"\n",
|
|
|
|
"\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"DDD = False\n",
|
|
|
|
"\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"# This code overrides the above constants with environment variables, do not edit.\n",
|
|
|
|
"for env_key, env_value in os.environ.items():\n",
|
|
|
|
" if env_key.startswith(\"ANA_NB_\"):\n",
|
|
|
|
" key = env_key.removeprefix(\"ANA_NB_\")\n",
|
|
|
|
" if key not in globals().keys():\n",
|
|
|
|
" continue\n",
|
|
|
|
" value = parse_as(type(globals()[key]), env_value)\n",
|
|
|
|
" globals()[key] = value\n",
|
|
|
|
"\n",
|
2022-09-15 18:04:45 +02:00
|
|
|
"\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"# Convert input paths to absolute paths\n",
|
|
|
|
"def _expand_path(path):\n",
|
|
|
|
" return os.path.realpath(os.path.expandvars(os.path.expanduser(path)))\n",
|
|
|
|
"\n",
|
2022-09-15 18:04:45 +02:00
|
|
|
"\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"TRACING_WS_BUILD_PATH = _expand_path(TRACING_WS_BUILD_PATH)\n",
|
|
|
|
"TR_PATH = _expand_path(TR_PATH)\n",
|
|
|
|
"OUT_PATH = _expand_path(OUT_PATH)\n",
|
|
|
|
"BW_PATH = _expand_path(BW_PATH)\n",
|
2022-09-14 14:08:47 +02:00
|
|
|
"CL_PATH = _expand_path(CL_PATH)\n",
|
|
|
|
"\n",
|
2022-09-16 19:11:35 +02:00
|
|
|
"os.makedirs(OUT_PATH, exist_ok=True)\n",
|
|
|
|
"\n",
|
|
|
|
"print(\"User Settings:\")\n",
|
2022-09-16 19:14:33 +02:00
|
|
|
"for k, v in globals().copy().items():\n",
|
2022-09-16 19:11:35 +02:00
|
|
|
" if not k.isupper():\n",
|
|
|
|
" continue\n",
|
|
|
|
" print(f\" {k:.<40s} := {v}\")"
|
2022-09-15 15:26:32 +02:00
|
|
|
],
|
2022-09-14 18:27:41 +02:00
|
|
|
"metadata": {
|
2022-09-20 12:44:04 +02:00
|
|
|
"collapsed": false
|
2022-09-15 15:26:32 +02:00
|
|
|
}
|
|
|
|
},
|
|
|
|
{
|
|
|
|
"cell_type": "code",
|
|
|
|
"execution_count": null,
|
2022-09-12 19:24:26 +02:00
|
|
|
"outputs": [],
|
|
|
|
"source": [
|
|
|
|
"sys.path.append(os.path.join(TRACING_WS_BUILD_PATH, \"tracetools_read/\"))\n",
|
|
|
|
"sys.path.append(os.path.join(TRACING_WS_BUILD_PATH, \"tracetools_analysis/\"))\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"# noinspection PyUnresolvedReferences\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"from tracetools_read.trace import *\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"# noinspection PyUnresolvedReferences\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"from tracetools_analysis.loading import load_file\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"# noinspection PyUnresolvedReferences\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"from tracetools_analysis.processor.ros2 import Ros2Handler\n",
|
|
|
|
"\n",
|
2022-09-15 18:04:45 +02:00
|
|
|
"from tracing_interop.tr_types import *\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"from message_tree.message_tree_structure import DepTree\n",
|
2022-09-15 18:04:45 +02:00
|
|
|
"from matching.subscriptions import sanitize"
|
2022-09-15 15:26:32 +02:00
|
|
|
],
|
|
|
|
"metadata": {
|
2022-09-20 12:44:04 +02:00
|
|
|
"collapsed": false
|
2022-09-15 15:26:32 +02:00
|
|
|
}
|
2022-09-12 19:24:26 +02:00
|
|
|
},
|
2022-05-23 21:28:40 +02:00
|
|
|
{
|
|
|
|
"cell_type": "markdown",
|
2022-09-15 15:26:32 +02:00
|
|
|
"source": [
|
2022-10-13 19:13:39 +09:00
|
|
|
"# Load Trace Data"
|
2022-09-15 15:26:32 +02:00
|
|
|
],
|
2022-07-19 18:34:41 +02:00
|
|
|
"metadata": {
|
2022-09-20 12:44:04 +02:00
|
|
|
"collapsed": false
|
2022-09-15 15:26:32 +02:00
|
|
|
}
|
2022-05-23 21:28:40 +02:00
|
|
|
},
|
2022-05-23 13:03:38 +02:00
|
|
|
{
|
|
|
|
"cell_type": "code",
|
2022-09-15 15:26:32 +02:00
|
|
|
"execution_count": null,
|
|
|
|
"outputs": [],
|
2022-05-24 20:35:30 +02:00
|
|
|
"source": [
|
2022-07-20 13:35:06 +02:00
|
|
|
"def _load_traces():\n",
|
|
|
|
" file = load_file(TR_PATH)\n",
|
|
|
|
" handler = Ros2Handler.process(file)\n",
|
2022-08-29 22:17:52 +02:00
|
|
|
" return TrContext(handler)\n",
|
2022-07-20 13:35:06 +02:00
|
|
|
"\n",
|
2022-08-09 18:36:53 +02:00
|
|
|
"\n",
|
2022-09-15 18:04:45 +02:00
|
|
|
"_tracing_context = cached(\"tr_objects\", _load_traces, [TR_PATH], not CACHING_ENABLED)\n",
|
2022-07-20 13:35:06 +02:00
|
|
|
"_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",
|
2022-05-30 16:51:06 +02:00
|
|
|
"\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"print(\"Done.\")"
|
2022-09-15 15:26:32 +02:00
|
|
|
],
|
|
|
|
"metadata": {
|
2022-09-20 12:44:04 +02:00
|
|
|
"collapsed": false
|
2022-09-15 15:26:32 +02:00
|
|
|
}
|
2022-09-14 18:27:41 +02:00
|
|
|
},
|
2022-09-16 13:36:42 +02:00
|
|
|
{
|
|
|
|
"cell_type": "code",
|
|
|
|
"execution_count": null,
|
|
|
|
"outputs": [],
|
|
|
|
"source": [
|
2022-09-16 19:11:35 +02:00
|
|
|
"\n",
|
2022-09-16 16:38:23 +02:00
|
|
|
"for topic in sorted(topics, key=lambda t: t.name):\n",
|
2022-09-16 13:36:42 +02:00
|
|
|
" topic: TrTopic\n",
|
2022-09-20 12:44:04 +02:00
|
|
|
" print(f\"{topic.name:.<120s} | {sum(map(lambda p: len(p.instances), topic.publishers))}\")\n",
|
|
|
|
"\n",
|
|
|
|
"print(\"\\n[ENTKÄFERN] INPUT TOPICS\")\n",
|
|
|
|
"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",
|
2022-10-07 15:35:34 +09:00
|
|
|
" print(f\"--[ENTKÄFERN] {f:<30s}:{t.name:.<89s} | {sum(map(lambda p: len(p.instances), t.publishers))}\")\n",
|
2022-09-20 12:44:04 +02:00
|
|
|
"\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",
|
2022-10-07 15:35:34 +09:00
|
|
|
" print(f\"--[ENTKÄFERN] {f:<30s}:{t.name:.<89s} | {sum(map(lambda p: len(p.instances), t.publishers))}\")"
|
2022-09-16 13:36:42 +02:00
|
|
|
],
|
|
|
|
"metadata": {
|
2022-09-20 12:44:04 +02:00
|
|
|
"collapsed": false
|
2022-09-16 13:36:42 +02:00
|
|
|
}
|
|
|
|
},
|
2022-05-23 21:28:40 +02:00
|
|
|
{
|
|
|
|
"cell_type": "markdown",
|
2022-09-15 15:26:32 +02:00
|
|
|
"source": [
|
2022-10-13 19:13:39 +09:00
|
|
|
"# Analyze ROS Graph"
|
2022-09-15 15:26:32 +02:00
|
|
|
],
|
2022-07-19 18:34:41 +02:00
|
|
|
"metadata": {
|
2022-09-20 12:44:04 +02:00
|
|
|
"collapsed": false
|
2022-09-15 15:26:32 +02:00
|
|
|
}
|
2022-05-23 21:28:40 +02:00
|
|
|
},
|
|
|
|
{
|
|
|
|
"cell_type": "code",
|
2022-09-15 15:26:32 +02:00
|
|
|
"execution_count": null,
|
|
|
|
"outputs": [],
|
2022-05-23 21:28:40 +02:00
|
|
|
"source": [
|
2022-10-13 19:13:39 +09:00
|
|
|
"import latency_graph.latency_graph_structure as lg\n",
|
2022-07-20 13:35:06 +02:00
|
|
|
"\n",
|
2022-09-15 18:04:45 +02:00
|
|
|
"\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"def _make_latency_graph():\n",
|
|
|
|
" return lg.LatencyGraph(_tracing_context)\n",
|
2022-07-20 13:35:06 +02:00
|
|
|
"\n",
|
2022-09-15 18:04:45 +02:00
|
|
|
"\n",
|
|
|
|
"lat_graph = cached(\"lat_graph\", _make_latency_graph, [TR_PATH], not CACHING_ENABLED)"
|
2022-09-15 15:26:32 +02:00
|
|
|
],
|
2022-07-20 13:35:06 +02:00
|
|
|
"metadata": {
|
2022-09-20 12:44:04 +02:00
|
|
|
"collapsed": false
|
2022-09-15 15:26:32 +02:00
|
|
|
}
|
|
|
|
},
|
2022-10-13 19:13:39 +09:00
|
|
|
{
|
|
|
|
"cell_type": "markdown",
|
|
|
|
"source": [
|
|
|
|
"## Plot ROS Graph (full)"
|
|
|
|
],
|
|
|
|
"metadata": {
|
|
|
|
"collapsed": false
|
|
|
|
}
|
|
|
|
},
|
2022-09-15 15:26:32 +02:00
|
|
|
{
|
|
|
|
"cell_type": "code",
|
|
|
|
"execution_count": null,
|
|
|
|
"outputs": [],
|
2022-07-20 13:35:06 +02:00
|
|
|
"source": [
|
2022-09-12 19:24:26 +02:00
|
|
|
"%%skip_if_false DFG_ENABLED\n",
|
|
|
|
"%%skip_if_false DFG_PLOT\n",
|
|
|
|
"\n",
|
2022-07-20 13:35:06 +02:00
|
|
|
"#################################################\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"# Plot full DFG, down to the callback level\n",
|
2022-07-20 13:35:06 +02:00
|
|
|
"#################################################\n",
|
|
|
|
"\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"from latency_graph.latency_graph_plots import plot_latency_graph_full\n",
|
|
|
|
"\n",
|
|
|
|
"plot_latency_graph_full(lat_graph, _tracing_context, \"latency_graph_full\")"
|
|
|
|
],
|
|
|
|
"metadata": {
|
|
|
|
"collapsed": false
|
|
|
|
}
|
|
|
|
},
|
|
|
|
{
|
|
|
|
"cell_type": "markdown",
|
|
|
|
"source": [
|
|
|
|
"## Plot Latency Graph (overview)"
|
2022-09-15 15:26:32 +02:00
|
|
|
],
|
2022-07-20 13:35:06 +02:00
|
|
|
"metadata": {
|
2022-09-20 12:44:04 +02:00
|
|
|
"collapsed": false
|
2022-09-15 15:26:32 +02:00
|
|
|
}
|
|
|
|
},
|
|
|
|
{
|
|
|
|
"cell_type": "code",
|
|
|
|
"execution_count": null,
|
|
|
|
"outputs": [],
|
2022-05-30 16:51:06 +02:00
|
|
|
"source": [
|
2022-09-12 19:24:26 +02:00
|
|
|
"%%skip_if_false DFG_ENABLED\n",
|
|
|
|
"%%skip_if_false DFG_PLOT\n",
|
|
|
|
"\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"#################################################\n",
|
|
|
|
"# Plot overview of DFG, down to a certain\n",
|
|
|
|
"# hierarchy level\n",
|
|
|
|
"#################################################\n",
|
2022-08-29 22:17:52 +02:00
|
|
|
"\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"from latency_graph.latency_graph_plots import plot_latency_graph_overview\n",
|
2022-06-28 10:06:42 +02:00
|
|
|
"\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"plot_latency_graph_overview(lat_graph, DFG_EXCL_NODE_PATTERNS, DFG_INPUT_NODE_PATTERNS, DFG_OUTPUT_NODE_PATTERNS, DFG_MAX_HIER_LEVEL, \"latency_graph_overview\")"
|
2022-09-15 15:26:32 +02:00
|
|
|
],
|
2022-07-19 18:34:41 +02:00
|
|
|
"metadata": {
|
2022-09-20 14:42:48 +02:00
|
|
|
"collapsed": false,
|
|
|
|
"pycharm": {
|
|
|
|
"name": "#%%%%skip_if_false DFG_ENABLED\n"
|
|
|
|
}
|
2022-09-15 15:26:32 +02:00
|
|
|
}
|
|
|
|
},
|
|
|
|
{
|
2022-10-13 19:13:39 +09:00
|
|
|
"cell_type": "markdown",
|
2022-08-29 22:17:52 +02:00
|
|
|
"source": [
|
2022-10-13 19:13:39 +09:00
|
|
|
"# Analyze Message Flow"
|
2022-09-15 15:26:32 +02:00
|
|
|
],
|
2022-09-14 18:27:41 +02:00
|
|
|
"metadata": {
|
2022-09-20 12:44:04 +02:00
|
|
|
"collapsed": false
|
2022-09-15 15:26:32 +02:00
|
|
|
}
|
|
|
|
},
|
|
|
|
{
|
|
|
|
"cell_type": "code",
|
|
|
|
"execution_count": null,
|
|
|
|
"outputs": [],
|
2022-08-29 22:17:52 +02:00
|
|
|
"source": [
|
2022-09-12 19:24:26 +02:00
|
|
|
"%%skip_if_false E2E_ENABLED\n",
|
|
|
|
"\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"from message_tree.message_tree_algorithms import build_dep_trees\n",
|
|
|
|
"\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"end_topics = [t for t in _tracing_context.topics if any(re.search(f, t.name) for f in E2E_OUTPUT_TOPIC_PATTERNS)]\n",
|
|
|
|
"\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"def _build_dep_trees():\n",
|
|
|
|
" return build_dep_trees(end_topics, lat_graph, _tracing_context, E2E_EXCLUDED_PATH_PATTERNS, E2E_TIME_LIMIT_S)\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"\n",
|
2022-09-19 12:39:53 +02:00
|
|
|
"try:\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
" trees = cached(\"trees\", _build_dep_trees, [TR_PATH], not CACHING_ENABLED)\n",
|
2022-09-19 12:39:53 +02:00
|
|
|
"except Exception as e:\n",
|
|
|
|
" import traceback\n",
|
|
|
|
" print(e)\n",
|
|
|
|
" traceback.print_exc()"
|
2022-09-15 15:26:32 +02:00
|
|
|
],
|
2022-08-29 22:17:52 +02:00
|
|
|
"metadata": {
|
2022-09-20 12:44:04 +02:00
|
|
|
"collapsed": false
|
2022-09-15 15:26:32 +02:00
|
|
|
}
|
|
|
|
},
|
|
|
|
{
|
|
|
|
"cell_type": "code",
|
|
|
|
"execution_count": null,
|
|
|
|
"outputs": [],
|
2022-08-29 22:17:52 +02:00
|
|
|
"source": [
|
2022-09-12 19:24:26 +02:00
|
|
|
"%%skip_if_false E2E_ENABLED\n",
|
|
|
|
"%%skip_if_false BW_ENABLED\n",
|
|
|
|
"\n",
|
2022-08-29 22:17:52 +02:00
|
|
|
"\n",
|
|
|
|
"def parse_bytes(string):\n",
|
|
|
|
" match string[-1]:\n",
|
|
|
|
" case 'K':\n",
|
|
|
|
" exponent = 1e3\n",
|
|
|
|
" case 'M':\n",
|
|
|
|
" exponent = 1e6\n",
|
|
|
|
" case _:\n",
|
|
|
|
" exponent = 1\n",
|
|
|
|
"\n",
|
|
|
|
" num = float(string.split(\" \")[0])\n",
|
|
|
|
" return num * exponent\n",
|
|
|
|
"\n",
|
|
|
|
"\n",
|
|
|
|
"def bytes_str(bytes):\n",
|
2022-09-15 18:04:45 +02:00
|
|
|
" if bytes >= 1024 ** 2:\n",
|
|
|
|
" return f\"{bytes / (1024 ** 2):.2f} MiB\"\n",
|
2022-08-29 22:17:52 +02:00
|
|
|
" if bytes >= 1024:\n",
|
2022-09-15 18:04:45 +02:00
|
|
|
" return f\"{bytes / 1024:.2f} KiB\"\n",
|
2022-08-29 22:17:52 +02:00
|
|
|
" return f\"{bytes:.0f} B\"\n",
|
|
|
|
"\n",
|
|
|
|
"\n",
|
|
|
|
"bw_files = glob.glob(os.path.join(BW_PATH, \"*.log\"))\n",
|
|
|
|
"msg_sizes = {}\n",
|
|
|
|
"for bw_file in bw_files:\n",
|
|
|
|
" with open(bw_file) as f:\n",
|
|
|
|
" lines = f.readlines()\n",
|
|
|
|
" topic = os.path.splitext(os.path.split(bw_file)[1])[0].replace(\"__\", \"/\")\n",
|
|
|
|
"\n",
|
|
|
|
" if not lines or re.match(f\"^\\s*$\", lines[-1]):\n",
|
|
|
|
" #print(f\"No data for {topic}\")\n",
|
|
|
|
" continue\n",
|
|
|
|
"\n",
|
2022-09-15 18:04:45 +02:00
|
|
|
" line_pattern = re.compile(\n",
|
|
|
|
" r\"(?P<bw>[0-9.]+ [KM]?)B/s from (?P<n_msgs>[0-9.]+) messages --- Message size mean: (?P<mean>[0-9.]+ [KM]?)B min: (?P<min>[0-9.]+ [KM]?)B max: (?P<max>[0-9.]+ [KM]?)B\\n\")\n",
|
2022-08-29 22:17:52 +02:00
|
|
|
" m = re.fullmatch(line_pattern, lines[-1])\n",
|
|
|
|
" if m is None:\n",
|
|
|
|
" print(f\"Line could not be parsed in {topic}: '{lines[-1]}'\")\n",
|
|
|
|
" continue\n",
|
|
|
|
"\n",
|
|
|
|
" msg_sizes[topic] = {'bw': parse_bytes(m.group(\"bw\")),\n",
|
|
|
|
" 'min': parse_bytes(m.group(\"min\")),\n",
|
|
|
|
" 'mean': parse_bytes(m.group(\"mean\")),\n",
|
2022-10-07 15:35:34 +09:00
|
|
|
" 'max': parse_bytes(m.group(\"max\"))}"
|
2022-09-15 15:26:32 +02:00
|
|
|
],
|
2022-08-29 22:17:52 +02:00
|
|
|
"metadata": {
|
2022-09-20 12:44:04 +02:00
|
|
|
"collapsed": false
|
2022-09-15 15:26:32 +02:00
|
|
|
}
|
|
|
|
},
|
|
|
|
{
|
|
|
|
"cell_type": "code",
|
|
|
|
"execution_count": null,
|
|
|
|
"outputs": [],
|
2022-08-29 22:17:52 +02:00
|
|
|
"source": [
|
2022-09-12 19:24:26 +02:00
|
|
|
"%%skip_if_false E2E_ENABLED\n",
|
|
|
|
"%%skip_if_false E2E_PLOT\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"%%skip_if_false DDD\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"\n",
|
|
|
|
"\n",
|
2022-10-07 15:35:34 +09:00
|
|
|
"fig, ax = plt.subplots(num=\"e2e_plot\")\n",
|
2022-09-15 18:04:45 +02:00
|
|
|
"DS = 1\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"times = [tree.head.timestamp - trees[0].head.timestamp for tree in trees]\n",
|
2022-08-29 22:17:52 +02:00
|
|
|
"\n",
|
|
|
|
"ax2 = ax.twinx()\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"ax2.plot(times, list(map(lambda paths: sum(map(len, paths)) / len(paths), e2e_pathss)), color=\"orange\")\n",
|
2022-08-29 22:17:52 +02:00
|
|
|
"ax2.fill_between(times,\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
" list(map(lambda paths: min(map(len, paths)), e2e_pathss)),\n",
|
|
|
|
" list(map(lambda paths: max(map(len, paths)), e2e_pathss)),\n",
|
2022-08-29 22:17:52 +02:00
|
|
|
" alpha=.3, color=\"orange\")\n",
|
|
|
|
"\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"ax.plot(times, [np.mean(e2es) for e2es in e2ess])\n",
|
|
|
|
"ax.fill_between(times, [np.min(e2es) for e2es in e2ess], [np.max(e2es) for e2es in e2ess], alpha=.3)\n",
|
2022-08-29 22:17:52 +02:00
|
|
|
"\n",
|
2022-09-15 18:04:45 +02:00
|
|
|
"\n",
|
2022-08-29 22:17:52 +02:00
|
|
|
"def scatter_topic(topic_name, y=0, **scatter_kwargs):\n",
|
|
|
|
" for pub in topics.by_name[topic_name].publishers:\n",
|
|
|
|
" if not pub:\n",
|
|
|
|
" continue\n",
|
|
|
|
"\n",
|
2022-09-15 18:04:45 +02:00
|
|
|
" inst_timestamps = [inst.timestamp - trees[0].head.timestamp for inst in pub.instances if\n",
|
|
|
|
" inst.timestamp >= trees[0].head.timestamp]\n",
|
2022-08-29 22:17:52 +02:00
|
|
|
" scatter_kwargs_default = {\"marker\": \"x\", \"color\": \"indianred\"}\n",
|
|
|
|
" scatter_kwargs_default.update(scatter_kwargs)\n",
|
|
|
|
" ax.scatter(inst_timestamps, np.full(len(inst_timestamps), fill_value=y), **scatter_kwargs_default)\n",
|
|
|
|
"\n",
|
2022-09-15 18:04:45 +02:00
|
|
|
"\n",
|
2022-08-29 22:17:52 +02:00
|
|
|
"scatter_topic(\"/autoware/engage\")\n",
|
|
|
|
"scatter_topic(\"/planning/scenario_planning/parking/trajectory\", y=-.04, color=\"cadetblue\")\n",
|
|
|
|
"scatter_topic(\"/planning/scenario_planning/lane_driving/trajectory\", y=-.08, color=\"darkgreen\")\n",
|
|
|
|
"\n",
|
|
|
|
"ax.set_xlabel(\"Simulation time [s]\")\n",
|
|
|
|
"ax.set_ylabel(\"End-to-End latency [s]\")\n",
|
|
|
|
"ax2.set_ylabel(\"End-to-End path length\")\n",
|
|
|
|
"None"
|
2022-09-15 15:26:32 +02:00
|
|
|
],
|
2022-08-29 22:17:52 +02:00
|
|
|
"metadata": {
|
2022-09-20 12:44:04 +02:00
|
|
|
"collapsed": false
|
2022-09-15 15:26:32 +02:00
|
|
|
}
|
|
|
|
},
|
|
|
|
{
|
|
|
|
"cell_type": "code",
|
|
|
|
"execution_count": null,
|
|
|
|
"outputs": [],
|
2022-08-29 22:17:52 +02:00
|
|
|
"source": [
|
2022-09-12 19:24:26 +02:00
|
|
|
"%%skip_if_false E2E_ENABLED\n",
|
|
|
|
"%%skip_if_false E2E_PLOT\n",
|
|
|
|
"\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"%load_ext line_profiler\n",
|
2022-09-16 19:11:35 +02:00
|
|
|
"\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"from message_tree.message_tree_algorithms import e2e_paths_sorted_desc\n",
|
|
|
|
"from message_tree.message_tree_plots import e2e_breakdown_type_hist\n",
|
2022-08-29 22:17:52 +02:00
|
|
|
"\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"def _map_tree_to_e2es(tree):\n",
|
|
|
|
" return e2e_paths_sorted_desc(tree, E2E_INPUT_TOPIC_PATTERNS)\n",
|
2022-08-29 22:17:52 +02:00
|
|
|
"\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"def ppp():\n",
|
|
|
|
" trees_paths = [e2e_paths_sorted_desc(tree, E2E_INPUT_TOPIC_PATTERNS) for tree in tqdm(trees, desc=\"Extracting E2E paths\")]\n",
|
|
|
|
" all_paths = [p for paths in trees_paths for p in paths]\n",
|
|
|
|
" all_e2e_items = [i for p in all_paths for i in p]\n",
|
2022-08-29 22:17:52 +02:00
|
|
|
"\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
" return all_e2e_items\n",
|
2022-08-29 22:17:52 +02:00
|
|
|
"\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"%lprun -f e2e_paths_sorted_desc ppp()\n",
|
2022-09-12 19:24:26 +02:00
|
|
|
"\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"e2e_breakdown_type_hist(ppp())\n",
|
2022-08-29 22:17:52 +02:00
|
|
|
"\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"None\n"
|
2022-09-15 15:26:32 +02:00
|
|
|
],
|
2022-09-14 18:27:41 +02:00
|
|
|
"metadata": {
|
2022-09-20 12:44:04 +02:00
|
|
|
"collapsed": false
|
2022-09-15 15:26:32 +02:00
|
|
|
}
|
|
|
|
},
|
|
|
|
{
|
|
|
|
"cell_type": "code",
|
|
|
|
"execution_count": null,
|
|
|
|
"outputs": [],
|
2022-09-09 13:52:28 +02:00
|
|
|
"source": [
|
2022-10-13 19:13:39 +09:00
|
|
|
"import pickle\n",
|
2022-10-07 15:35:34 +09:00
|
|
|
"\n",
|
2022-10-13 19:13:39 +09:00
|
|
|
"with open(\"trees.pkl\", \"wb\") as f:\n",
|
|
|
|
" pickle.dump(trees, f)\n"
|
2022-09-15 15:26:32 +02:00
|
|
|
],
|
2022-10-07 15:35:34 +09:00
|
|
|
"metadata": {
|
|
|
|
"collapsed": false
|
|
|
|
}
|
|
|
|
},
|
|
|
|
{
|
|
|
|
"cell_type": "code",
|
|
|
|
"execution_count": null,
|
|
|
|
"outputs": [],
|
|
|
|
"source": [],
|
|
|
|
"metadata": {
|
|
|
|
"collapsed": false
|
|
|
|
}
|
2022-05-23 13:03:38 +02:00
|
|
|
}
|
|
|
|
],
|
|
|
|
"metadata": {
|
|
|
|
"interpreter": {
|
2022-06-28 10:06:42 +02:00
|
|
|
"hash": "e7370f93d1d0cde622a1f8e1c04877d8463912d04d973331ad4851f04de6915a"
|
2022-05-23 13:03:38 +02:00
|
|
|
},
|
|
|
|
"kernelspec": {
|
2022-09-14 18:27:41 +02:00
|
|
|
"display_name": "Python 3 (ipykernel)",
|
2022-05-23 13:03:38 +02:00
|
|
|
"language": "python",
|
|
|
|
"name": "python3"
|
|
|
|
},
|
|
|
|
"language_info": {
|
|
|
|
"codemirror_mode": {
|
|
|
|
"name": "ipython",
|
|
|
|
"version": 3
|
|
|
|
},
|
|
|
|
"file_extension": ".py",
|
|
|
|
"mimetype": "text/x-python",
|
|
|
|
"name": "python",
|
|
|
|
"nbconvert_exporter": "python",
|
|
|
|
"pygments_lexer": "ipython3",
|
2022-09-14 18:27:41 +02:00
|
|
|
"version": "3.10.4"
|
2022-05-23 13:03:38 +02:00
|
|
|
}
|
|
|
|
},
|
|
|
|
"nbformat": 4,
|
|
|
|
"nbformat_minor": 2
|
2022-09-20 12:44:04 +02:00
|
|
|
}
|