Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 13 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ rclnodejs.init().then(() => {
- [Electron-based Visualization](#electron-based-visualization)
- [Using TypeScript](#using-rclnodejs-with-typescript)
- [ROS2 Interface Message Generation](#ros2-interface-message-generation)
- [Performance Benchmarks](#performance-benchmarks)
- [Efficient Usage Tips](./docs/EFFICIENCY.md)
- [FAQ and Known Issues](./docs/FAQ.md)
- [Building from Scratch](./docs/BUILDING.md)
Expand Down Expand Up @@ -139,6 +140,18 @@ To generate messages from IDL files, use the `generate-messages-idl` npm script:
npm run generate-messages-idl
```

## Performance Benchmarks

Benchmark results for 1000 iterations with 1024KB messages (Ubuntu 24.04.3 WSL2, i7-1185G7):

| Library | Topic (ms) | Service (ms) |
| ----------------------- | ---------- | ------------ |
| **rclcpp (C++)** | 168 | 627 |
| **rclnodejs (Node.js)** | 744 | 927 |
| **rclpy (Python)** | 1,618 | 15,380 |

See [benchmark/README.md](benchmark/README.md) for details.

## Contributing

Please read the [Contributing Guide](./docs/CONTRIBUTING.md) before making a pull request.
Expand Down
146 changes: 118 additions & 28 deletions benchmark/README.md
Original file line number Diff line number Diff line change
@@ -1,47 +1,137 @@
# Benchmarks for ROS 2.0 clients
# ROS 2 Client Library Benchmarks

This folder contains code used to measure the performance between different ROS 2.0 clients.
Performance benchmarks for comparing ROS 2 client libraries: C++ (rclcpp), Python (rclpy), and JavaScript (rclnodejs).

## Prerequisites

1.Install ROS 2.0 from binary
1. **ROS 2**: Install from [ros.org](https://docs.ros.org/en/jazzy/Installation.html)
2. **Node.js**: v16+ for rclnodejs (from [nodejs.org](https://nodejs.org/))
3. **rclnodejs**: Follow [installation guide](https://github.com/RobotWebTools/rclnodejs#installation)
4. **Build Dependencies**: For C++ benchmarks: `sudo apt install libssl-dev cmake build-essential`

You can download the latest binary package of ROS2 from [here](http://ci.ros2.org/view/packaging/) and follow the instructions to setup the environment.
## Benchmark Structure

- [Linux](https://github.com/ros2/ros2/wiki/Linux-Install-Binary)
- [macOS](https://github.com/ros2/ros2/wiki/OSX-Install-Binary)
- [Windows](https://github.com/ros2/ros2/wiki/Windows-Install-Binary)
Each client library has identical benchmark tests:

2.Install Node.js
| Test Type | Description |
| ----------- | ------------------------------------------- |
| **topic** | Publisher/subscriber performance |
| **service** | Client/service request-response performance |

Download the latest LTS edition from https://nodejs.org/en/
## Performance Results

3.[Get the code](https://github.com/RobotWebTools/rclnodejs#get-code) and [install](https://github.com/RobotWebTools/rclnodejs#build-module)
### Test Environment

## Benchmark directories
**Hardware:**

The table lists the directories for each kind of the ROS 2.0 clients.
- **CPU:** 11th Gen Intel(R) Core(TM) i7-1185G7 @ 3.00GHz (4 cores, 8 threads)
- **Memory:** 8GB RAM
- **Architecture:** x86_64

| Directory | Purpose |
| :-------: | ------------------------------------------------------ |
| topic | Benchmarks for `publisher` and `subscription` features |
| service | Benchmarks for `client` and `service` features |
| startup | Benchmarks for measuring the startup time consumption |
**Software:**

## Run tests
- **OS:** Ubuntu 24.04.3 LTS (WSL2)
- **Kernel:** 6.6.87.2-microsoft-standard-WSL2
- **ROS 2:** [Jazzy Patch Release 6](https://github.com/ros2/ros2/releases/tag/release-jazzy-20250820)
- **C++ Compiler:** GCC 13.3.0 (Ubuntu 13.3.0-6ubuntu2~24.04)
- **Python:** 3.12.3
- **Node.js:** v22.18.0
- **rclnodejs:** [v1.5.0](https://www.npmjs.com/package/rclnodejs/v/1.5.0)

1.Benchmark for [rclcpp](https://github.com/ros2/rclcpp)
### Benchmark Results

- Compile the source files, `cd benchmark/rclcpp/` and run `colcon build`
- The executable files locate at `build/rclcpp_benchmark/`
- `your_benchmark -h` for help.
Benchmark parameters: 1000 iterations, 1024KB message size

2.Benchmark for [rclpy](https://github.com/ros2/rclpy)
| Client Library | Topic (ms) | Service (ms) | Performance Ratio |
| ----------------------- | ---------- | ------------ | ------------------- |
| **rclcpp (C++)** | 168 | 627 | Baseline (fastest) |
| **rclpy (Python)** | 1,618 | 15,380 | 9.6x / 24.5x slower |
| **rclnodejs (Node.js)** | 744 | 927 | 4.4x / 1.5x slower |

- Enter the Python scripts folder `benchmark/rclpy/`
- `python3 your_benchmark -h` for help.
_Last updated: August 30, 2025_

3.Benchmark for rclnodejs
**Notes:**

- Enter the Node.js scripts folder `benchmark/rclnodejs/`
- `node your_benchmark -h` for help.
- Topic benchmarks: All libraries completed successfully with 1024KB messages
- Service benchmarks: All libraries completed successfully with 1024KB responses
- Performance ratios are relative to C++ baseline
- C++ shows excellent performance as expected for a compiled language
- Node.js performs significantly better than Python, likely due to V8 optimizations
- Python service performance shows significant overhead with large payloads compared to topics

## Running Benchmarks

### C++ (rclcpp)

```bash
cd benchmark/rclcpp/
mkdir -p build && cd build
source ~/Download/ros2-linux/local_setup.bash # Adjust path
cmake .. && make
# Run from build directory:
./publisher-stress-test -r 1000 -s 1024
./client-stress-test -r 1000
```

### Python (rclpy)

```bash
cd benchmark/rclpy/
source ~/Download/ros2-linux/local_setup.bash # Adjust path
python3 topic/publisher-stress-test.py -r 1000 -s 1024
python3 service/client-stress-test.py -r 1000
```

### JavaScript (rclnodejs)

```bash
cd /path/to/rclnodejs/ # Project root
source ~/Download/ros2-linux/local_setup.bash # Adjust path
node benchmark/rclnodejs/topic/publisher-stress-test.js -r 1000 -s 1024
node benchmark/rclnodejs/service/client-stress-test.js -r 1000
```

## Test Workflow

For complete tests, run subscriber/service first, then publisher/client:

**Topic Test:**

```bash
# Terminal 1: Start subscriber (adjust for your language)
python3 topic/subscription-stress-test.py # Python
./subscription-stress-test # C++ (from build dir)
node benchmark/rclnodejs/topic/subscription-stress-test.js # Node.js

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

**Service Test:**

```bash
# Terminal 1: Start service (adjust for your language)
python3 service/service-stress-test.py -s 1024 # Python
./service-stress-test -s 1024 # C++ (from build dir)
node benchmark/rclnodejs/service/service-stress-test.js -s 1024 # Node.js

# Terminal 2: Run client benchmark
python3 service/client-stress-test.py -r 1000 # Python
./client-stress-test -r 1000 # C++ (from build dir)
node benchmark/rclnodejs/service/client-stress-test.js -r 1000 # Node.js
```

## Message Types

- **Topics**: `std_msgs/msg/UInt8MultiArray` (configurable size)
- **Services**: `nav_msgs/srv/GetMap` (map data request/response)

## Notes

- All benchmarks use high-precision timing for accurate measurements
- C++ provides baseline performance; Python/JavaScript show expected interpreted language overhead
- All implementations are now working correctly across the three client libraries
- Results vary by system configuration; use relative comparisons between client libraries
- Service benchmarks involve request-response cycles with substantial data payloads (OccupancyGrid maps)
11 changes: 7 additions & 4 deletions benchmark/rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,10 +1,14 @@
cmake_minimum_required(VERSION 3.5)
cmake_minimum_required(VERSION 3.8)

project(rclcpp_benchmark)

# Default to C++14
# Default to C++17
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD 17)
endif()

if(CMAKE_CXX_STANDARD LESS 17)
set(CMAKE_CXX_STANDARD 17)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
Expand Down Expand Up @@ -39,6 +43,5 @@ custom_executable(publisher-stress-test topic/publisher-stress-test.cpp)
custom_executable(subscription-stress-test topic/subscription-stress-test.cpp)
custom_executable(client-stress-test service/client-stress-test.cpp)
custom_executable(service-stress-test service/service-stress-test.cpp)
custom_executable(startup-test startup/startup-test.cpp)

ament_package()
18 changes: 14 additions & 4 deletions benchmark/rclcpp/package.xml
Original file line number Diff line number Diff line change
@@ -1,14 +1,24 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>rclcpp_benchmark</name>
<version>0.0.1</version>
<description>Benchmark for rclcpp</description>
<maintainer email="[email protected]">Minggang Wang</maintainer>
<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>rclcpp</build_depend>
<exec_depend>rclcpp</exec_depend>

<depend>rclcpp</depend>
<depend>example_interfaces</depend>
<depend>sensor_msgs</depend>
<depend>std_msgs</depend>
<depend>std_srvs</depend>
<depend>nav_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
Expand Down
45 changes: 32 additions & 13 deletions benchmark/rclcpp/service/client-stress-test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,11 +22,10 @@
#include "utilities.hpp"

void ShowUsage(const std::string name) {
std::cerr << "Usage: " << name << " [options]\n"
<< "\nOptions:\n"
<< "\n--run <n> \tHow many times to run\n"
<< "--help \toutput usage information"
<< std::endl;
std::cerr << "Usage: " << name << " [options]\n"
<< "\nOptions:\n"
<< "\n-r, --run <n> \tHow many times to run\n"
<< "-h, --help \toutput usage information" << std::endl;
}

int main(int argc, char* argv[]) {
Expand All @@ -36,34 +35,54 @@ int main(int argc, char* argv[]) {
for (int i = 1; i < argc; i++) {
std::string arg = argv[i];
if ((arg == "-h") || (arg == "--help")) {
ShowUsage(argv[0]);
return 0;
ShowUsage(argv[0]);
return 0;
} else if (arg.find("--run=") != std::string::npos) {
total_times = std::stoi(arg.substr(arg.find("=") + 1));
total_times = std::stoi(arg.substr(arg.find("=") + 1));
} else if (arg == "-r" && i + 1 < argc) {
total_times = std::stoi(argv[++i]);
}
}
printf(
"The client will send a GetMap request continuously until receiving "
"response %d times.\n", total_times);
"response %d times.\n",
total_times);

auto start = std::chrono::high_resolution_clock::now();
auto node = rclcpp::Node::make_shared("stress_client_rclcpp");
auto client = node->create_client<nav_msgs::srv::GetMap>("get_map");
auto request = std::make_shared<nav_msgs::srv::GetMap::Request>();
auto received_times = 0;

// Wait for service to be available
while (!client->wait_for_service(std::chrono::seconds(1))) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(rclcpp::get_logger("rclcpp"),
"Interrupted while waiting for the service. Exiting.");
return 0;
}
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),
"Service not available, waiting again...");
}

while (rclcpp::ok()) {
if (received_times > total_times) {
if (received_times >= total_times) {
Copy link
Preview

Copilot AI Aug 29, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Similar to the publisher issue, this condition should be checked before making the service call to avoid making one extra request beyond the requested count.

Copilot uses AI. Check for mistakes.

rclcpp::shutdown();
auto end = std::chrono::high_resolution_clock::now();
LogTimeConsumption(start, end);
break;
} else {
auto result_future = client->async_send_request(request);
if (rclcpp::spin_until_future_complete(node, result_future) !=
rclcpp::executor::FutureReturnCode::SUCCESS) {
RCLCPP_ERROR(node->get_logger(), "service call failed.");

// Spin until future is ready using the node directly
auto future_status = rclcpp::spin_until_future_complete(
node, result_future, std::chrono::seconds(10));

if (future_status != rclcpp::FutureReturnCode::SUCCESS) {
RCLCPP_ERROR(node->get_logger(), "Service call failed or timed out.");
return 1;
}

auto result = result_future.get();
received_times++;
}
Expand Down
33 changes: 15 additions & 18 deletions benchmark/rclcpp/service/service-stress-test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,11 +21,10 @@
#include "rclcpp/rclcpp.hpp"

void ShowUsage(const std::string name) {
std::cerr << "Usage: " << name << " [options]\n"
<< "\nOptions:\n"
<< "\n--size [size_kb]\tThe block size\n"
<< "--help \toutput usage information"
<< std::endl;
std::cerr << "Usage: " << name << " [options]\n"
<< "\nOptions:\n"
<< "\n-s, --size [size_kb]\tThe block size\n"
<< "-h, --help \toutput usage information" << std::endl;
}

int main(int argc, char* argv[]) {
Expand All @@ -35,26 +34,24 @@ int main(int argc, char* argv[]) {
for (int i = 1; i < argc; i++) {
std::string arg = argv[i];
if ((arg == "-h") || (arg == "--help")) {
ShowUsage(argv[0]);
return 0;
ShowUsage(argv[0]);
return 0;
} else if (arg.find("--size=") != std::string::npos) {
amount = std::stoi(arg.substr(arg.find("=") + 1));
amount = std::stoi(arg.substr(arg.find("=") + 1));
} else if (arg == "-s" && i + 1 < argc) {
amount = std::stoi(argv[++i]);
}
}

auto node = rclcpp::Node::make_shared("stress_service_rclcpp");
auto sub = node->create_service<nav_msgs::srv::GetMap>(
auto service = node->create_service<nav_msgs::srv::GetMap>(
"get_map",
[amount](const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<nav_msgs::srv::GetMap::Request> request,
const std::shared_ptr<nav_msgs::srv::GetMap::Response> response) {
(void)request_header;
[amount](const std::shared_ptr<nav_msgs::srv::GetMap::Request> request,
std::shared_ptr<nav_msgs::srv::GetMap::Response> response) {
(void)request;
response->map.header.stamp.sec = 123456;
response->map.header.stamp.nanosec = 789;
response->map.header.stamp = rclcpp::Clock().now();
response->map.header.frame_id = "main_frame";
response->map.info.map_load_time.sec = 123456;
response->map.info.map_load_time.nanosec = 789;
response->map.info.map_load_time = rclcpp::Clock().now();
response->map.info.resolution = 1.0;
response->map.info.width = 1024;
response->map.info.height = 768;
Expand All @@ -64,7 +61,7 @@ int main(int argc, char* argv[]) {
response->map.info.origin.orientation.x = 0.0;
response->map.info.origin.orientation.y = 0.0;
response->map.info.origin.orientation.z = 0.0;
Copy link
Preview

Copilot AI Aug 29, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This quaternion normalization fix should be documented. The change from w=0.0 to w=1.0 corrects an invalid quaternion (zero quaternion) to a valid identity quaternion representing no rotation.

Copilot uses AI. Check for mistakes.

response->map.info.origin.orientation.w = 0.0;
response->map.info.origin.orientation.w = 1.0;
response->map.data = std::vector<int8_t>(1024 * amount, 125);
});
rclcpp::spin(node);
Expand Down
Loading
Loading