Skip to content

Commit 7f0d800

Browse files
Set CPU affinity for producers and recorder from benchmark parameters (ros2#1305)
Signed-off-by: Michael Orlov <[email protected]>
1 parent 6e28b92 commit 7f0d800

File tree

3 files changed

+27
-3
lines changed

3 files changed

+27
-3
lines changed

rosbag2_performance/rosbag2_performance_benchmarking/config/benchmarks/default_benchmark_producers.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,8 @@ rosbag2_performance_benchmarking:
77
repeat_each: 1 # How many times to run each configurations (to average results)
88
no_transport: False # Whether to run storage-only or end-to-end (including transport) benchmark
99
preserve_bags: False # Whether to leave bag files after experiment (and between runs). Some configurations can take lots of space!
10+
producers_cpu_affinity: [0, 1] # CPU affinity for producers
11+
recorder_cpu_affinity: [2, 3] # CPU affinity for recorder
1012
parameters: # Each combination of parameters in this section will be benchmarked
1113
storage_id: ["mcap", "sqlite3"]
1214
max_cache_size: [100000000, 500000000]

rosbag2_performance/rosbag2_performance_benchmarking/config/benchmarks/default_no_transport.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,8 @@ rosbag2_performance_benchmarking:
77
repeat_each: 1 # How many times to run each configurations (to average results)
88
no_transport: True # Whether to run storage-only or end-to-end (including transport) benchmark
99
preserve_bags: False # Whether to leave bag files after experiment (and between runs). Some configurations can take lots of space!
10+
producers_cpu_affinity: [0, 1] # CPU affinity for producers
11+
recorder_cpu_affinity: [2, 3] # CPU affinity for recorder
1012
parameters: # Each combination of parameters in this section will be benchmarked
1113
storage_id: ["mcap", "sqlite3"]
1214
max_cache_size: [100000000, 500000000]

rosbag2_performance/rosbag2_performance_benchmarking/launch/benchmark_launch.py

+23-3
Original file line numberDiff line numberDiff line change
@@ -78,6 +78,9 @@
7878
_producer_cpu_usage = 0.0
7979
_recorder_cpu_usage = 0.0
8080

81+
_producer_cpu_affinity = []
82+
_recorder_cpu_affinity = []
83+
8184

8285
def _parse_arguments(args=sys.argv[4:]):
8386
"""Parse benchmark and producers config file paths."""
@@ -141,9 +144,11 @@ def _launch_sequence(transport):
141144

142145
def _rosbag_proc_started(event, context):
143146
"""Register current rosbag2 PID so we can terminate it when producer exits."""
144-
global _rosbag_pid, _rosbag_process
147+
global _rosbag_pid, _rosbag_process, _recorder_cpu_affinity
145148
_rosbag_pid = event.pid
146149
_rosbag_process = psutil.Process(_rosbag_pid)
150+
if len(_recorder_cpu_affinity) > 0:
151+
_rosbag_process.cpu_affinity(_recorder_cpu_affinity)
147152

148153

149154
def _rosbag_ready_check(event):
@@ -202,9 +207,11 @@ def _results_writer_exited(event, context):
202207
def _producer_node_started(event, context):
203208
"""Log current benchmark progress on producer start."""
204209
global _producer_idx, _producer_pid, _producer_process, _producer_cpu_usage
205-
global _cpu_usage_per_core
210+
global _cpu_usage_per_core, _producer_cpu_affinity
206211
_producer_pid = event.pid
207212
_producer_process = psutil.Process(_producer_pid)
213+
if len(_producer_cpu_affinity) > 0:
214+
_producer_process.cpu_affinity(_producer_cpu_affinity)
208215
_producer_process.cpu_percent()
209216
_producer_cpu_usage = 0.0
210217
psutil.cpu_percent(None, True)
@@ -357,6 +364,7 @@ def _producer_node_exited(event, context):
357364
def generate_launch_description():
358365
"""Generate launch description for ros2 launch system."""
359366
global _producer_nodes, _bench_cfg_path, _producers_cfg_path
367+
global _producer_cpu_affinity, _recorder_cpu_affinity
360368
_bench_cfg_path, _producers_cfg_path = _parse_arguments()
361369

362370
# Parse yaml config for benchmark
@@ -376,6 +384,17 @@ def generate_launch_description():
376384
transport = not benchmark_params.get('no_transport')
377385
preserve_bags = benchmark_params.get('preserve_bags')
378386

387+
# CPU affinity for producers and recorder
388+
_producer_cpu_affinity = benchmark_params.get('producers_cpu_affinity', [])
389+
_recorder_cpu_affinity = benchmark_params.get('recorder_cpu_affinity', [])
390+
if not transport:
391+
_producer_cpu_affinity = _recorder_cpu_affinity
392+
print('Warning! With no_transport = True, producer_cpu_affinity will be ignored')
393+
394+
if len(_producer_cpu_affinity) > 0:
395+
# Set CPU affinity for current process to avoid impact on the recorder
396+
psutil.Process().cpu_affinity(_producer_cpu_affinity)
397+
379398
# Producers options
380399
producers_params = bench_cfg['benchmark']['parameters']
381400

@@ -577,7 +596,8 @@ def __generate_cross_section_parameter(i,
577596
'sigkill_timeout', default=60),
578597
sigterm_timeout=launch.substitutions.LaunchConfiguration(
579598
'sigterm_timeout', default=60),
580-
cmd=['ros2', 'bag', 'record', '-e', r'\/.*_benchmarking_node\/.*'] + rosbag_args
599+
cmd=['ros2', 'bag', 'record', '-e',
600+
r'\/.*_benchmarking_node\/.*'] + rosbag_args
581601
)
582602

583603
# Fill up list with rosbag record process and result writers actions

0 commit comments

Comments
 (0)