Skip to content

Commit 9a54598

Browse files
committed
Address comments
1 parent 91d128a commit 9a54598

File tree

3 files changed

+99
-66
lines changed

3 files changed

+99
-66
lines changed

benchmark/README.md

Lines changed: 27 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@ Performance benchmarks for comparing ROS 2 client libraries: C++ (rclcpp), Pytho
77
1. **ROS 2**: Install from [ros.org](https://docs.ros.org/en/jazzy/Installation.html)
88
2. **Node.js**: v16+ for rclnodejs (from [nodejs.org](https://nodejs.org/))
99
3. **rclnodejs**: Follow [installation guide](https://github.com/RobotWebTools/rclnodejs#installation)
10+
4. **Build Dependencies**: For C++ benchmarks: `sudo apt install libssl-dev cmake build-essential`
1011

1112
## Benchmark Structure
1213

@@ -16,55 +17,59 @@ Each client library has identical benchmark tests:
1617
| ----------- | ------------------------------------------- |
1718
| **topic** | Publisher/subscriber performance |
1819
| **service** | Client/service request-response performance |
19-
| **startup** | Node initialization time |
2020

2121
## Performance Results
2222

2323
### Test Environment
2424

2525
**Hardware:**
2626

27-
- **CPU:** Intel(R) Core(TM) i9-10900X @ 3.70GHz (10 cores, 20 threads)
28-
- **Memory:** 32GB RAM
27+
- **CPU:** 11th Gen Intel(R) Core(TM) i7-1185G7 @ 3.00GHz (4 cores, 8 threads)
28+
- **Memory:** 8GB RAM
2929
- **Architecture:** x86_64
3030

3131
**Software:**
3232

3333
- **OS:** Ubuntu 24.04.3 LTS (WSL2)
34+
- **Kernel:** 6.6.87.2-microsoft-standard-WSL2
3435
- **ROS 2:** Jazzy distribution
35-
- **C++ Compiler:** GCC 13.3.0
36+
- **C++ Compiler:** GCC 13.3.0 (Ubuntu 13.3.0-6ubuntu2~24.04)
3637
- **Python:** 3.12.3
3738
- **Node.js:** v22.18.0
3839

3940
### Benchmark Results
4041

4142
Benchmark parameters: 1000 iterations, 1024KB message size
4243

43-
| Client Library | Topic (ms) | Service (ms) | Performance Ratio |
44-
| ----------------------- | ---------- | ------------ | ---------------------- |
45-
| **rclcpp (C++)** | 437 | 8,129 | Baseline (fastest) |
46-
| **rclpy (Python)** | 2,294 | 25,519 | 5.3x / 3.1x slower |
47-
| **rclnodejs (Node.js)** | 2,075 | 3,420\* | 4.7x / 2.4x faster\*\* |
44+
| Client Library | Topic (ms) | Service (ms) | Performance Ratio |
45+
| ----------------------- | ---------- | ------------ | ------------------- |
46+
| **rclcpp (C++)** | 168 | 627 | Baseline (fastest) |
47+
| **rclpy (Python)** | 1,618 | 15,380 | 9.6x / 24.5x slower |
48+
| **rclnodejs (Node.js)** | 744 | 927 | 4.4x / 1.5x slower |
4849

49-
_Last updated: August 29, 2025_
50+
_Last updated: August 30, 2025_
5051

5152
**Notes:**
5253

5354
- Topic benchmarks: All libraries completed successfully with 1024KB messages
54-
- Service benchmarks: C++ and Python completed with 1024KB responses; Node.js completed with minimal data
55-
- \*Node.js service uses minimal response data due to serialization issues with large (1024KB) payloads
56-
- \*\*Node.js service performance is surprisingly good with small data, but not directly comparable due to different data sizes
55+
- Service benchmarks: All libraries completed successfully with 1024KB responses
5756
- Performance ratios are relative to C++ baseline
57+
- C++ shows excellent performance as expected for a compiled language
58+
- Node.js performs significantly better than Python, likely due to V8 optimizations
59+
- Python service performance shows significant overhead with large payloads compared to topics
5860

5961
## Running Benchmarks
6062

6163
### C++ (rclcpp)
6264

6365
```bash
6466
cd benchmark/rclcpp/
65-
colcon build
66-
./build/rclcpp_benchmark/publisher-stress-test -r 1000 -s 1024
67-
./build/rclcpp_benchmark/client-stress-test -r 1000
67+
mkdir -p build && cd build
68+
source ~/Download/ros2-linux/local_setup.bash # Adjust path
69+
cmake .. && make
70+
# Run from build directory:
71+
./publisher-stress-test -r 1000 -s 1024
72+
./client-stress-test -r 1000
6873
```
6974

7075
### Python (rclpy)
@@ -94,26 +99,26 @@ For complete tests, run subscriber/service first, then publisher/client:
9499
```bash
95100
# Terminal 1: Start subscriber (adjust for your language)
96101
python3 topic/subscription-stress-test.py # Python
97-
./build/rclcpp_benchmark/subscription-stress-test # C++
102+
./subscription-stress-test # C++ (from build dir)
98103
node benchmark/rclnodejs/topic/subscription-stress-test.js # Node.js
99104

100105
# Terminal 2: Run publisher benchmark
101106
python3 topic/publisher-stress-test.py -r 1000 -s 1024 # Python
102-
./build/rclcpp_benchmark/publisher-stress-test -r 1000 -s 1024 # C++
107+
./publisher-stress-test -r 1000 -s 1024 # C++ (from build dir)
103108
node benchmark/rclnodejs/topic/publisher-stress-test.js -r 1000 -s 1024 # Node.js
104109
```
105110

106111
**Service Test:**
107112

108113
```bash
109114
# Terminal 1: Start service (adjust for your language)
110-
python3 service/service-stress-test.py # Python
111-
./build/rclcpp_benchmark/service-stress-test # C++
112-
node benchmark/rclnodejs/service/service-stress-test.js # Node.js
115+
python3 service/service-stress-test.py -s 1024 # Python
116+
./service-stress-test -s 1024 # C++ (from build dir)
117+
node benchmark/rclnodejs/service/service-stress-test.js -s 1024 # Node.js
113118

114119
# Terminal 2: Run client benchmark
115120
python3 service/client-stress-test.py -r 1000 # Python
116-
./build/rclcpp_benchmark/client-stress-test -r 1000 # C++
121+
./client-stress-test -r 1000 # C++ (from build dir)
117122
node benchmark/rclnodejs/service/client-stress-test.js -r 1000 # Node.js
118123
```
119124

benchmark/rclnodejs/service/client-stress-test.js

Lines changed: 47 additions & 36 deletions
Original file line numberDiff line numberDiff line change
@@ -43,50 +43,61 @@ async function main() {
4343
`The client will send a GetMap request continuously until receiving response ${totalTimes} times.`
4444
);
4545

46-
// Wait for service to be available - simplified approach
46+
// Wait for service to be available using client.waitForService()
4747
node.getLogger().info('Waiting for service to be available...');
4848

49-
// Simple wait with spinning
50-
await new Promise((resolve) => {
51-
setTimeout(() => {
52-
node.getLogger().info('Service should be available now');
53-
resolve();
54-
}, 2000); // Wait 2 seconds for service to start
55-
});
49+
const serviceAvailable = await client.waitForService(5000); // Wait up to 5 seconds
50+
if (!serviceAvailable) {
51+
throw new Error(
52+
'GetMap service not available after 5 seconds. Make sure the service is running.'
53+
);
54+
}
55+
56+
node.getLogger().info('Service is available, starting benchmark...');
57+
58+
// Start spinning to handle callbacks
59+
rclnodejs.spin(node);
5660

5761
// Send requests sequentially using callback pattern
58-
const sendRequests = async () => {
59-
// Start spinning to handle callbacks
60-
rclnodejs.spin(node);
61-
62-
for (let i = 0; i < totalTimes; i++) {
63-
try {
64-
const response = await new Promise((resolve, reject) => {
65-
client.sendRequest({}, (response) => {
66-
console.log('send+++');
67-
console.log(response);
68-
if (response) {
69-
resolve(response.map.header);
70-
} else {
71-
reject(new Error('No response received'));
62+
let requestPromiseResolve, requestPromiseReject;
63+
let currentRequestPromise = null;
64+
65+
const sendRequests = () => {
66+
return new Promise((resolve, reject) => {
67+
let requestCount = 0;
68+
69+
const sendNextRequest = () => {
70+
if (requestCount >= totalTimes) {
71+
resolve();
72+
return;
73+
}
74+
75+
requestCount++;
76+
client.sendRequest({}, (response) => {
77+
if (response) {
78+
receivedTimes++;
79+
// Show progress every 100 requests or for small test runs
80+
if (receivedTimes % 100 === 0 || totalTimes <= 10) {
81+
node
82+
.getLogger()
83+
.info(
84+
`Progress: ${receivedTimes}/${totalTimes} requests completed`
85+
);
7286
}
73-
});
74-
});
75-
if (response) {
76-
receivedTimes++;
77-
// Show progress every 100 requests
78-
if (receivedTimes % 100 === 0) {
87+
} else {
7988
node
8089
.getLogger()
81-
.info(
82-
`Progress: ${receivedTimes}/${totalTimes} requests completed`
83-
);
90+
.error(`Request ${requestCount} failed: No response received`);
8491
}
85-
}
86-
} catch (error) {
87-
node.getLogger().error(`Request ${i + 1} failed: ${error.message}`);
88-
}
89-
}
92+
93+
// Send next request
94+
setImmediate(sendNextRequest);
95+
});
96+
};
97+
98+
// Start the first request
99+
sendNextRequest();
100+
});
90101
};
91102

92103
await sendRequests();

benchmark/rclnodejs/service/service-stress-test.js

Lines changed: 25 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -19,19 +19,34 @@ const { program } = require('commander');
1919
const rclnodejs = require('../../../index.js');
2020

2121
program
22-
.option('-s, --size <size_kb>', 'The block size', '1')
22+
.option('-s, --size <size_kb>', 'The block size in KB', '1')
2323
.parse(process.argv);
2424

2525
const options = program.opts();
26-
let size = parseInt(options.size) || 1;
26+
let sizeKB = parseInt(options.size) || 1;
27+
28+
// Calculate map dimensions based on size
29+
// Each cell is 1 byte (int8), so for sizeKB kilobytes we need sizeKB * 1024 cells
30+
const totalCells = sizeKB * 1024;
31+
32+
// Calculate width and height as close to square as possible
33+
const width = Math.floor(Math.sqrt(totalCells));
34+
const height = Math.ceil(totalCells / width);
35+
const actualCells = width * height;
36+
37+
console.log(`Requested size: ${sizeKB}KB (${totalCells} cells)`);
38+
console.log(
39+
`Calculated dimensions: ${width} x ${height} = ${actualCells} cells`
40+
);
41+
console.log(`Actual size: ${(actualCells / 1024).toFixed(2)}KB`);
2742

2843
rclnodejs
2944
.init()
3045
.then(() => {
3146
let node = rclnodejs.createNode('stress_service_rclnodejs');
3247

3348
node.createService('nav_msgs/srv/GetMap', 'get_map', () => {
34-
// Create map data structure that matches the working test pattern
49+
// Create map data structure with calculated dimensions
3550
const mapData = {
3651
map: {
3752
header: {
@@ -47,8 +62,8 @@ rclnodejs
4762
nanosec: 789,
4863
},
4964
resolution: 1.0,
50-
width: 1024,
51-
height: 768,
65+
width: width,
66+
height: height,
5267
origin: {
5368
position: {
5469
x: 0.0,
@@ -63,15 +78,17 @@ rclnodejs
6378
},
6479
},
6580
},
66-
// Use minimal data array for stability
67-
data: [1, 2, 3],
81+
// Generate data array with the exact size needed (width * height)
82+
data: new Int8Array(actualCells).fill(0),
6883
},
6984
};
7085

7186
return mapData;
7287
});
7388

74-
console.log(`GetMap service started, data size: ${size}KB`);
89+
console.log(`GetMap service started`);
90+
console.log(`Map dimensions: ${width} x ${height} = ${actualCells} cells`);
91+
console.log(`Data size: ${(actualCells / 1024).toFixed(2)}KB`);
7592
rclnodejs.spin(node);
7693
})
7794
.catch((e) => {

0 commit comments

Comments
 (0)