Merge branch '18-implement-memory-usage-analysis' into 'master'

Implement userspace memory usage analysis

Closes #18

See merge request micro-ROS/ros_tracing/tracetools_analysis!27
This commit is contained in:
Christophe Bedard 2019-12-27 21:41:23 +00:00
commit db1e0ffa65
9 changed files with 563 additions and 1 deletions

View file

@ -0,0 +1,158 @@
{
"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",
"# AND\n",
"# Convert trace data:\n",
"# $ ros2 trace-analysis convert ~/.ros/tracing/memory-usage/ust"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"converted_file_path = '~/.ros/tracing/memory-usage/ust/converted'"
]
},
{
"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.layouts import row\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 MemoryUsageHandler\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(converted_file_path)\n",
"memory_handler = MemoryUsageHandler()\n",
"ros2_handler = Ros2Handler()\n",
"Processor(memory_handler, ros2_handler).process(events)"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"memory_data_util = MemoryUsageDataModelUtil(memory_handler.data)\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",
"memory_usage_dfs = memory_data_util.get_absolute_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 = memory_usage_dfs[first_tid].loc[:, 'timestamp'].iloc[0].strftime('%Y-%m-%d %H:%M')\n",
"memory = figure(\n",
" title='Userspace 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, memory_usage_df in memory_usage_dfs.items():\n",
" if tid not in tids:\n",
" continue\n",
" memory.line(\n",
" x='timestamp',\n",
" y='memory_usage',\n",
" legend=str(tid) + ' ' + str(ros2_data_util.get_node_names_from_tid(tid)),\n",
" line_width=2,\n",
" source=ColumnDataSource(memory_usage_df),\n",
" line_color=colours[i_colour],\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
}

View file

@ -0,0 +1,48 @@
# Copyright 2019 Robert Bosch GmbH
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
"""Example launch file for a memory_usage analysis."""
from launch import LaunchDescription
from launch_ros.actions import Node
from tracetools_launch.action import Trace
from tracetools_trace.tools.names import DEFAULT_EVENTS_ROS
def generate_launch_description():
return LaunchDescription([
Trace(
session_name='memory-usage',
events_ust=[
'lttng_ust_libc:malloc',
'lttng_ust_libc:calloc',
'lttng_ust_libc:realloc',
'lttng_ust_libc:free',
'lttng_ust_libc:memalign',
'lttng_ust_libc:posix_memalign',
] + DEFAULT_EVENTS_ROS,
),
Node(
package='tracetools_test',
node_executable='test_ping',
arguments=['do_more'],
output='screen',
),
Node(
package='tracetools_test',
node_executable='test_pong',
arguments=['do_more'],
output='screen',
),
])

View file

@ -43,7 +43,8 @@ setup(
'console_scripts': [
f'convert = {package_name}.convert:main',
f'process = {package_name}.process:main',
f'cb_durations = {package_name}.scripts.cb_durations:main'
f'cb_durations = {package_name}.scripts.cb_durations:main',
f'memory_usage = {package_name}.scripts.memory_usage:main',
],
},
license='Apache 2.0',

View file

@ -0,0 +1,56 @@
# Copyright 2019 Apex.AI, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
"""Module for memory usage data model."""
import pandas as pd
from . import DataModel
class MemoryUsageDataModel(DataModel):
"""
Container to model pre-processed memory usage data for analysis.
Contains changes in memory allocation (e.g. + for malloc, - for free) with the corresponding
timestamp.
"""
def __init__(self) -> None:
"""Create a MemoryUsageDataModel."""
super().__init__()
self.memory_diff = pd.DataFrame(columns=[
'timestamp',
'tid',
'memory_diff',
])
def add_memory_difference(
self,
timestamp: int,
tid: int,
memory_diff: int,
) -> None:
data = {
'timestamp': timestamp,
'tid': tid,
'memory_diff': memory_diff,
}
self.memory_diff = self.memory_diff.append(data, ignore_index=True)
def print_data(self) -> None:
print('==================MEMORY USAGE DATA MODEL==================')
tail = 20
print(f'Memory difference (tail={tail}):\n{self.times.tail(tail).to_string()}')
print('===========================================================')

View file

