tracetools_analysis/tracetools_analysis/analysis/memory_usage.ipynb
2019-12-29 14:25:08 -05:00

173 lines
5.2 KiB
Text

{
"cells": [
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"# Memory usage\n",
"#\n",
"# Get trace data using the provided launch file:\n",
"# $ ros2 launch tracetools_analysis memory_usage.launch.py\n",
"# (wait a few seconds, then kill with Ctrl+C)\n",
"#\n",
"# (optional) convert trace data:\n",
"# $ ros2 trace-analysis convert ~/.ros/tracing/memory-usage"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"path = '~/.ros/tracing/memory-usage'"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"import sys\n",
"# Assuming a workspace with:\n",
"# src/tracetools_analysis/\n",
"# src/micro-ROS/ros_tracing/ros2_tracing/tracetools_read/\n",
"sys.path.insert(0, '../')\n",
"sys.path.insert(0, '../../../micro-ROS/ros_tracing/ros2_tracing/tracetools_read/')\n",
"import datetime as dt\n",
"\n",
"from bokeh.palettes import viridis\n",
"from bokeh.plotting import figure\n",
"from bokeh.plotting import output_notebook\n",
"from bokeh.io import show\n",
"from bokeh.models import ColumnDataSource\n",
"from bokeh.models import DatetimeTickFormatter\n",
"from bokeh.models import NumeralTickFormatter\n",
"import numpy as np\n",
"import pandas as pd\n",
"\n",
"from tracetools_analysis.loading import load_file\n",
"from tracetools_analysis.processor import Processor\n",
"from tracetools_analysis.processor.memory_usage import KernelMemoryUsageHandler\n",
"from tracetools_analysis.processor.memory_usage import UserspaceMemoryUsageHandler\n",
"from tracetools_analysis.processor.ros2 import Ros2Handler\n",
"from tracetools_analysis.utils.memory_usage import MemoryUsageDataModelUtil\n",
"from tracetools_analysis.utils.ros2 import Ros2DataModelUtil"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"# Process\n",
"events = load_file(path)\n",
"ust_memory_handler = UserspaceMemoryUsageHandler()\n",
"kernel_memory_handler = KernelMemoryUsageHandler()\n",
"ros2_handler = Ros2Handler()\n",
"Processor(ust_memory_handler, kernel_memory_handler, ros2_handler).process(events)"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"memory_data_util = MemoryUsageDataModelUtil(\n",
" userspace=ust_memory_handler.data,\n",
" kernel=kernel_memory_handler.data,\n",
")\n",
"ros2_data_util = Ros2DataModelUtil(ros2_handler.data)\n",
"\n",
"output_notebook()\n",
"psize = 650"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"# Plot memory usage\n",
"ust_memory_usage_dfs = memory_data_util.get_absolute_userspace_memory_usage_by_tid()\n",
"kernel_memory_usage_dfs = memory_data_util.get_absolute_kernel_memory_usage_by_tid()\n",
"tids = ros2_data_util.get_tids()\n",
"\n",
"colours = viridis(len(tids) + 1)\n",
"first_tid = min(tids)\n",
"starttime = ust_memory_usage_dfs[first_tid].loc[:, 'timestamp'].iloc[0].strftime('%Y-%m-%d %H:%M')\n",
"memory = figure(\n",
" title='Memory usage per thread/node',\n",
" x_axis_label=f'time ({starttime})',\n",
" y_axis_label='memory usage',\n",
" plot_width=psize, plot_height=psize,\n",
")\n",
"\n",
"i_colour = 0\n",
"for tid in tids:\n",
" legend = str(tid) + ' ' + str(ros2_data_util.get_node_names_from_tid(tid))\n",
" # Userspace\n",
" memory.line(\n",
" x='timestamp',\n",
" y='memory_usage',\n",
" legend=legend + ' (ust)',\n",
" line_width=2,\n",
" source=ColumnDataSource(ust_memory_usage_dfs[tid]),\n",
" line_color=colours[i_colour],\n",
" )\n",
" # Kernel\n",
" memory.line(\n",
" x='timestamp',\n",
" y='memory_usage',\n",
" legend=legend + ' (kernel)',\n",
" line_width=2,\n",
" source=ColumnDataSource(kernel_memory_usage_dfs[tid]),\n",
" line_color=colours[i_colour],\n",
" line_dash='dotted',\n",
" )\n",
" i_colour += 1\n",
"\n",
"memory.title.align = 'center'\n",
"memory.legend.label_text_font_size = '11px'\n",
"memory.xaxis[0].formatter = DatetimeTickFormatter(seconds=['%Ss'])\n",
"memory.yaxis[0].formatter = NumeralTickFormatter(format='0.0b')\n",
"\n",
"show(memory)"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": []
}
],
"metadata": {
"kernelspec": {
"display_name": "Python 3",
"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.6.9"
}
},
"nbformat": 4,
"nbformat_minor": 2
}