Skip to content

Commit 30c315e

Browse files
committed
new readme and default port 9090
Entire-Checkpoint: b531b04d554b
1 parent 44e5da1 commit 30c315e

11 files changed

Lines changed: 87 additions & 96 deletions

File tree

CLAUDE.md

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -135,7 +135,7 @@ BridgeServer does NOT own timers. The entry point (`main.cpp`) drives the event
135135

136136
### Communication Pattern
137137

138-
**WebSocket** (single port, default 8080):
138+
**WebSocket** (single port, default 9090):
139139
- **Text frames**: JSON API commands and responses (get_topics, subscribe, heartbeat, pause, resume, unsubscribe)
140140
- **Binary frames**: ZSTD-compressed aggregated message stream
141141

@@ -220,20 +220,20 @@ pre-commit run -a
220220

221221
### ROS2 (via `--ros-args -p`):
222222
```yaml
223-
port: 8080 # WebSocket port
223+
port: 9090 # WebSocket port
224224
publish_rate: 50.0 # Hz
225225
session_timeout: 10.0 # seconds
226226
strip_large_messages: true # Strip Image/PointCloud2/etc data fields
227227
```
228228
229229
### RTI (via CLI flags):
230230
```bash
231-
pj_bridge_rti --domains 0 1 --port 8080 --publish-rate 50 --session-timeout 10
231+
pj_bridge_rti --domains 0 1 --port 9090 --publish-rate 50 --session-timeout 10
232232
```
233233

234234
### FastDDS (via CLI flags):
235235
```bash
236-
pj_bridge_fastdds --domains 0 1 --port 8080 --publish-rate 50 --session-timeout 10
236+
pj_bridge_fastdds --domains 0 1 --port 9090 --publish-rate 50 --session-timeout 10
237237
```
238238

239239
## Important Design Decisions

README.md

Lines changed: 66 additions & 79 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@
44

55
A high-performance bridge server that forwards middleware topic content over WebSocket to PlotJuggler clients. Three backends share a common core:
66

7-
- **ROS2** (`pj_bridge_ros2`) — ROS2 Humble / Jazzy via `rclcpp`
7+
- **ROS2** (`pj_bridge_ros2`) — ROS2 Humble / Jazzy / Kilted via `rclcpp`
88
- **FastDDS** (`pj_bridge_fastdds`) — eProsima Fast DDS 3.4 (standalone, no ROS2 required)
99
- **RTI** (`pj_bridge_rti`) — RTI Connext DDS (build disabled, code preserved)
1010

@@ -20,51 +20,82 @@ independently.
2020
- **No DDS Required**: Clients connect via WebSocket (single port) without needing ROS2/DDS installed
2121
- **High Performance**: 50 Hz message aggregation with ZSTD compression
2222
- **Multi-Client Support**: Multiple clients can connect simultaneously with shared subscriptions
23-
- **Session Management**: Automatic cleanup of disconnected clients via heartbeat monitoring and WebSocket close events
2423
- **Runtime Schema Discovery**: Automatic extraction of message schemas from installed ROS2 packages
25-
- **Zero-Copy Design**: Efficient message handling using shared pointers and move semantics
2624
- **Large Message Stripping**: Automatic stripping of large array fields (Image, PointCloud2, LaserScan, OccupancyGrid) to reduce bandwidth while preserving metadata
27-
- **Type-Safe Error Handling**: Comprehensive error reporting using `tl::expected`
2825

29-
## Architecture
30-
31-
For detailed architecture documentation, see [docs/ARCHITECTURE.md](docs/ARCHITECTURE.md).
32-
33-
## Building
26+
## CI Status
3427

