Skip to content

Commit

Permalink
Merge pull request #1 from RobotecAI/refactor
Browse files Browse the repository at this point in the history
PEP8 issues refactor, rosbag2_benchmarking package info updated.
  • Loading branch information
adamdbrw authored Jun 23, 2020
2 parents f8b19bd + 00ca87f commit 1bab689
Show file tree
Hide file tree
Showing 10 changed files with 706 additions and 357 deletions.
1 change: 1 addition & 0 deletions rosbag2_performance/rosbag2_benchmarking/.gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
*__pycache__*
343 changes: 219 additions & 124 deletions rosbag2_performance/rosbag2_benchmarking/launch/benchmarking.launch.py

Large diffs are not rendered by default.

6 changes: 3 additions & 3 deletions rosbag2_performance/rosbag2_benchmarking/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,10 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>rosbag2_benchmarking</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<version>0.1.0</version>
<description>Benchmarking tools for rosbag2</description>
<maintainer email="jaroszekpiotr@gmail.com">pjaroszek</maintainer>
<license>TODO: License declaration</license>
<license>Apache License 2.0</license>

<exec_depend>rclpy</exec_depend>
<exec_depend>std_msgs</exec_depend>
Expand Down
106 changes: 76 additions & 30 deletions rosbag2_performance/rosbag2_benchmarking/plotting/plot_logging_data.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,30 +4,31 @@
# 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
# 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 os, pathlib, re
import matplotlib.pyplot as plt
import numpy as np
import sys
import argparse
import os
import pathlib
import re

import matplotlib.pyplot as plt

full_path = os.path.realpath(__file__)
path, filename = os.path.split(full_path)
filename = "record.1000.100.1000.txt"
filename = 'record.1000.100.1000.txt'

parser = argparse.ArgumentParser()
parser.add_argument('-i', '--input')
args = parser.parse_args()
filename = args.input

print("processing file " + filename)
print('processing file ' + filename)

raport_path = pathlib.Path(path).joinpath(filename)

Expand All @@ -37,33 +38,43 @@
insert_start_times = []
insert_end_times = []

with open(str(raport_path), "r") as raport1:
with open(str(raport_path), 'r') as raport1:
first_line = raport1.readline()
start_time = float(re.search('([0-9]*\.[0-9]*).*', first_line).group(1))
start_time = float(re.search(r'([0-9]*\.[0-9]*).*', first_line).group(1))
print(start_time)

lines = raport1.readlines()
for line in [first_line] + lines:

callback_match = re.search('([0-9]*\.[0-9]*).*\[Callback\]', line)
callback_match = \
re.search(r'([0-9]*\.[0-9]*).*\[Callback\]', line)
if callback_match:
callback_times.append(float(callback_match.group(1))-start_time)
callback_times.append(
float(callback_match.group(1))-start_time)

begin_trans_match = re.search('([0-9]*\.[0-9]*).*begin transaction', line)
begin_trans_match = \
re.search(r'([0-9]*\.[0-9]*).*begin transaction', line)
if begin_trans_match:
begin_trans_times.append(float(begin_trans_match.group(1))-start_time)
begin_trans_times.append(
float(begin_trans_match.group(1)) - start_time)

commit_trans_match = re.search('([0-9]*\.[0-9]*).*commit transaction', line)
commit_trans_match = \
re.search(r'([0-9]*\.[0-9]*).*commit transaction', line)
if commit_trans_match:
commit_trans_times.append(float(commit_trans_match.group(1))-start_time)
commit_trans_times.append(
float(commit_trans_match.group(1)) - start_time)

insert_start_match = re.search('([0-9]*\.[0-9]*).*Executing insert start', line)
insert_start_match = \
re.search(r'([0-9]*\.[0-9]*).*Executing insert start', line)
if insert_start_match:
insert_start_times.append(float(insert_start_match.group(1))-start_time)
insert_start_times.append(
float(insert_start_match.group(1)) - start_time)

insert_end_match = re.search('([0-9]*\.[0-9]*).*Executing insert end', line)
insert_end_match = \
re.search(r'([0-9]*\.[0-9]*).*Executing insert end', line)
if insert_end_match:
insert_end_times.append(float(insert_end_match.group(1))-start_time)
insert_end_times.append(
float(insert_end_match.group(1)) - start_time)

dt_between_callbacks = []
last_callback_time = None
Expand All @@ -82,17 +93,52 @@
insert_end_times_v = [2] * len(insert_end_times)