@ -0,0 +1,152 @@
# Copyright 2019 Apex.AI, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
"""Module for memory usage events processing."""
from typing import Dict
from tracetools_read import get_field
from . import EventHandler
from . import EventMetadata
from ..data_model.memory_usage import MemoryUsageDataModel
class MemoryUsageHandler(EventHandler):
"""
Handler that extracts data for memory usage.
It uses the following events:
* lttng_ust_libc:malloc
* lttng_ust_libc:calloc
* lttng_ust_libc:realloc
* lttng_ust_libc:free
* lttng_ust_libc:memalign
* lttng_ust_libc:posix_memalign
The above events are generated when LD_PRELOAD-ing liblttng-ust-libc-wrapper.so, see:
https://lttng.org/docs/v2.10/#doc-liblttng-ust-libc-pthread-wrapper
Implementation inspired by Trace Compass' implementation:
https://git.eclipse.org/c/tracecompass/org.eclipse.tracecompass.git/tree/lttng/org.eclipse.tracecompass.lttng2.ust.core/src/org/eclipse/tracecompass/internal/lttng2/ust/core/analysis/memory/UstMemoryStateProvider.java#n161
"""
def __init__(
self,
**kwargs,
) -> None:
# Link event to handling method
handler_map = {
'lttng_ust_libc:malloc':
self._handle_malloc,
'lttng_ust_libc:calloc':
self._handle_calloc,
'lttng_ust_libc:realloc':
self._handle_realloc,
'lttng_ust_libc:free':
self._handle_free,
'lttng_ust_libc:memalign':
self._handle_memalign,
'lttng_ust_libc:posix_memalign':
self._handle_posix_memalign,
}
super().__init__(
handler_map=handler_map,
**kwargs,
)
self._data_model = MemoryUsageDataModel()
# Temporary buffers
# pointer -> current memory size
# (used to know keep track of the memory size allocated at a given pointer)
self._memory: Dict[int, int] = {}
@property
def data(self) -> MemoryUsageDataModel:
return self._data_model
def _handle_malloc(
self, event: Dict, metadata: EventMetadata
) -> None:
ptr = get_field(event, 'ptr')
if ptr != 0:
size = get_field(event, 'size')
self._handle(event, metadata, ptr, size)
def _handle_calloc(
self, event: Dict, metadata: EventMetadata
) -> None:
ptr = get_field(event, 'ptr')
if ptr != 0:
nmemb = get_field(event, 'nmemb')
size = get_field(event, 'size')
self._handle(event, metadata, ptr, size * nmemb)
def _handle_realloc(
self, event: Dict, metadata: EventMetadata
) -> None:
ptr = get_field(event, 'ptr')
if ptr != 0:
new_ptr = get_field(event, 'in_ptr')
size = get_field(event, 'size')
self._handle(event, metadata, ptr, 0)
self._handle(event, metadata, new_ptr, size)
def _handle_free(
self, event: Dict, metadata: EventMetadata
) -> None:
ptr = get_field(event, 'ptr')
if ptr != 0:
self._handle(event, metadata, ptr, 0)
def _handle_memalign(
self, event: Dict, metadata: EventMetadata
) -> None:
ptr = get_field(event, 'ptr')
if ptr != 0:
size = get_field(event, 'size')
self._handle(event, metadata, ptr, size)
def _handle_posix_memalign(
self, event: Dict, metadata: EventMetadata
) -> None:
ptr = get_field(event, 'out_ptr')
if ptr != 0:
size = get_field(event, 'size')
self._handle(event, metadata, ptr, size)
def _handle(
self,
event: Dict,
metadata: EventMetadata,
ptr: int,
size: int,
) -> None:
timestamp = metadata.timestamp
tid = metadata.tid
memory_difference = size
# Store the size allocated for the given pointer
if memory_difference != 0:
self._memory[ptr] = memory_difference
else:
# Othersize, if size is 0, it means it was deleted
# Try to fetch the size stored previously
allocated_memory = self._memory.get(ptr, None)
if allocated_memory is not None:
memory_difference = -allocated_memory
# Add to data model
self.data.add_memory_difference(timestamp, tid, memory_difference)

View file

