-
Notifications
You must be signed in to change notification settings - Fork 412
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
Showing
6 changed files
with
499 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,49 @@ | ||
cmake_minimum_required(VERSION 3.5) | ||
|
||
project(rclcpp_performance) | ||
|
||
# Default to C++14 | ||
if(NOT CMAKE_CXX_STANDARD) | ||
set(CMAKE_CXX_STANDARD 14) | ||
endif() | ||
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") | ||
add_compile_options(-Wall -Wextra -Wpedantic) | ||
endif() | ||
|
||
find_package(ament_cmake REQUIRED) | ||
# find_package(ament_cmake_python REQUIRED) | ||
find_package(builtin_interfaces REQUIRED) | ||
find_package(rosidl_default_generators REQUIRED) | ||
|
||
# ament_python_install_package(${PROJECT_NAME}) | ||
|
||
file(MAKE_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/logs) | ||
|
||
rosidl_generate_interfaces(${PROJECT_NAME} | ||
"msg/MatchingPublisher.msg" | ||
ADD_LINTER_TESTS | ||
) | ||
|
||
find_package(rclcpp REQUIRED) | ||
|
||
add_executable(communication_performance src/communication_performance.cpp) | ||
ament_target_dependencies(communication_performance | ||
"rclcpp" | ||
"rosidl_generator_cpp") | ||
rosidl_target_interfaces(communication_performance | ||
${PROJECT_NAME} "rosidl_typesupport_cpp") | ||
|
||
ament_export_dependencies(rosidl_default_runtime) | ||
# ament_export_dependencies(rclcpp) | ||
|
||
ament_package() | ||
|
||
install( | ||
PROGRAMS scripts/posprocess_logging | ||
DESTINATION lib/${PROJECT_NAME} | ||
) | ||
|
||
install( | ||
TARGETS communication_performance | ||
DESTINATION lib/${PROJECT_NAME} | ||
) |
Empty file.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,2 @@ | ||
uint64 publisher_id | ||
uint64 message_id |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,27 @@ | ||
<?xml version="1.0"?> | ||
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?> | ||
<package format="3"> | ||
<name>rclcpp_performance</name> | ||
<version>0.6.2</version> | ||
<description>A package containing rclcpp communication characterization tests.</description> | ||
<maintainer email="ivanpauno@ekumenlabs.com">Ivan Paunovic</maintainer> | ||
<license>Apache License 2.0</license> | ||
|
||
<buildtool_depend>ament_cmake</buildtool_depend> | ||
|
||
<buildtool_depend>rosidl_default_generators</buildtool_depend> | ||
|
||
<build_depend>rclcpp</build_depend> | ||
|
||
<exec_depend>rosidl_default_runtime</exec_depend> | ||
<exec_depend>rclcpp</exec_depend> | ||
|
||
<test_depend>ament_lint_auto</test_depend> | ||
<test_depend>ament_lint_common</test_depend> | ||
|
||
<member_of_group>rosidl_interface_packages</member_of_group> | ||
|
||
<export> | ||
<build_type>ament_cmake</build_type> | ||
</export> | ||
</package> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,126 @@ | ||
#!/usr/bin/env python3 | ||
|
||
# Copyright 2019 Open Source Robotics Foundation, 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. | ||
|
||
""" | ||
Posprocess communication_performance logging. | ||
Calculates latency between publish and subscribe, and actual | ||
publishers and subscriptions rates. | ||
""" | ||
|
||
import argparse | ||
|
||
from pathlib import Path | ||
|
||
import matplotlib.pyplot as plt | ||
|
||
import numpy as np | ||
|
||
|
||
def main(): | ||
"""Do stuff.""" | ||
parser = argparse.ArgumentParser(description='Process logged data.') | ||
parser.add_argument('-d', '--dir', nargs='?', default='./logs', const='./logs') | ||
|
||
args = parser.parse_args() | ||
|
||
path = Path(args.dir) | ||
publishers = path.glob('publisher_*') | ||
subscriptions = path.glob('subscription_*') | ||
publishers_data = dict({}) | ||
for publisher in publishers: | ||
publisher_id = int(str(publisher).partition('publisher_')[2]) | ||
csv_data = np.genfromtxt( | ||
str(publisher), | ||
dtype=(int, float), | ||
delimiter=',') | ||
publishers_data[publisher_id] = {row[0]: row[1] for row in csv_data} | ||
subscription_data = dict({}) | ||
for subscription in subscriptions: | ||
subscription_id = int(str(subscription).partition('subscription_')[2]) | ||
csv_data = np.genfromtxt( | ||
str(subscription), | ||
dtype=(int, int, float), | ||
delimiter=',') | ||
subscription_data[subscription_id] = dict({}) | ||
for row in csv_data: | ||
try: | ||
subscription_data[subscription_id][row[0]].update({row[1]: row[2]}) | ||
except: | ||
subscription_data[subscription_id][row[0]] = {row[1]: row[2]} | ||
plot_publishers_average_rate(publishers_data) | ||
plot_subscriptions_average_rate(subscription_data) | ||
plot_latencys(subscription_data, publishers_data) | ||
plt.show() | ||
|
||
|
||
def plot_publishers_average_rate(data): | ||
pub_rates = dict({}) | ||
for pub_id in sorted(data): | ||
timestamps = np.array(list(data[pub_id].values())) | ||
period = np.array([timestamps[i+1] - timestamps[i] | ||
for i in range(timestamps.size-1)]) | ||
pub_rates[pub_id] = np.average(period) / 1000 | ||
fig, ax = plt.subplots() | ||
ax.plot( | ||
np.array(list(pub_rates.keys())), | ||
np.array(list(pub_rates.values())), | ||
'ro', | ||
marker='o') | ||
fig.suptitle('Publishers average period') | ||
fig.canvas.set_window_title('Publishers average period') | ||
|
||
|
||
def plot_subscriptions_average_rate(data): | ||
sub_rates = dict({}) | ||
for sub_id in sorted(data): | ||
for pub_id in sorted(data[sub_id]): | ||
timestamps = np.array(list(data[sub_id][pub_id].values())) | ||
period = np.array([timestamps[i+1] - timestamps[i] | ||
for i in range(timestamps.size-1)]) | ||
sub_rates[(sub_id, pub_id)] = np.average(period) / 1000 | ||
fig, ax = plt.subplots() | ||
x = np.linspace(0, len(sub_rates)-1, len(sub_rates)) | ||
y = np.array(list(sub_rates.values())) | ||
ax.plot( | ||
x, | ||
y, | ||
'ro', | ||
marker='o') | ||
fig.suptitle('Subscriptions average period') | ||
fig.canvas.set_window_title('Subscriptions average period') | ||
|
||
|
||
def plot_latencys(sub_data, pub_data): | ||
av_latencys = dict({}) | ||
for sub_id in sorted(sub_data): | ||
for pub_id in sorted(sub_data[sub_id]): | ||
latencys = np.array([ | ||
sub_data[sub_id][pub_id][m_id] - | ||
pub_data[pub_id][m_id] | ||
for m_id in sub_data[sub_id][pub_id]] | ||
) | ||
av_latencys[(sub_id, pub_id)] = np.average(latencys) / 1000 | ||
fig, ax = plt.subplots() | ||
x = np.linspace(0, len(av_latencys)-1, len(av_latencys)) | ||
y = np.array(list(av_latencys.values())) | ||
ax.plot(x, y, marker='o') | ||
fig.suptitle('Average latencys, between publish and subscribe') | ||
fig.canvas.set_window_title('Average latencys, between publish and subscribe') | ||
|
||
|
||
if __name__ == '__main__': | ||
main() |
Oops, something went wrong.