469 lines
37 KiB
Text
469 lines
37 KiB
Text
{
|
||
"cells": [
|
||
{
|
||
"cell_type": "code",
|
||
"execution_count": 5,
|
||
"metadata": {},
|
||
"outputs": [],
|
||
"source": [
|
||
"# # Building\n",
|
||
"# colcon build\n",
|
||
"# # later also just:\n",
|
||
"# colcon build --packages-select full_topology\n",
|
||
"# \n",
|
||
"# # Running\n",
|
||
"# source install/setup.bash\n",
|
||
"# ros2 launch full_topology trace_full_topology.launch.py\n",
|
||
"# ros2 trace-analysis convert ./analysis/tracing/full_topology_tracing\n",
|
||
"# ros2 trace-analysis process ./analysis/tracing/full_topology_tracing\n",
|
||
"#\n",
|
||
"# ## On the host machine for lttng:\n",
|
||
"# ### Getting the modules\n",
|
||
"# sudo su -\n",
|
||
"# cd /var/lib/dkms/lttng-modules/2.13.0.rc1.516.g41ea7c4b/build\n",
|
||
"# make clean\n",
|
||
"# make\n",
|
||
"# make modules_install\n",
|
||
"# exit\n",
|
||
"# sudo depmod -a\n",
|
||
"# sudo modprobe lttng-tracer\n",
|
||
"# sudo modprobe lttng-ring-buffer-client-discard\n",
|
||
"# sudo modprobe lttng-ring-buffer-client-overwrite\n",
|
||
"# sudo modprobe lttng-ring-buffer-metadata-client\n",
|
||
"# sudo systemctl restart lttng-sessiond.service\n",
|
||
"# \n",
|
||
"# # we need \"libxml2.so.2\"\n",
|
||
"# sudo ln -s /usr/lib/libxml2.so /usr/lib/libxml2.so.2\n",
|
||
"# ### Verify the modules\n",
|
||
"# lsmod | grep lttng\n",
|
||
"# \n",
|
||
"# sudo systemctl status lttng-sessiond.service\n",
|
||
"# \n",
|
||
"# lttng create test-session\n",
|
||
"# lttng enable-event -k sched_switch\n",
|
||
"# lttng start\n",
|
||
"# sleep 1\n",
|
||
"# lttng stop\n",
|
||
"# lttng destroy"
|
||
]
|
||
},
|
||
{
|
||
"cell_type": "code",
|
||
"execution_count": 6,
|
||
"metadata": {},
|
||
"outputs": [],
|
||
"source": [
|
||
"#path = '~/.ros/tracing/pingpong/ust'\n",
|
||
"path = '/workspaces/ROS-Dynamic-Executor-Experiments/analysis/tracing/full_topology_tracing-20250516134156/ust/converted'"
|
||
]
|
||
},
|
||
{
|
||
"cell_type": "code",
|
||
"execution_count": 7,
|
||
"metadata": {},
|
||
"outputs": [
|
||
{
|
||
"name": "stdout",
|
||
"output_type": "stream",
|
||
"text": [
|
||
" [100%] [Ros2Handler]\n",
|
||
"Index(['callback_object', 'timestamp', 'duration', 'intra_process'], dtype='object')\n"
|
||
]
|
||
}
|
||
],
|
||
"source": [
|
||
"import sys\n",
|
||
"# Assuming a workspace with:\n",
|
||
"# <...>/tracetools_analysis/\n",
|
||
"# <...>/ros2_tracing/tracetools_read/\n",
|
||
"sys.path.insert(0, '../')\n",
|
||
"sys.path.insert(0, '../../../ros2_tracing/tracetools_read/')\n",
|
||
"\n",
|
||
"from tracetools_analysis.loading import load_file\n",
|
||
"from tracetools_analysis.processor.ros2 import Ros2Handler\n",
|
||
"events = load_file(path)\n",
|
||
"handler = Ros2Handler.process(events)\n",
|
||
"names = {ev['_name'] for ev in events}\n",
|
||
"#print(names)\n",
|
||
"assert 'ros2:rclcpp_publish' in names\n",
|
||
"assert 'ros2:callback_start' in names\n",
|
||
"print(handler.data.callback_instances.columns)\n",
|
||
"# → … 'message_id' … now present\n"
|
||
]
|
||
},
|
||
{
|
||
"cell_type": "code",
|
||
"execution_count": 8,
|
||
"metadata": {},
|
||
"outputs": [],
|
||
"source": [
|
||
"import sys\n",
|
||
"# Assuming a workspace with:\n",
|
||
"# <...>/tracetools_analysis/\n",
|
||
"# <...>/ros2_tracing/tracetools_read/\n",
|
||
"sys.path.insert(0, '../')\n",
|
||
"sys.path.insert(0, '../../../ros2_tracing/tracetools_read/')\n",
|
||
"import datetime as dt\n",
|
||
"\n",
|
||
"from bokeh.plotting import figure\n",
|
||
"from bokeh.plotting import output_notebook\n",
|
||
"from bokeh.io import show\n",
|
||
"from bokeh.layouts import row\n",
|
||
"from bokeh.models import ColumnDataSource\n",
|
||
"from bokeh.models import DatetimeTickFormatter\n",
|
||
"from bokeh.models import PrintfTickFormatter\n",
|
||
"import numpy as np\n",
|
||
"import pandas as pd\n",
|
||
"\n",
|
||
"from tracetools_analysis.loading import load_file\n",
|
||
"from tracetools_analysis.processor.ros2 import Ros2Handler\n",
|
||
"from tracetools_analysis.utils.ros2 import Ros2DataModelUtil"
|
||
]
|
||
},
|
||
{
|
||
"cell_type": "code",
|
||
"execution_count": 9,
|
||
"metadata": {},
|
||
"outputs": [
|
||
{
|
||
"name": "stdout",
|
||
"output_type": "stream",
|
||
"text": [
|
||
" [100%] [Ros2Handler]\n"
|
||
]
|
||
}
|
||
],
|
||
"source": [
|
||
"# Process\n",
|
||
"events = load_file(path)\n",
|
||
"handler = Ros2Handler.process(events)\n",
|
||
"#handler.data.print_data()"
|
||
]
|
||
},
|
||
{
|
||
"cell_type": "code",
|
||
"execution_count": 10,
|
||
"metadata": {},
|
||
"outputs": [
|
||
{
|
||
"data": {
|
||
"text/html": [
|
||
"<style>\n",
|
||
" .bk-notebook-logo {\n",
|
||
" display: block;\n",
|
||
" width: 20px;\n",
|
||
" height: 20px;\n",
|
||
" background-image: url(data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAABQAAAAUCAYAAACNiR0NAAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAABx0RVh0U29mdHdhcmUAQWRvYmUgRmlyZXdvcmtzIENTNui8sowAAAOkSURBVDiNjZRtaJVlGMd/1/08zzln5zjP1LWcU9N0NkN8m2CYjpgQYQXqSs0I84OLIC0hkEKoPtiH3gmKoiJDU7QpLgoLjLIQCpEsNJ1vqUOdO7ppbuec5+V+rj4ctwzd8IIbbi6u+8f1539dt3A78eXC7QizUF7gyV1fD1Yqg4JWz84yffhm0qkFqBogB9rM8tZdtwVsPUhWhGcFJngGeWrPzHm5oaMmkfEg1usvLFyc8jLRqDOMru7AyC8saQr7GG7f5fvDeH7Ej8CM66nIF+8yngt6HWaKh7k49Soy9nXurCi1o3qUbS3zWfrYeQDTB/Qj6kX6Ybhw4B+bOYoLKCC9H3Nu/leUTZ1JdRWkkn2ldcCamzrcf47KKXdAJllSlxAOkRgyHsGC/zRday5Qld9DyoM4/q/rUoy/CXh3jzOu3bHUVZeU+DEn8FInkPBFlu3+nW3Nw0mk6vCDiWg8CeJaxEwuHS3+z5RgY+YBR6V1Z1nxSOfoaPa4LASWxxdNp+VWTk7+4vzaou8v8PN+xo+KY2xsw6une2frhw05CTYOmQvsEhjhWjn0bmXPjpE1+kplmmkP3suftwTubK9Vq22qKmrBhpY4jvd5afdRA3wGjFAgcnTK2s4hY0/GPNIb0nErGMCRxWOOX64Z8RAC4oCXdklmEvcL8o0BfkNK4lUg9HTl+oPlQxdNo3Mg4Nv175e/1LDGzZen30MEjRUtmXSfiTVu1kK8W4txyV6BMKlbgk3lMwYCiusNy9fVfvvwMxv8Ynl6vxoByANLTWplvuj/nF9m2+PDtt1eiHPBr1oIfhCChQMBw6Aw0UulqTKZdfVvfG7VcfIqLG9bcldL/+pdWTLxLUy8Qq38heUIjh4XlzZxzQm19lLFlr8vdQ97rjZVOLf8nclzckbcD4wxXMidpX30sFd37Fv/GtwwhzhxGVAprjbg0gCAEeIgwCZyTV2Z1REEW8O4py0wsjeloKoMr6iCY6dP92H6Vw/oTyICIthibxjm/DfN9lVz8IqtqKYLUXfoKVMVQVVJOElGjrnnUt9T9wbgp8AyYKaGlqingHZU/uG2NTZSVqwHQTWkx9hxjkpWDaCg6Ckj5qebgBVbT3V3NNXMSiWSDdGV3hrtzla7J+duwPOToIg42ChPQOQjspnSlp1V+Gjdged7+8UN5CRAV7a5EdFNwCjEaBR27b3W890TE7g24NAP/mMDXRWrGoFPQI9ls/MWO2dWFAar/xcOIImbbpA3zgAAAABJRU5ErkJggg==);\n",
|
||
" }\n",
|
||
" </style>\n",
|
||
" <div>\n",
|
||
" <a href=\"https://bokeh.org\" target=\"_blank\" class=\"bk-notebook-logo\"></a>\n",
|
||
" <span id=\"e69a3b91-32bd-4eb3-a5af-3b8844dac007\">Loading BokehJS ...</span>\n",
|
||
" </div>\n"
|
||
]
|
||
},
|
||
"metadata": {},
|
||
"output_type": "display_data"
|
||
},
|
||
{
|
||
"data": {
|
||
"application/javascript": "(function(root) {\n function now() {\n return new Date();\n }\n\n const force = true;\n\n if (typeof root._bokeh_onload_callbacks === \"undefined\" || force === true) {\n root._bokeh_onload_callbacks = [];\n root._bokeh_is_loading = undefined;\n }\n\nconst JS_MIME_TYPE = 'application/javascript';\n const HTML_MIME_TYPE = 'text/html';\n const EXEC_MIME_TYPE = 'application/vnd.bokehjs_exec.v0+json';\n const CLASS_NAME = 'output_bokeh rendered_html';\n\n /**\n * Render data to the DOM node\n */\n function render(props, node) {\n const script = document.createElement(\"script\");\n node.appendChild(script);\n }\n\n /**\n * Handle when an output is cleared or removed\n */\n function handleClearOutput(event, handle) {\n const cell = handle.cell;\n\n const id = cell.output_area._bokeh_element_id;\n const server_id = cell.output_area._bokeh_server_id;\n // Clean up Bokeh references\n if (id != null && id in Bokeh.index) {\n Bokeh.index[id].model.document.clear();\n delete Bokeh.index[id];\n }\n\n if (server_id !== undefined) {\n // Clean up Bokeh references\n const cmd_clean = \"from bokeh.io.state import curstate; print(curstate().uuid_to_server['\" + server_id + \"'].get_sessions()[0].document.roots[0]._id)\";\n cell.notebook.kernel.execute(cmd_clean, {\n iopub: {\n output: function(msg) {\n const id = msg.content.text.trim();\n if (id in Bokeh.index) {\n Bokeh.index[id].model.document.clear();\n delete Bokeh.index[id];\n }\n }\n }\n });\n // Destroy server and session\n const cmd_destroy = \"import bokeh.io.notebook as ion; ion.destroy_server('\" + server_id + \"')\";\n cell.notebook.kernel.execute(cmd_destroy);\n }\n }\n\n /**\n * Handle when a new output is added\n */\n function handleAddOutput(event, handle) {\n const output_area = handle.output_area;\n const output = handle.output;\n\n // limit handleAddOutput to display_data with EXEC_MIME_TYPE content only\n if ((output.output_type != \"display_data\") || (!Object.prototype.hasOwnProperty.call(output.data, EXEC_MIME_TYPE))) {\n return\n }\n\n const toinsert = output_area.element.find(\".\" + CLASS_NAME.split(' ')[0]);\n\n if (output.metadata[EXEC_MIME_TYPE][\"id\"] !== undefined) {\n toinsert[toinsert.length - 1].firstChild.textContent = output.data[JS_MIME_TYPE];\n // store reference to embed id on output_area\n output_area._bokeh_element_id = output.metadata[EXEC_MIME_TYPE][\"id\"];\n }\n if (output.metadata[EXEC_MIME_TYPE][\"server_id\"] !== undefined) {\n const bk_div = document.createElement(\"div\");\n bk_div.innerHTML = output.data[HTML_MIME_TYPE];\n const script_attrs = bk_div.children[0].attributes;\n for (let i = 0; i < script_attrs.length; i++) {\n toinsert[toinsert.length - 1].firstChild.setAttribute(script_attrs[i].name, script_attrs[i].value);\n toinsert[toinsert.length - 1].firstChild.textContent = bk_div.children[0].textContent\n }\n // store reference to server id on output_area\n output_area._bokeh_server_id = output.metadata[EXEC_MIME_TYPE][\"server_id\"];\n }\n }\n\n function register_renderer(events, OutputArea) {\n\n function append_mime(data, metadata, element) {\n // create a DOM node to render to\n const toinsert = this.create_output_subarea(\n metadata,\n CLASS_NAME,\n EXEC_MIME_TYPE\n );\n this.keyboard_manager.register_events(toinsert);\n // Render to node\n const props = {data: data, metadata: metadata[EXEC_MIME_TYPE]};\n render(props, toinsert[toinsert.length - 1]);\n element.append(toinsert);\n return toinsert\n }\n\n /* Handle when an output is cleared or removed */\n events.on('clear_output.CodeCell', handleClearOutput);\n events.on('delete.Cell', handleClearOutput);\n\n /* Handle when a new output is added */\n events.on('output_added.OutputArea', handleAddOutput);\n\n /**\n * Register the mime type and append_mime function with output_area\n */\n OutputArea.prototype.register_mime_type(EXEC_MIME_TYPE, append_mime, {\n /* Is output safe? */\n safe: true,\n /* Index of renderer in `output_area.display_order` */\n index: 0\n });\n }\n\n // register the mime type if in Jupyter Notebook environment and previously unregistered\n if (root.Jupyter !== undefined) {\n const events = require('base/js/events');\n const OutputArea = require('notebook/js/outputarea').OutputArea;\n\n if (OutputArea.prototype.mime_types().indexOf(EXEC_MIME_TYPE) == -1) {\n register_renderer(events, OutputArea);\n }\n }\n if (typeof (root._bokeh_timeout) === \"undefined\" || force === true) {\n root._bokeh_timeout = Date.now() + 5000;\n root._bokeh_failed_load = false;\n }\n\n const NB_LOAD_WARNING = {'data': {'text/html':\n \"<div style='background-color: #fdd'>\\n\"+\n \"<p>\\n\"+\n \"BokehJS does not appear to have successfully loaded. If loading BokehJS from CDN, this \\n\"+\n \"may be due to a slow or bad network connection. Possible fixes:\\n\"+\n \"</p>\\n\"+\n \"<ul>\\n\"+\n \"<li>re-rerun `output_notebook()` to attempt to load from CDN again, or</li>\\n\"+\n \"<li>use INLINE resources instead, as so:</li>\\n\"+\n \"</ul>\\n\"+\n \"<code>\\n\"+\n \"from bokeh.resources import INLINE\\n\"+\n \"output_notebook(resources=INLINE)\\n\"+\n \"</code>\\n\"+\n \"</div>\"}};\n\n function display_loaded() {\n const el = document.getElementById(\"e69a3b91-32bd-4eb3-a5af-3b8844dac007\");\n if (el != null) {\n el.textContent = \"BokehJS is loading...\";\n }\n if (root.Bokeh !== undefined) {\n if (el != null) {\n el.textContent = \"BokehJS \" + root.Bokeh.version + \" successfully loaded.\";\n }\n } else if (Date.now() < root._bokeh_timeout) {\n setTimeout(display_loaded, 100)\n }\n }\n\n function run_callbacks() {\n try {\n root._bokeh_onload_callbacks.forEach(function(callback) {\n if (callback != null)\n callback();\n });\n } finally {\n delete root._bokeh_onload_callbacks\n }\n console.debug(\"Bokeh: all callbacks have finished\");\n }\n\n function load_libs(css_urls, js_urls, callback) {\n if (css_urls == null) css_urls = [];\n if (js_urls == null) js_urls = [];\n\n root._bokeh_onload_callbacks.push(callback);\n if (root._bokeh_is_loading > 0) {\n console.debug(\"Bokeh: BokehJS is being loaded, scheduling callback at\", now());\n return null;\n }\n if (js_urls == null || js_urls.length === 0) {\n run_callbacks();\n return null;\n }\n console.debug(\"Bokeh: BokehJS not loaded, scheduling load and callback at\", now());\n root._bokeh_is_loading = css_urls.length + js_urls.length;\n\n function on_load() {\n root._bokeh_is_loading--;\n if (root._bokeh_is_loading === 0) {\n console.debug(\"Bokeh: all BokehJS libraries/stylesheets loaded\");\n run_callbacks()\n }\n }\n\n function on_error(url) {\n console.error(\"failed to load \" + url);\n }\n\n for (let i = 0; i < css_urls.length; i++) {\n const url = css_urls[i];\n const element = document.createElement(\"link\");\n element.onload = on_load;\n element.onerror = on_error.bind(null, url);\n element.rel = \"stylesheet\";\n element.type = \"text/css\";\n element.href = url;\n console.debug(\"Bokeh: injecting link tag for BokehJS stylesheet: \", url);\n document.body.appendChild(element);\n }\n\n for (let i = 0; i < js_urls.length; i++) {\n const url = js_urls[i];\n const element = document.createElement('script');\n element.onload = on_load;\n element.onerror = on_error.bind(null, url);\n element.async = false;\n element.src = url;\n console.debug(\"Bokeh: injecting script tag for BokehJS library: \", url);\n document.head.appendChild(element);\n }\n };\n\n function inject_raw_css(css) {\n const element = document.createElement(\"style\");\n element.appendChild(document.createTextNode(css));\n document.body.appendChild(element);\n }\n\n const js_urls = [\"https://cdn.bokeh.org/bokeh/release/bokeh-3.1.1.min.js\", \"https://cdn.bokeh.org/bokeh/release/bokeh-gl-3.1.1.min.js\", \"https://cdn.bokeh.org/bokeh/release/bokeh-widgets-3.1.1.min.js\", \"https://cdn.bokeh.org/bokeh/release/bokeh-tables-3.1.1.min.js\", \"https://cdn.bokeh.org/bokeh/release/bokeh-mathjax-3.1.1.min.js\"];\n const css_urls = [];\n\n const inline_js = [ function(Bokeh) {\n Bokeh.set_log_level(\"info\");\n },\nfunction(Bokeh) {\n }\n ];\n\n function run_inline_js() {\n if (root.Bokeh !== undefined || force === true) {\n for (let i = 0; i < inline_js.length; i++) {\n inline_js[i].call(root, root.Bokeh);\n }\nif (force === true) {\n display_loaded();\n }} else if (Date.now() < root._bokeh_timeout) {\n setTimeout(run_inline_js, 100);\n } else if (!root._bokeh_failed_load) {\n console.log(\"Bokeh: BokehJS failed to load within specified timeout.\");\n root._bokeh_failed_load = true;\n } else if (force !== true) {\n const cell = $(document.getElementById(\"e69a3b91-32bd-4eb3-a5af-3b8844dac007\")).parents('.cell').data().cell;\n cell.output_area.append_execute_result(NB_LOAD_WARNING)\n }\n }\n\n if (root._bokeh_is_loading === 0) {\n console.debug(\"Bokeh: BokehJS loaded, going straight to plotting\");\n run_inline_js();\n } else {\n load_libs(css_urls, js_urls, function() {\n console.debug(\"Bokeh: BokehJS plotting callback run at\", now());\n run_inline_js();\n });\n }\n}(window));",
|
||
"application/vnd.bokehjs_load.v0+json": ""
|
||
},
|
||
"metadata": {},
|
||
"output_type": "display_data"
|
||
}
|
||
],
|
||
"source": [
|
||
"data_util = Ros2DataModelUtil(handler.data)\n",
|
||
"\n",
|
||
"callback_symbols = data_util.get_callback_symbols()\n",
|
||
"\n",
|
||
"output_notebook()\n",
|
||
"psize = 450\n",
|
||
"colours = [\n",
|
||
" '#29788E', '#DD4968', '#410967', '#44BFC8', '#F76F8E',\n",
|
||
" '#8B1E3F', '#81C784', '#FFB74D', '#9575CD', '#F06292',\n",
|
||
" '#4DB6AC', '#BA68C8', '#7986CB', '#AED581', '#FF8A65',\n",
|
||
" '#E57373', '#64B5F6', '#4FC3F7', '#81D4FA', '#4DD0E1',\n",
|
||
" '#26A69A', '#66BB6A', '#D4E157', '#FFEE58', '#FFCA28',\n",
|
||
" '#FFA726', '#FF7043', '#8D6E63', '#BDBDBD', '#78909C',\n",
|
||
" '#90CAF9', '#A5D6A7', '#FFF59D', '#FFD54F', '#FFCC80',\n",
|
||
" '#FFAB91', '#CE93D8', '#F48FB1', '#B39DDB', '#80DEEA',\n",
|
||
" '#A1887F', '#E0E0E0', '#E6EE9C', '#C5E1A5', '#FFCDD2',\n",
|
||
" '#F0F4C3', '#B0BEC5', '#B2EBF2', '#DCEDC8', '#F5F5F5'\n",
|
||
"]"
|
||
]
|
||
},
|
||
{
|
||
"cell_type": "code",
|
||
"execution_count": 11,
|
||
"metadata": {},
|
||
"outputs": [
|
||
{
|
||
"name": "stdout",
|
||
"output_type": "stream",
|
||
"text": [
|
||
"Callback object → symbol → owner info\n",
|
||
"\n",
|
||
"110492369590912 → Subscription -- node: sensor_fusion_node, tid: 210285, topic: /imu/data\n",
|
||
"110492377049488 → Subscription -- node: telemetry_node, tid: 210285, topic: /camera/mapped\n",
|
||
"110492374014864 → Subscription -- node: flight_mgmt_node, tid: 210285, topic: /operator/commands\n",
|
||
"110492361275680 → Subscription -- node: radiometric_node, tid: 210285, topic: /camera/debayered\n",
|
||
"110492363270560 → Subscription -- node: mapping_node, tid: 210285, topic: /camera/geometric\n",
|
||
"110492369806368 → Subscription -- node: sensor_fusion_node, tid: 210285, topic: /gps/fix\n",
|
||
"110492378550192 → Subscription -- node: radio_tx_node, tid: 210285, topic: /telemetry/data\n",
|
||
"110492364459312 → Subscription -- node: smoke_classifier_node, tid: 210285, topic: /camera/radiometric\n",
|
||
"110492375534528 → Subscription -- node: flight_control_node, tid: 210285, topic: /flight/plan\n",
|
||
"110492362358864 → Subscription -- node: geometric_node, tid: 210285, topic: /camera/radiometric\n",
|
||
"110492369808864 → Subscription -- node: sensor_fusion_node, tid: 210285, topic: /baro/alt\n",
|
||
"110492377005024 → Subscription -- node: telemetry_node, tid: 210285, topic: /sensors/fused\n",
|
||
"110492374009056 → Subscription -- node: flight_mgmt_node, tid: 210285, topic: /sensors/fused\n",
|
||
"110492360066032 → Subscription -- node: debayer_node, tid: 210285, topic: /camera/raw\n",
|
||
"110492373756400 → Subscription -- node: flight_mgmt_node, tid: 210285, topic: /lidar/scan\n"
|
||
]
|
||
}
|
||
],
|
||
"source": [
|
||
"callback_symbols = data_util.get_callback_symbols()\n",
|
||
"\n",
|
||
"def print_callback_info():\n",
|
||
" print(\"Callback object → symbol → owner info\\n\")\n",
|
||
" for obj, symbol in callback_symbols.items():\n",
|
||
" info = data_util.get_callback_owner_info(obj)\n",
|
||
" # fallback if for some reason Ros2DataModelUtil doesn’t know this one\n",
|
||
" if info is None:\n",
|
||
" info = \"[unknown]\"\n",
|
||
"\n",
|
||
" # We don't care about timers or the parameter events topic\n",
|
||
" if 'Timer -- tid:' in info or 'topic: /parameter_events' in info:\n",
|
||
" continue\n",
|
||
" \n",
|
||
" print(f\"{obj} → {info}\")\n",
|
||
"\n",
|
||
"print_callback_info()\n",
|
||
"\n",
|
||
"# find the object ID at runtime by matching node & topic\n",
|
||
"def find_cb(node, topic):\n",
|
||
" return next(\n",
|
||
" obj for obj in callback_symbols\n",
|
||
" if f\"node: {node}\" in data_util.get_callback_owner_info(obj)\n",
|
||
" and f\"topic: {topic}\" in data_util.get_callback_owner_info(obj)\n",
|
||
" )\n",
|
||
"\n",
|
||
"# === CONFIGURATION: define DAGs here ===\n",
|
||
"# For each logical chain, map each callback_object → list of successor callback_objects\n",
|
||
"\n",
|
||
"dags = {\n",
|
||
" \"image2ground_mapping\": {\n",
|
||
" find_cb(\"debayer_node\", \"/camera/raw\"): [find_cb(\"radiometric_node\", \"/camera/debayered\")],\n",
|
||
" find_cb(\"radiometric_node\", \"/camera/debayered\"): [find_cb(\"geometric_node\", \"/camera/radiometric\")],\n",
|
||
" find_cb(\"geometric_node\", \"/camera/radiometric\"): [find_cb(\"mapping_node\", \"/camera/geometric\")],\n",
|
||
" },\n",
|
||
" \"sematic_classification\": {\n",
|
||
" find_cb(\"debayer_node\", \"/camera/raw\"): [find_cb(\"radiometric_node\", \"/camera/debayered\")],\n",
|
||
" find_cb(\"radiometric_node\", \"/camera/debayered\"): [find_cb(\"smoke_classifier_node\", \"/camera/radiometric\")],\n",
|
||
" },\n",
|
||
" \"data_streaming\": {\n",
|
||
" find_cb(\"debayer_node\", \"/camera/raw\"): [find_cb(\"radiometric_node\", \"/camera/debayered\")],\n",
|
||
" find_cb(\"radiometric_node\", \"/camera/debayered\"): [find_cb(\"geometric_node\", \"/camera/radiometric\")],\n",
|
||
" find_cb(\"geometric_node\", \"/camera/radiometric\"): [find_cb(\"mapping_node\", \"/camera/geometric\")],\n",
|
||
" find_cb(\"mapping_node\", \"/camera/geometric\"): [find_cb(\"telemetry_node\", \"/camera/mapped\")],\n",
|
||
" # fuse sensors\n",
|
||
" find_cb(\"sensor_fusion_node\", \"/gps/fix\"): [find_cb(\"telemetry_node\", \"/sensors/fused\")],\n",
|
||
" find_cb(\"sensor_fusion_node\", \"/imu/data\"): [find_cb(\"telemetry_node\", \"/sensors/fused\")],\n",
|
||
" find_cb(\"sensor_fusion_node\", \"/baro/alt\"): [find_cb(\"telemetry_node\", \"/sensors/fused\")],\n",
|
||
" # fuse fused sensors and mapping\n",
|
||
" find_cb(\"telemetry_node\", \"/camera/mapped\"): [find_cb(\"radio_tx_node\", \"/telemetry/data\")],\n",
|
||
" find_cb(\"telemetry_node\", \"/sensors/fused\"): [find_cb(\"radio_tx_node\", \"/telemetry/data\")],\n",
|
||
" },\n",
|
||
" \"flight_control\": {\n",
|
||
" # fuse sensors\n",
|
||
" find_cb(\"sensor_fusion_node\", \"/gps/fix\"): [find_cb(\"flight_mgmt_node\", \"/sensors/fused\")],\n",
|
||
" find_cb(\"sensor_fusion_node\", \"/imu/data\"): [find_cb(\"flight_mgmt_node\", \"/sensors/fused\")],\n",
|
||
" find_cb(\"sensor_fusion_node\", \"/baro/alt\"): [find_cb(\"flight_mgmt_node\", \"/sensors/fused\")],\n",
|
||
" # fuse fused sensors, lidar and control\n",
|
||
" find_cb(\"flight_mgmt_node\", \"/lidar/scan\"): [find_cb(\"flight_control_node\", \"/flight/plan\")],\n",
|
||
" find_cb(\"flight_mgmt_node\", \"/sensors/fused\"): [find_cb(\"flight_control_node\", \"/flight/plan\")],\n",
|
||
" # ToDo: remote control or autonomous flight plan\n",
|
||
" find_cb(\"flight_mgmt_node\", \"/operator/commands\"): [find_cb(\"flight_control_node\", \"/flight/plan\")],\n",
|
||
" }\n",
|
||
"}"
|
||
]
|
||
},
|
||
{
|
||
"cell_type": "code",
|
||
"execution_count": 12,
|
||
"metadata": {},
|
||
"outputs": [
|
||
{
|
||
"name": "stdout",
|
||
"output_type": "stream",
|
||
"text": [
|
||
"Sample 'ros2:callback_start' events:\n",
|
||
"[{'_name': 'ros2:callback_start',\n",
|
||
" '_timestamp': 1747402916746588396,\n",
|
||
" 'callback': 110492359050048,\n",
|
||
" 'cpu_id': 5,\n",
|
||
" 'is_intra_process': 0,\n",
|
||
" 'procname': 'full_topology',\n",
|
||
" 'vpid': 210285,\n",
|
||
" 'vtid': 210305},\n",
|
||
" {'_name': 'ros2:callback_start',\n",
|
||
" '_timestamp': 1747402916746626810,\n",
|
||
" 'callback': 110492367069024,\n",
|
||
" 'cpu_id': 4,\n",
|
||
" 'is_intra_process': 0,\n",
|
||
" 'procname': 'full_topology',\n",
|
||
" 'vpid': 210285,\n",
|
||
" 'vtid': 210300},\n",
|
||
" {'_name': 'ros2:callback_start',\n",
|
||
" '_timestamp': 1747402916746699511,\n",
|
||
" 'callback': 110492361080960,\n",
|
||
" 'cpu_id': 4,\n",
|
||
" 'is_intra_process': 0,\n",
|
||
" 'procname': 'full_topology',\n",
|
||
" 'vpid': 210285,\n",
|
||
" 'vtid': 210300},\n",
|
||
" {'_name': 'ros2:callback_start',\n",
|
||
" '_timestamp': 1747402916746699675,\n",
|
||
" 'callback': 110492358927152,\n",
|
||
" 'cpu_id': 5,\n",
|
||
" 'is_intra_process': 0,\n",
|
||
" 'procname': 'full_topology',\n",
|
||
" 'vpid': 210285,\n",
|
||
" 'vtid': 210305},\n",
|
||
" {'_name': 'ros2:callback_start',\n",
|
||
" '_timestamp': 1747402916746699821,\n",
|
||
" 'callback': 110492359968384,\n",
|
||
" 'cpu_id': 7,\n",
|
||
" 'is_intra_process': 0,\n",
|
||
" 'procname': 'full_topology',\n",
|
||
" 'vpid': 210285,\n",
|
||
" 'vtid': 210302}]\n",
|
||
"Path you loaded: /workspaces/ROS-Dynamic-Executor-Experiments/analysis/tracing/full_topology_tracing-20250516134156/ust/converted\n",
|
||
"Columns in callback_instances:\n",
|
||
"['callback_object', 'timestamp', 'duration', 'intra_process']\n"
|
||
]
|
||
}
|
||
],
|
||
"source": [
|
||
"import pprint\n",
|
||
"\n",
|
||
"start_samples = [ev for ev in events if ev.get('_name') == 'ros2:callback_start'][:5]\n",
|
||
"print(\"Sample 'ros2:callback_start' events:\")\n",
|
||
"pprint.pprint(start_samples)\n",
|
||
"\n",
|
||
"print(\"Path you loaded:\", path)\n",
|
||
"print(\"Columns in callback_instances:\")\n",
|
||
"print(handler.data.callback_instances.columns.tolist())\n"
|
||
]
|
||
},
|
||
{
|
||
"cell_type": "code",
|
||
"execution_count": 13,
|
||
"metadata": {},
|
||
"outputs": [
|
||
{
|
||
"ename": "KeyError",
|
||
"evalue": "\"['message_id'] not in index\"",
|
||
"output_type": "error",
|
||
"traceback": [
|
||
"\u001b[0;31m---------------------------------------------------------------------------\u001b[0m",
|
||
"\u001b[0;31mKeyError\u001b[0m Traceback (most recent call last)",
|
||
"Cell \u001b[0;32mIn[13], line 10\u001b[0m\n\u001b[1;32m 6\u001b[0m colour_i \u001b[38;5;241m=\u001b[39m \u001b[38;5;241m0\u001b[39m\n\u001b[1;32m 8\u001b[0m \u001b[38;5;28;01mfor\u001b[39;00m chain_name, seq \u001b[38;5;129;01min\u001b[39;00m dags\u001b[38;5;241m.\u001b[39mitems():\n\u001b[1;32m 9\u001b[0m \u001b[38;5;66;03m# 1) pull invocations for each callback\u001b[39;00m\n\u001b[0;32m---> 10\u001b[0m node_tables \u001b[38;5;241m=\u001b[39m {\n\u001b[1;32m 11\u001b[0m obj: handler\u001b[38;5;241m.\u001b[39mdata\u001b[38;5;241m.\u001b[39mcallback_instances[\n\u001b[1;32m 12\u001b[0m handler\u001b[38;5;241m.\u001b[39mdata\u001b[38;5;241m.\u001b[39mcallback_instances[\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mcallback_object\u001b[39m\u001b[38;5;124m\"\u001b[39m] \u001b[38;5;241m==\u001b[39m obj\n\u001b[1;32m 13\u001b[0m ][[\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mmessage_id\u001b[39m\u001b[38;5;124m\"\u001b[39m,\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mtimestamp\u001b[39m\u001b[38;5;124m\"\u001b[39m]]\n\u001b[1;32m 14\u001b[0m \u001b[38;5;28;01mfor\u001b[39;00m obj \u001b[38;5;129;01min\u001b[39;00m seq\n\u001b[1;32m 15\u001b[0m }\n\u001b[1;32m 17\u001b[0m \u001b[38;5;66;03m# 2) keep only message_ids that appear in *every* stage\u001b[39;00m\n\u001b[1;32m 18\u001b[0m common_ids \u001b[38;5;241m=\u001b[39m \u001b[38;5;28mset\u001b[39m\u001b[38;5;241m.\u001b[39mintersection(\n\u001b[1;32m 19\u001b[0m \u001b[38;5;241m*\u001b[39m(\u001b[38;5;28mset\u001b[39m(t[\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mmessage_id\u001b[39m\u001b[38;5;124m\"\u001b[39m]) \u001b[38;5;28;01mfor\u001b[39;00m t \u001b[38;5;129;01min\u001b[39;00m node_tables\u001b[38;5;241m.\u001b[39mvalues())\n\u001b[1;32m 20\u001b[0m )\n",
|
||
"Cell \u001b[0;32mIn[13], line 11\u001b[0m, in \u001b[0;36m<dictcomp>\u001b[0;34m(.0)\u001b[0m\n\u001b[1;32m 6\u001b[0m colour_i \u001b[38;5;241m=\u001b[39m \u001b[38;5;241m0\u001b[39m\n\u001b[1;32m 8\u001b[0m \u001b[38;5;28;01mfor\u001b[39;00m chain_name, seq \u001b[38;5;129;01min\u001b[39;00m dags\u001b[38;5;241m.\u001b[39mitems():\n\u001b[1;32m 9\u001b[0m \u001b[38;5;66;03m# 1) pull invocations for each callback\u001b[39;00m\n\u001b[1;32m 10\u001b[0m node_tables \u001b[38;5;241m=\u001b[39m {\n\u001b[0;32m---> 11\u001b[0m obj: \u001b[43mhandler\u001b[49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43mdata\u001b[49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43mcallback_instances\u001b[49m\u001b[43m[\u001b[49m\n\u001b[1;32m 12\u001b[0m \u001b[43m \u001b[49m\u001b[43mhandler\u001b[49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43mdata\u001b[49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43mcallback_instances\u001b[49m\u001b[43m[\u001b[49m\u001b[38;5;124;43m\"\u001b[39;49m\u001b[38;5;124;43mcallback_object\u001b[39;49m\u001b[38;5;124;43m\"\u001b[39;49m\u001b[43m]\u001b[49m\u001b[43m \u001b[49m\u001b[38;5;241;43m==\u001b[39;49m\u001b[43m \u001b[49m\u001b[43mobj\u001b[49m\n\u001b[1;32m 13\u001b[0m \u001b[43m \u001b[49m\u001b[43m]\u001b[49m\u001b[43m[\u001b[49m\u001b[43m[\u001b[49m\u001b[38;5;124;43m\"\u001b[39;49m\u001b[38;5;124;43mmessage_id\u001b[39;49m\u001b[38;5;124;43m\"\u001b[39;49m\u001b[43m,\u001b[49m\u001b[38;5;124;43m\"\u001b[39;49m\u001b[38;5;124;43mtimestamp\u001b[39;49m\u001b[38;5;124;43m\"\u001b[39;49m\u001b[43m]\u001b[49m\u001b[43m]\u001b[49m\n\u001b[1;32m 14\u001b[0m \u001b[38;5;28;01mfor\u001b[39;00m obj \u001b[38;5;129;01min\u001b[39;00m seq\n\u001b[1;32m 15\u001b[0m }\n\u001b[1;32m 17\u001b[0m \u001b[38;5;66;03m# 2) keep only message_ids that appear in *every* stage\u001b[39;00m\n\u001b[1;32m 18\u001b[0m common_ids \u001b[38;5;241m=\u001b[39m \u001b[38;5;28mset\u001b[39m\u001b[38;5;241m.\u001b[39mintersection(\n\u001b[1;32m 19\u001b[0m \u001b[38;5;241m*\u001b[39m(\u001b[38;5;28mset\u001b[39m(t[\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mmessage_id\u001b[39m\u001b[38;5;124m\"\u001b[39m]) \u001b[38;5;28;01mfor\u001b[39;00m t \u001b[38;5;129;01min\u001b[39;00m node_tables\u001b[38;5;241m.\u001b[39mvalues())\n\u001b[1;32m 20\u001b[0m )\n",
|
||
"File \u001b[0;32m/workspaces/ROS-Dynamic-Executor-Experiments/venv38/lib/python3.8/site-packages/pandas/core/frame.py:3767\u001b[0m, in \u001b[0;36mDataFrame.__getitem__\u001b[0;34m(self, key)\u001b[0m\n\u001b[1;32m 3765\u001b[0m \u001b[38;5;28;01mif\u001b[39;00m is_iterator(key):\n\u001b[1;32m 3766\u001b[0m key \u001b[38;5;241m=\u001b[39m \u001b[38;5;28mlist\u001b[39m(key)\n\u001b[0;32m-> 3767\u001b[0m indexer \u001b[38;5;241m=\u001b[39m \u001b[38;5;28;43mself\u001b[39;49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43mcolumns\u001b[49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43m_get_indexer_strict\u001b[49m\u001b[43m(\u001b[49m\u001b[43mkey\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[38;5;124;43m\"\u001b[39;49m\u001b[38;5;124;43mcolumns\u001b[39;49m\u001b[38;5;124;43m\"\u001b[39;49m\u001b[43m)\u001b[49m[\u001b[38;5;241m1\u001b[39m]\n\u001b[1;32m 3769\u001b[0m \u001b[38;5;66;03m# take() does not accept boolean indexers\u001b[39;00m\n\u001b[1;32m 3770\u001b[0m \u001b[38;5;28;01mif\u001b[39;00m \u001b[38;5;28mgetattr\u001b[39m(indexer, \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mdtype\u001b[39m\u001b[38;5;124m\"\u001b[39m, \u001b[38;5;28;01mNone\u001b[39;00m) \u001b[38;5;241m==\u001b[39m \u001b[38;5;28mbool\u001b[39m:\n",
|
||
"File \u001b[0;32m/workspaces/ROS-Dynamic-Executor-Experiments/venv38/lib/python3.8/site-packages/pandas/core/indexes/base.py:5877\u001b[0m, in \u001b[0;36mIndex._get_indexer_strict\u001b[0;34m(self, key, axis_name)\u001b[0m\n\u001b[1;32m 5874\u001b[0m \u001b[38;5;28;01melse\u001b[39;00m:\n\u001b[1;32m 5875\u001b[0m keyarr, indexer, new_indexer \u001b[38;5;241m=\u001b[39m \u001b[38;5;28mself\u001b[39m\u001b[38;5;241m.\u001b[39m_reindex_non_unique(keyarr)\n\u001b[0;32m-> 5877\u001b[0m \u001b[38;5;28;43mself\u001b[39;49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43m_raise_if_missing\u001b[49m\u001b[43m(\u001b[49m\u001b[43mkeyarr\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[43mindexer\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[43maxis_name\u001b[49m\u001b[43m)\u001b[49m\n\u001b[1;32m 5879\u001b[0m keyarr \u001b[38;5;241m=\u001b[39m \u001b[38;5;28mself\u001b[39m\u001b[38;5;241m.\u001b[39mtake(indexer)\n\u001b[1;32m 5880\u001b[0m \u001b[38;5;28;01mif\u001b[39;00m \u001b[38;5;28misinstance\u001b[39m(key, Index):\n\u001b[1;32m 5881\u001b[0m \u001b[38;5;66;03m# GH 42790 - Preserve name from an Index\u001b[39;00m\n",
|
||
"File \u001b[0;32m/workspaces/ROS-Dynamic-Executor-Experiments/venv38/lib/python3.8/site-packages/pandas/core/indexes/base.py:5941\u001b[0m, in \u001b[0;36mIndex._raise_if_missing\u001b[0;34m(self, key, indexer, axis_name)\u001b[0m\n\u001b[1;32m 5938\u001b[0m \u001b[38;5;28;01mraise\u001b[39;00m \u001b[38;5;167;01mKeyError\u001b[39;00m(\u001b[38;5;124mf\u001b[39m\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mNone of [\u001b[39m\u001b[38;5;132;01m{\u001b[39;00mkey\u001b[38;5;132;01m}\u001b[39;00m\u001b[38;5;124m] are in the [\u001b[39m\u001b[38;5;132;01m{\u001b[39;00maxis_name\u001b[38;5;132;01m}\u001b[39;00m\u001b[38;5;124m]\u001b[39m\u001b[38;5;124m\"\u001b[39m)\n\u001b[1;32m 5940\u001b[0m not_found \u001b[38;5;241m=\u001b[39m \u001b[38;5;28mlist\u001b[39m(ensure_index(key)[missing_mask\u001b[38;5;241m.\u001b[39mnonzero()[\u001b[38;5;241m0\u001b[39m]]\u001b[38;5;241m.\u001b[39munique())\n\u001b[0;32m-> 5941\u001b[0m \u001b[38;5;28;01mraise\u001b[39;00m \u001b[38;5;167;01mKeyError\u001b[39;00m(\u001b[38;5;124mf\u001b[39m\u001b[38;5;124m\"\u001b[39m\u001b[38;5;132;01m{\u001b[39;00mnot_found\u001b[38;5;132;01m}\u001b[39;00m\u001b[38;5;124m not in index\u001b[39m\u001b[38;5;124m\"\u001b[39m)\n",
|
||
"\u001b[0;31mKeyError\u001b[0m: \"['message_id'] not in index\""
|
||
]
|
||
}
|
||
],
|
||
"source": [
|
||
"import numpy as np, pandas as pd\n",
|
||
"from bokeh.plotting import figure, show\n",
|
||
"from bokeh.layouts import row\n",
|
||
"from bokeh.models import ColumnDataSource, DatetimeTickFormatter\n",
|
||
"\n",
|
||
"colour_i = 0\n",
|
||
"\n",
|
||
"for chain_name, seq in dags.items():\n",
|
||
" # 1) pull invocations for each callback\n",
|
||
" node_tables = {\n",
|
||
" obj: handler.data.callback_instances[\n",
|
||
" handler.data.callback_instances[\"callback_object\"] == obj\n",
|
||
" ][[\"message_id\",\"timestamp\"]]\n",
|
||
" for obj in seq\n",
|
||
" }\n",
|
||
"\n",
|
||
" # 2) keep only message_ids that appear in *every* stage\n",
|
||
" common_ids = set.intersection(\n",
|
||
" *(set(t[\"message_id\"]) for t in node_tables.values())\n",
|
||
" )\n",
|
||
" if not common_ids:\n",
|
||
" print(f\"⚠️ no complete messages for '{chain_name}'\")\n",
|
||
" continue\n",
|
||
"\n",
|
||
" # 3) for each message_id compute Δt = last − first\n",
|
||
" rows = []\n",
|
||
" for mid in common_ids:\n",
|
||
" start_time = node_tables[seq[0]].loc[\n",
|
||
" node_tables[seq[0]][\"message_id\"]==mid,\"timestamp\"\n",
|
||
" ].iloc[0]\n",
|
||
" end_time = node_tables[seq[-1]].loc[\n",
|
||
" node_tables[seq[-1]][\"message_id\"]==mid,\"timestamp\"\n",
|
||
" ].iloc[0]\n",
|
||
" rows.append({\"timestamp\": start_time,\n",
|
||
" \"latency\": (end_time-start_time).total_seconds()*1e3})\n",
|
||
"\n",
|
||
" df = pd.DataFrame(rows)\n",
|
||
" avg, jitter = df[\"latency\"].mean(), df[\"latency\"].std()\n",
|
||
"\n",
|
||
" # --- plotting (same style as your notebook) ---\n",
|
||
" src = ColumnDataSource(df)\n",
|
||
" p = figure(\n",
|
||
" title=f\"{chain_name}\\nAvg {avg:.2f} ms | Jitter {jitter:.2f} ms\",\n",
|
||
" x_axis_label=f\"first stage start ({df['timestamp'].min().strftime('%Y-%m-%d %H:%M')})\",\n",
|
||
" y_axis_label=\"latency (ms)\",\n",
|
||
" width=psize, height=psize,\n",
|
||
" )\n",
|
||
" p.line(\"timestamp\",\"latency\", source=src,\n",
|
||
" line_width=2, line_color=colours[colour_i])\n",
|
||
" p.xaxis[0].formatter = DatetimeTickFormatter(seconds=\"%Ss\")\n",
|
||
"\n",
|
||
" hist, edges = np.histogram(df[\"latency\"], bins=\"auto\")\n",
|
||
" h = figure(title=\"Latency histogram\",\n",
|
||
" x_axis_label=\"latency (ms)\", y_axis_label=\"frequency\",\n",
|
||
" width=psize, height=psize)\n",
|
||
" h.quad(bottom=0, top=hist,\n",
|
||
" left=edges[:-1], right=edges[1:],\n",
|
||
" fill_color=colours[colour_i], line_color=colours[colour_i])\n",
|
||
"\n",
|
||
" show(row(p, h))\n",
|
||
" colour_i = (colour_i + 1) % len(colours)\n"
|
||
]
|
||
}
|
||
],
|
||
"metadata": {
|
||
"kernelspec": {
|
||
"display_name": "venv38",
|
||
"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",
|
||
"version": "3.8.10"
|
||
}
|
||
},
|
||
"nbformat": 4,
|
||
"nbformat_minor": 2
|
||
}
|