@ -36,6 +36,10 @@ class ProfileHandler(EventHandler):
* lttng_ust_cyg_profile_fast:func_exit
* sched_switch
The above events are generated when using -finstrument-functions with gcc and LD_PRELOAD-ing
liblttng-ust-cyg-profile-fast.so, see:
https://lttng.org/docs/v2.10/#doc-liblttng-ust-cyg-profile
TODO get debug_info from babeltrace for
lttng_ust_cyg_profile_fast:func_entry events
(or resolve { address -> function } name another way)

View file

@ -0,0 +1,67 @@
# Copyright 2019 Apex.AI, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
import sys
import pandas as pd
from tracetools_analysis.loading import load_file
from tracetools_analysis.processor import Processor
from tracetools_analysis.processor.memory_usage import MemoryUsageHandler
from tracetools_analysis.processor.ros2 import Ros2Handler
from tracetools_analysis.utils.memory_usage import MemoryUsageDataModelUtil
from tracetools_analysis.utils.ros2 import Ros2DataModelUtil
# From: https://stackoverflow.com/a/32009595/6476709
def format_memory_size(size: int, precision: int = 2):
suffixes = ['B', 'KB', 'MB', 'GB', 'TB']
suffixIndex = 0
while size > 1024 and suffixIndex < 4:
# Increment the index of the suffix
suffixIndex += 1
# Apply the division
size = size / 1024.0
return f'{size:.{precision}f} {suffixes[suffixIndex]}'
def main():
if len(sys.argv) < 2:
print('Syntax: <converted tracefile>')
sys.exit(-1)
file_path = sys.argv[1]
events = load_file(file_path)
memory_handler = MemoryUsageHandler()
ros2_handler = Ros2Handler()
Processor(memory_handler, ros2_handler).process(events)
memory_data_util = MemoryUsageDataModelUtil(memory_handler.data)
ros2_data_util = Ros2DataModelUtil(ros2_handler.data)
memory_usage_dfs = memory_data_util.get_absolute_memory_usage_by_tid()
tids = ros2_data_util.get_tids()
data = [
[
tid,
ros2_data_util.get_node_names_from_tid(tid),
format_memory_size(memory_usage['memory_usage'].max(), precision=1),
]
for tid, memory_usage in memory_usage_dfs.items()
if tid in tids
]
summary_df = pd.DataFrame(data, columns=['tid', 'node_names', 'max_memory_usage'])
print('\n\n' + summary_df.to_string(index=False))

View file

@ -0,0 +1,72 @@
# Copyright 2019 Apex.AI, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
"""Module for memory usage data model utils."""
from collections import defaultdict
from typing import Dict
from pandas import DataFrame
from . import DataModelUtil
from ..data_model.memory_usage import MemoryUsageDataModel
class MemoryUsageDataModelUtil(DataModelUtil):
"""Memory usage data model utility class."""
def __init__(
self,
data_model: MemoryUsageDataModel,
) -> None:
"""
Create a MemoryUsageDataModelUtil.
:param data_model: the data model object to use
"""
super().__init__(data_model)
def get_absolute_memory_usage_by_tid(self) -> Dict[int, DataFrame]:
"""
Get absolute memory usage over time per tid.
:return (tid -> DataFrame of absolute memory usage over time)
"""
previous = defaultdict(int)
data = defaultdict(list)
for index, row in self.data.memory_diff.iterrows():
timestamp = row['timestamp']
tid = int(row['tid'])
diff = row['memory_diff']
previous_value = previous[tid]
next_value = previous_value + diff
data[tid].append({
'timestamp': timestamp,
'tid': tid,
'memory_usage': previous_value,
})
data[tid].append({
'timestamp': timestamp,
'tid': tid,
'memory_usage': next_value,
})
previous[tid] = next_value
return {
tid: self.convert_time_columns(
DataFrame(data[tid], columns=['timestamp', 'tid', 'memory_usage']),
columns_ns_to_datetime=['timestamp'],
inplace=True,
)
for tid in data
}

View file

@ -114,6 +114,10 @@ class Ros2DataModelUtil(DataModelUtil):
obj: self._prettify(callback_symbols.loc[obj, 'symbol']) for obj in callback_objects
}
def get_tids(self) -> List[str]:
"""Get a list of thread ids corresponding to the nodes."""
return self.data.nodes['tid'].unique().tolist()
def get_callback_durations(
self,
callback_obj: int,