3528
| | Humble | Jazzy | Kilted |
3629
|--|--------|-------|--------|
3730
| **Pixi** | [![Pixi: Humble](https://github.com/PlotJuggler/plotjuggler_bridge/actions/workflows/pixi_humble.yaml/badge.svg?branch=main)](https://github.com/PlotJuggler/plotjuggler_bridge/actions/workflows/pixi_humble.yaml) | [![Pixi: Jazzy](https://github.com/PlotJuggler/plotjuggler_bridge/actions/workflows/pixi_jazzy.yaml/badge.svg?branch=main)](https://github.com/PlotJuggler/plotjuggler_bridge/actions/workflows/pixi_jazzy.yaml) | [![Pixi: Kilted](https://github.com/PlotJuggler/plotjuggler_bridge/actions/workflows/pixi_kilted.yaml/badge.svg?branch=main)](https://github.com/PlotJuggler/plotjuggler_bridge/actions/workflows/pixi_kilted.yaml) |
3831
| **colcon** | [![ROS: Humble](https://github.com/PlotJuggler/plotjuggler_bridge/actions/workflows/ros_humble.yaml/badge.svg?branch=main)](https://github.com/PlotJuggler/plotjuggler_bridge/actions/workflows/ros_humble.yaml) | [![ROS: Jazzy](https://github.com/PlotJuggler/plotjuggler_bridge/actions/workflows/ros_jazzy.yaml/badge.svg?branch=main)](https://github.com/PlotJuggler/plotjuggler_bridge/actions/workflows/ros_jazzy.yaml) | [![ROS: Kilted](https://github.com/PlotJuggler/plotjuggler_bridge/actions/workflows/ros_kilted.yaml/badge.svg?branch=main)](https://github.com/PlotJuggler/plotjuggler_bridge/actions/workflows/ros_kilted.yaml) |
3932

33+
## Configuration Parameters
34+
35+
| Parameter | Type | Default | Description |
36+
|-----------|------|---------|-------------|
37+
| `port` | int | 9090 | WebSocket server port |
38+
| `publish_rate` | double | 50.0 | Aggregation publish rate in Hz |
39+
| `session_timeout` | double | 10.0 | Client timeout duration in seconds |
40+
| `strip_large_messages` | bool | true | Strip large arrays from Image, PointCloud2, LaserScan, OccupancyGrid messages |
41+
42+
## Just "Download and Run"
43+
44+
### Pixi
45+
46+
Install the pre-built package from the [PlotJuggler conda channel](https://prefix.dev/channels/plotjuggler) — no build step required.
47+
48+
```bash
49+
# Install (change humble to jazzy or kilted as needed)
50+
pixi global install pj-bridge-ros2-humble \
51+
-c https://prefix.dev/plotjuggler -c robostack-staging -c conda-forge
52+
53+
# Run (add arguments if different from default)
54+
pj_bridge_ros2 --ros-args -p port:=9090
55+
```
56+
57+
### AppImage
58+
59+
Pre-built AppImages are available from [GitHub Releases](https://github.com/PlotJuggler/plotjuggler_bridge/releases).
60+
61+
Example for ROS2 Humble:
62+
63+
```bash
64+
# Do once after downloading the file
65+
chmod +x pj_bridge_ros2-humble-x86_64.AppImage
66+
67+
# Run (add arguments if different from default)
68+
./pj_bridge_ros2-humble-x86_64.AppImage --ros-args -p port:=9090
69+
```
4070

71+
## Build Instructions
4172

4273
All dependencies (IXWebSocket, spdlog, nlohmann_json, ZSTD) are provided by the dependency manager — nothing is vendored except `tl::expected`.
4374

44-
### ROS2 backend — Pixi (recommended)
75+
### ROS2 — Pixi
4576

4677
[Pixi](https://pixi.sh) manages the full toolchain including ROS2 via [RoboStack](https://robostack.github.io/).
4778

48-
```bash
49-
git clone <repository_url> pj_bridge && cd pj_bridge
79+
From the cloned **plotjuggler_bridge** directory:
5080

51-
# Humble
81+
```bash
82+
# Build and test (change humble to jazzy or kilted as needed)
5283
pixi run -e humble build
5384
pixi run -e humble test
5485

55-
# Jazzy
56-
pixi run -e jazzy build
57-
pixi run -e jazzy test
86+
# Run
87+
pixi shell -e humble
88+
ros2 run pj_bridge pj_bridge_ros2
5889
```
5990

60-
### ROS2 backend — colcon
91+
### ROS2 — colcon
6192

6293
Standard ROS2 build using `colcon`. Dependencies are installed via `rosdep`; only IXWebSocket is fetched automatically via CMake FetchContent.
6394

6495
```bash
6596
# Set up workspace
6697
mkdir -p ~/ws_plotjuggler/src && cd ~/ws_plotjuggler/src
67-
git clone <repository_url> pj_bridge
98+
git clone https://github.com/PlotJuggler/plotjuggler_bridge && cd plotjuggler_bridge
6899

69100
# Install dependencies
70101
source /opt/ros/${ROS_DISTRO}/setup.bash
@@ -74,77 +105,33 @@ rosdep install --from-paths pj_bridge --ignore-src -y
74105
cd ~/ws_plotjuggler
75106
colcon build --packages-select pj_bridge --cmake-args -DCMAKE_BUILD_TYPE=Release
76107
colcon test --packages-select pj_bridge && colcon test-result --verbose
108+
109+
# Run
110+
source install/setup.bash
111+
ros2 run pj_bridge pj_bridge_ros2
77112
```
78113

79-
### FastDDS backend — Conan
114+
### FastDDS — Conan
115+
116+
Standalone build using eProsima Fast DDS (no ROS2 required).
117+
118+
From the cloned **plotjuggler_bridge** directory:
80119

81120
```bash
82-
cd pj_bridge
121+
# Build
83122
conan install . --output-folder=build_fastdds --build=missing -s build_type=Release
84123
cd build_fastdds
85124
cmake .. -DCMAKE_BUILD_TYPE=Release -DENABLE_FASTDDS=ON \
86125
-DCMAKE_TOOLCHAIN_FILE=conan_toolchain.cmake
87126
make -j$(nproc)
88-
```
89-
90-
### Running Tests
91-
92-
```bash
93-
# Via pixi (154 unit tests)
94-
pixi run -e humble test
95127

96-
# Or manually after building
97-
colcon test --packages-select pj_bridge && colcon test-result --verbose
128+
# Run
129+
./pj_bridge_fastdds --domains 0 1
98130
```
99131

100-
## Usage
101-
102-
### Starting the Server
103-
104-
#### ROS2 backend
105-
106-
```bash
107-
# Default (port 8080, 50 Hz, 10 s timeout)
108-
ros2 run pj_bridge pj_bridge_ros2
109-
110-
# Custom
111-
ros2 run pj_bridge pj_bridge_ros2 --ros-args \
112-
-p port:=9090 -p publish_rate:=50.0 -p session_timeout:=10.0
113-
```
114-
115-
#### FastDDS backend
116-
117-
```bash
118-
pj_bridge_fastdds --domains 0 1 --port 8080 --publish-rate 50 --session-timeout 10
119-
```
120-
121-
### Configuration Parameters
122-
123-
| Parameter | Type | Default | Description |
124-
|-----------|------|---------|-------------|
125-
| `port` | int | 9090 | WebSocket server port |
126-
| `publish_rate` | double | 50.0 | Aggregation publish rate in Hz |
127-
| `session_timeout` | double | 10.0 | Client timeout duration in seconds |
128-
| `strip_large_messages` | bool | true | Strip large arrays from Image, PointCloud2, LaserScan, OccupancyGrid messages |
129-
130-
### Testing with Sample Data
131-
132-
```bash
133-
# Terminal 1: Play rosbag
134-
source /opt/ros/humble/setup.bash
135-
ros2 bag play /path/to/sample.mcap --loop
136-
137-
# Terminal 2: Run server
138-
source /opt/ros/humble/setup.bash
139-
source ~/ws_plotjuggler/install/setup.bash
140-
ros2 run pj_bridge pj_bridge_node
141-
142-
# Terminal 3: Run Python test client
143-
cd ~/ws_plotjuggler/src/pj_bridge
144-
python3 tests/integration/test_client.py --subscribe /topic1 /topic2
145-
```
132+
## Documentation
146133

147-
## API Protocol
134+
- For detailed architecture documentation, see [docs/ARCHITECTURE.md](docs/ARCHITECTURE.md).
148135

149136
For the full API protocol documentation (commands, responses, binary wire format), see [docs/API.md](docs/API.md).
150137

@@ -155,15 +142,15 @@ For the full API protocol documentation (commands, responses, binary wire format
155142
Another process is using the port. Either kill the conflicting process or use a custom port:
156143

157144
```bash
158-
ros2 run pj_bridge pj_bridge_node --ros-args -p port:=9090
145+
ros2 run pj_bridge pj_bridge_ros2 --ros-args -p port:=9090
159146
```
160147

161148
### Client receives no data
162149

163150
1. Verify server is running: `ps aux | grep pj_bridge`
164151
2. Check topics are being published: `ros2 topic list`
165152
3. Verify heartbeat is being sent (required every 1 second)
166-
4. Check server logs: `ros2 run pj_bridge pj_bridge_node --ros-args --log-level debug`
153+
4. Check server logs: `ros2 run pj_bridge pj_bridge_ros2 --ros-args --log-level debug`
167154

168155
### "Failed to get schema for topic" error
169156

@@ -178,7 +165,7 @@ ros2 interface show <package_name>/msg/<MessageType>
178165
The client stopped sending heartbeats. Ensure the client sends a heartbeat every 1 second. The default timeout is 10 seconds. Increase if needed:
179166

180167
```bash
181-
ros2 run pj_bridge pj_bridge_node --ros-args -p session_timeout:=20.0
168+
ros2 run pj_bridge pj_bridge_ros2 --ros-args -p session_timeout:=20.0
182169
```
183170

184171
## License

app/include/pj_bridge/bridge_server.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -60,14 +60,14 @@ class BridgeServer {
6060
* @param topic_source Backend-specific topic discovery and schema provider
6161
* @param subscription_manager Backend-specific subscription manager
6262
* @param middleware Middleware interface for network communication
63-
* @param port Server port (default: 8080)
63+
* @param port Server port (default: 9090)
6464
* @param session_timeout Session timeout in seconds (default: 10.0)
6565
* @param publish_rate Message aggregation publish rate in Hz (default: 50.0)
6666
*/
6767
explicit BridgeServer(
6868
std::shared_ptr<TopicSourceInterface> topic_source,
6969
std::shared_ptr<SubscriptionManagerInterface> subscription_manager,
70-
std::shared_ptr<MiddlewareInterface> middleware, int port = 8080, double session_timeout = 10.0,
70+
std::shared_ptr<MiddlewareInterface> middleware, int port = 9090, double session_timeout = 10.0,
7171
double publish_rate = 50.0);
7272

7373
/// Shuts down middleware before members are destroyed, preventing

conda.recipe/recipe.yaml

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,9 @@ build:
1919
-DBUILD_TESTING=OFF \
2020
-S . -B build
2121
cmake --build build --target install
22+
# Symlink into bin/ so pixi global install auto-exposes the executable
23+
mkdir -p $PREFIX/bin
24+
ln -sf ../lib/pj_bridge/pj_bridge_ros2 $PREFIX/bin/pj_bridge_ros2
2225
2326
requirements:
2427
build:
@@ -49,6 +52,7 @@ tests:
4952
- package_contents:
5053
files:
5154
- lib/pj_bridge/pj_bridge_ros2
55+
- bin/pj_bridge_ros2
5256

5357
about:
5458
homepage: https://github.com/PlotJuggler/plotjuggler_bridge

docs/API.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
# API Protocol
22

3-
`pj_ros_bridge` uses a single WebSocket port (default 8080). Text frames carry JSON API requests/responses; binary frames carry ZSTD-compressed aggregated message data.
3+
`pj_ros_bridge` uses a single WebSocket port (default 9090). Text frames carry JSON API requests/responses; binary frames carry ZSTD-compressed aggregated message data.
44

55
## Request IDs and Protocol Version
66

docs/ARCHITECTURE.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,7 @@ pj_bridge is a multi-backend bridge server that forwards middleware topic data o
2828

2929
## Communication Pattern
3030

31-
Single WebSocket port (default 8080), two frame types:
31+
Single WebSocket port (default 9090), two frame types:
3232

3333
- **Text frames**: JSON API requests and responses (`get_topics`, `subscribe`, `unsubscribe`, `heartbeat`, `pause`, `resume`)
3434
- **Binary frames**: ZSTD-compressed aggregated message stream, sent per-client based on their subscriptions

fastdds/src/main.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -32,14 +32,14 @@ int main(int argc, char* argv[]) {
3232
CLI::App app{"pj_bridge eProsima FastDDS Backend"};
3333

3434
std::vector<int32_t> domain_ids;
35-
int port = 8080;
35+
int port = 9090;
3636
double publish_rate = 50.0;
3737
double session_timeout = 10.0;
3838
std::string log_level = "info";
3939
bool stats_enabled = false;
4040

4141
app.add_option("--domains,-d", domain_ids, "DDS domain IDs")->required()->expected(1, -1);
42-
app.add_option("--port,-p", port, "WebSocket port")->default_val(8080)->check(CLI::Range(1, 65535));
42+
app.add_option("--port,-p", port, "WebSocket port")->default_val(9090)->check(CLI::Range(1, 65535));
4343
app.add_option("--publish-rate", publish_rate, "Aggregation publish rate in Hz")->default_val(50.0);
4444
app.add_option("--session-timeout", session_timeout, "Session timeout in seconds")->default_val(10.0);
4545
app.add_option("--log-level", log_level, "Log level (trace, debug, info, warn, error)")->default_val("info");

launch/test_topics.launch.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@
1616

1717
def generate_launch_description():
1818
port_arg = DeclareLaunchArgument(
19-
"port", default_value="8080", description="WebSocket server port"
19+
"port", default_value="9090", description="WebSocket server port"
2020
)
2121
publish_rate_arg = DeclareLaunchArgument(
2222
"publish_rate",

ros2/src/main.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@ int main(int argc, char** argv) {
3636
RCLCPP_INFO(node->get_logger(), "Starting pj_bridge (ROS2 backend)...");
3737

3838
// Declare and get parameters
39-
node->declare_parameter<int>("port", 8080);
39+
node->declare_parameter<int>("port", 9090);
4040
node->declare_parameter<double>("publish_rate", 50.0);
4141
node->declare_parameter<double>("session_timeout", 10.0);
4242
node->declare_parameter<bool>("strip_large_messages", true);

rti/src/main.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -32,15 +32,15 @@ int main(int argc, char* argv[]) {
3232
CLI::App app{"pj_bridge RTI DDS Backend"};
3333

3434
std::vector<int32_t> domain_ids;
35-
int port = 8080;
35+
int port = 9090;
3636
double publish_rate = 50.0;
3737
double session_timeout = 10.0;
3838
std::string qos_profile;
3939
std::string log_level = "info";
4040
bool stats_enabled = false;
4141

4242
app.add_option("--domains,-d", domain_ids, "DDS domain IDs")->required()->expected(1, -1);
43-
app.add_option("--port,-p", port, "WebSocket port")->default_val(8080)->check(CLI::Range(1, 65535));
43+
app.add_option("--port,-p", port, "WebSocket port")->default_val(9090)->check(CLI::Range(1, 65535));
4444
app.add_option("--publish-rate", publish_rate, "Aggregation publish rate in Hz")->default_val(50.0);
4545
app.add_option("--session-timeout", session_timeout, "Session timeout in seconds")->default_val(10.0);
4646
app.add_option("--qos-profile", qos_profile, "QoS profile XML file path");

0 commit comments

Comments
 (0)