fig, ax = plt.subplots(figsize=(15, 6))
fig.suptitle(filename + " msg_count=" + str(len(callback_times)), fontsize=16)
if (len(begin_trans_times_v)>0):
ax.stem(begin_trans_times, begin_trans_times_v, label='begin_transaction', markerfmt=' ', linefmt='r-', basefmt='k')
if (len(commit_trans_times_v)>0):
ax.stem(commit_trans_times, commit_trans_times_v, label='commit_transaction', markerfmt=' ', linefmt='g-', basefmt='k')
if (len(insert_start_times)>0):
ax.stem(insert_start_times, insert_start_times_v, label='insert_start', markerfmt=' ', linefmt='y-', basefmt='k')
if (len(insert_end_times)>0):
ax.stem(insert_end_times, insert_end_times_v, label='insert_end', markerfmt=' ', linefmt='m-', basefmt='k')
if (len(callback_times)>0):
ax.stem(callback_times, callback_times_v, label='callback', markerfmt=' ', linefmt='b-', basefmt='k')
fig.suptitle(filename + ' msg_count=' + str(len(callback_times)), fontsize=16)
if (len(begin_trans_times_v) > 0):
ax.stem(
begin_trans_times,
begin_trans_times_v,
label='begin_transaction',
markerfmt=' ',
linefmt='r-',
basefmt='k'
)
if (len(commit_trans_times_v) > 0):
ax.stem(
commit_trans_times,
commit_trans_times_v,
label='commit_transaction',
markerfmt=' ',
linefmt='g-',
basefmt='k'
)
if (len(insert_start_times) > 0):
ax.stem(
insert_start_times,
insert_start_times_v,
label='insert_start',
markerfmt=' ',
linefmt='y-',
basefmt='k'
)
if (len(insert_end_times) > 0):
ax.stem(
insert_end_times,
insert_end_times_v,
label='insert_end',
markerfmt=' ',
linefmt='m-',
basefmt='k'
)
if (len(callback_times) > 0):
ax.stem(
callback_times,
callback_times_v,
label='callback',
markerfmt=' ',
linefmt='b-',
basefmt='k'
)
plt.yticks([])

ax.legend(loc='upper right')
Expand Down
2 changes: 2 additions & 0 deletions rosbag2_performance/rosbag2_benchmarking/pytest.ini
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
[pytest]
junit_family=xunit2
Original file line number Diff line number Diff line change
Expand Up @@ -11,50 +11,69 @@
# 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.
"""Dummy publisher for warming up rosbag2 topics."""

import rclpy, time
import time

import rclpy
from rclpy.node import Node


class DummyPublisherUtility(Node):
"""Dummy publisher creates publishers for warming up topics on rosbag2."""

__publishers = []

def __init__(self):
"""Initialize class with required topics and corresponding types."""
super().__init__('dummy_publisher')
self.declare_parameter("topics")
self.declare_parameter("types")
self.declare_parameter('topics')
self.declare_parameter('types')

topics = self.get_parameter("topics").get_parameter_value().string_array_value
types = self.get_parameter("types").get_parameter_value().string_array_value
topics = self.get_parameter(
'topics'
).get_parameter_value().string_array_value
types = self.get_parameter(
'types'
).get_parameter_value().string_array_value

if len(topics) != len(types):
raise RuntimeError("Topics and types length mismatch.")
raise RuntimeError('Topics and types length mismatch.')

for i in range(0,len(topics)):
self.warm_up_topic(topics[i], types[i])
for i in range(0, len(topics)):
self.__warm_up_topic(topics[i], types[i])
time.sleep(0.01)

def warm_up_topic(self, topic, type_):
if type_ == "sensor_msgs/msg/Image":
def __warm_up_topic(self, topic, type_):
if type_ == 'sensor_msgs/msg/Image':
from sensor_msgs.msg import Image
self.__publishers.append(self.create_publisher(Image, topic, 1))
elif type_ == "sensor_msgs/msg/PointCloud2":
self.__publishers.append(
self.create_publisher(Image, topic, 1)
)
elif type_ == 'sensor_msgs/msg/PointCloud2':
from sensor_msgs.msg import PointCloud2
self.__publishers.append(self.create_publisher(PointCloud2, topic, 1))
elif type_ == "std_msgs/msg/ByteMultiArray":
self.__publishers.append(
self.create_publisher(PointCloud2, topic, 1)
)
elif type_ == 'std_msgs/msg/ByteMultiArray':
from std_msgs.msg import ByteMultiArray
self.__publishers.append(self.create_publisher(ByteMultiArray, topic, 1))
self.__publishers.append(
self.create_publisher(ByteMultiArray, topic, 1)
)
else:
# (piotr.jaroszek) TODO: fill out rest or make a dynamic import
pass


def main():
"""Ros2 once-spin run."""
rclpy.init()
node = DummyPublisherUtility()
while rclpy.ok():
rclpy.spin_once(node, timeout_sec=0.1)
rclpy.shutdown()
node.destroy_node()


if __name__ == '__main__':
main()
Loading

0 comments on commit 1bab689

Please sign in to comment.