Skip to content

Commit

Permalink
Performance benchmarking improvements (ros2#634)
Browse files Browse the repository at this point in the history
* Performance benchmarking improvements

Signed-off-by: Piotr Jaroszek <piotr.jaroszek@robotec.ai>

* fixed durability qos in config

Signed-off-by: Adam Dabrowski <adam.dabrowski@robotec.ai>

* Benchmark db files information in one file

Signed-off-by: Piotr Jaroszek <piotr.jaroszek@robotec.ai>

Co-authored-by: Adam Dabrowski <adam.dabrowski@robotec.ai>
  • Loading branch information
pijaro and adamdbrw authored Feb 12, 2021
1 parent 10fff0d commit e6377d7
Show file tree
Hide file tree
Showing 3 changed files with 33 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@
import shutil
import signal
import sys
import time

from ament_index_python import get_package_share_directory

Expand Down Expand Up @@ -196,8 +197,22 @@ def _producer_node_exited(event, context):
# Handle clearing bag files
if not node_params['preserve_bags']:
db_files = pathlib.Path.cwd().joinpath(node_params['db_folder']).glob('*.db3')
stats_path = pathlib.Path.cwd().joinpath(node_params['db_folder'], 'bagfiles_info.yaml')
stats = {
'total_size': 0,
'bagfiles': []
}

# Delete rosbag files
for f in db_files:
filesize = f.stat().st_size
f.unlink()
stats['bagfiles'].append({f.name: {'size': filesize}})
stats['total_size'] += filesize

# Dump files size information
with open(stats_path, 'w') as stats_file:
yaml.dump(stats, stats_file)

# If we have non empty rosbag PID, then we need to kill it (end-to-end transport case)
if _rosbag_pid is not None and transport:
Expand All @@ -217,6 +232,10 @@ def _producer_node_exited(event, context):

# Bump up producer index, so the launch sequence can continue
_producer_idx += 1

# Give disks some time to flush their internal cache before starting next experiment
time.sleep(5)

return [
launch.actions.LogInfo(
msg='---------------------------'
Expand Down Expand Up @@ -435,7 +454,7 @@ def __generate_cross_section_parameter(i,
'sigkill_timeout', default=60),
sigterm_timeout=launch.substitutions.LaunchConfiguration(
'sigterm_timeout', default=60),
cmd=['ros2', 'bag', 'record', '-a'] + rosbag_args
cmd=['ros2', 'bag', 'record', '-e', r'\/.*_benchmarking_node\/.*'] + rosbag_args
)

# Result writer node walks through output metadata files and generates
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -106,12 +106,16 @@ def __process_test(compression_selected,
cache_samples[sample[0]['cache_size']].append(
int(sample[0]['total_recorded_count'])/sample_total_produced)

cache_avg_recorded_percentage = {
cache: statistics.mean(samples)
cache_recorded_percentage_stats = {
cache: {
'avg': statistics.mean(samples),
'min': min(samples),
'max': max(samples)
}
for cache, samples in cache_samples.items()
}
cache_data_per_storage_conf.update(
{storage_cfg_name: cache_avg_recorded_percentage}
{storage_cfg_name: cache_recorded_percentage_stats}
)

result = {
Expand All @@ -135,9 +139,11 @@ def __process_test(compression_selected,
for storage_cfg, caches in result['cache_data'].items():
print('\t\tstorage config: {}:'.format(pathlib.Path(storage_cfg).name))
for cache, percent_recorded in caches.items():
print('\t\t\tcache [bytes]: {:,}: {:.2%} recorded'.format(
print('\t\t\tcache {:,} - min: {:.2%}, average: {:.2%}, max: {:.2%}'.format(
int(cache),
percent_recorded))
percent_recorded['min'],
percent_recorded['avg'],
percent_recorded['max']))

[
__process_test(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,8 @@ void load_qos_configuration(
// TODO(adamdbrw) - error handling / map string to function
if (qos_reliability == "reliable") {group_config.qos.reliable();}
if (qos_reliability == "best_effort") {group_config.qos.best_effort();}
if (qos_reliability == "transient_local") {group_config.qos.transient_local();}
if (qos_reliability == "volatile") {group_config.qos.durability_volatile();}
if (qos_durability == "transient_local") {group_config.qos.transient_local();}
if (qos_durability == "volatile") {group_config.qos.durability_volatile();}
}

bool wait_for_subscriptions_from_node_parameters(rclcpp::Node & node)
Expand Down

0 comments on commit e6377d7

Please sign in to comment.