Adds rosbridge_suite to the Jetson stack so the browser dashboard can
subscribe to ROS2 topics via roslibjs over ws://jetson:9090.
docker-compose.yml
New service: saltybot-rosbridge
- Runs saltybot_bringup/launch/rosbridge.launch.py
- network_mode: host → port 9090 directly reachable on Jetson LAN
- Depends on saltybot-ros2, stm32-bridge, csi-cameras
saltybot_bringup/launch/rosbridge.launch.py
- rosbridge_websocket node (port 9090, params from rosbridge_params.yaml)
- 4× image_transport/republish nodes: compress CSI camera streams
/camera/<name>/image_raw → /camera/<name>/image_raw/compressed (JPEG 75%)
saltybot_bringup/config/rosbridge_params.yaml
Whitelisted topics:
/map /scan /tf /tf_static
/saltybot/imu /saltybot/balance_state
/cmd_vel
/person/*
/camera/*/image_raw/compressed
max_message_size: 10 MB (OccupancyGrid headroom)
saltybot_bringup/SENSORS.md
Added rosbridge connection section with roslibjs snippet,
topic reference table, bandwidth estimates, and throttle_rate tips.
saltybot_bringup/package.xml
Added exec_depend: rosbridge_server, image_transport,
image_transport_plugins (all already installed in Docker image).
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
98 lines
3.7 KiB
Python
98 lines
3.7 KiB
Python
"""
|
||
rosbridge.launch.py — rosbridge WebSocket server + compressed image transport
|
||
|
||
Starts two things:
|
||
1. rosbridge_websocket — WebSocket server on port 9090 (roslibjs-compatible)
|
||
2. image_transport/republish × 4 — compresses each CSI camera's raw stream
|
||
/camera/<name>/image_raw → /camera/<name>/image_raw/compressed
|
||
|
||
Prerequisites (already installed in saltybot/ros2-humble:jetson-orin):
|
||
apt install ros-humble-rosbridge-server
|
||
apt install ros-humble-image-transport-plugins # supplies compressed plugin
|
||
|
||
Browser connection:
|
||
var ros = new ROSLIB.Ros({ url: 'ws://<jetson-ip>:9090' });
|
||
|
||
Topic whitelist is configured in config/rosbridge_params.yaml.
|
||
|
||
Bandwidth tips:
|
||
- Subscribe to /camera/<name>/image_raw/compressed, not raw images.
|
||
- Use throttle_rate in ROSLIB.Topic to cap camera update rate:
|
||
new ROSLIB.Topic({ ... messageType: 'sensor_msgs/CompressedImage',
|
||
throttle_rate: 200 }) // max 5 fps per camera
|
||
- Subscribe to /map with throttle_rate: 5000 (0.2 Hz is enough for display).
|
||
|
||
Usage:
|
||
ros2 launch saltybot_bringup rosbridge.launch.py
|
||
|
||
Verify:
|
||
ros2 topic echo /rosbridge_websocket/status
|
||
# In browser console:
|
||
# var ros = new ROSLIB.Ros({ url: 'ws://jetson.local:9090' });
|
||
# ros.on('connection', () => console.log('connected'));
|
||
"""
|
||
|
||
import os
|
||
from launch import LaunchDescription
|
||
from launch_ros.actions import Node
|
||
from ament_index_python.packages import get_package_share_directory
|
||
|
||
|
||
# Camera names matching saltybot_cameras/launch/csi_cameras.launch.py
|
||
# Topics: /camera/<name>/image_raw (published by v4l2_camera_node)
|
||
_CAMERAS = ['front', 'left', 'rear', 'right']
|
||
|
||
# JPEG quality for compressed output (0–100).
|
||
# 75 = good quality/size trade-off at 640×480: ~15–25 KB/frame.
|
||
# Lower to 50 for tighter bandwidth budgets; raise to 90 for inspection use.
|
||
_JPEG_QUALITY = 75
|
||
|
||
|
||
def generate_launch_description():
|
||
pkg_share = get_package_share_directory('saltybot_bringup')
|
||
params_file = os.path.join(pkg_share, 'config', 'rosbridge_params.yaml')
|
||
|
||
# ── rosbridge WebSocket server ────────────────────────────────────────────
|
||
rosbridge = Node(
|
||
package='rosbridge_server',
|
||
executable='rosbridge_websocket',
|
||
name='rosbridge_websocket',
|
||
parameters=[params_file],
|
||
output='screen',
|
||
)
|
||
|
||
# ── Compressed image republishers ─────────────────────────────────────────
|
||
# image_transport/republish subscribes to raw sensor_msgs/Image and
|
||
# re-publishes as sensor_msgs/CompressedImage using the compressed plugin.
|
||
#
|
||
# Node arguments: ['raw', 'compressed']
|
||
# 'raw' — input transport type
|
||
# 'compressed' — output transport type
|
||
#
|
||
# Topic remappings:
|
||
# in → /camera/<name>/image_raw
|
||
# out/compressed → /camera/<name>/image_raw/compressed
|
||
#
|
||
# Parameter jpeg_quality controls JPEG encoder quality for the
|
||
# compressed publisher. The full parameter path in ROS2 is:
|
||
# /<node_name>/compressed/jpeg_quality
|
||
republishers = [
|
||
Node(
|
||
package='image_transport',
|
||
executable='republish',
|
||
name=f'compress_{name}',
|
||
arguments=['raw', 'compressed'],
|
||
remappings=[
|
||
('in', f'/camera/{name}/image_raw'),
|
||
('out/compressed', f'/camera/{name}/image_raw/compressed'),
|
||
],
|
||
parameters=[{
|
||
'compressed.jpeg_quality': _JPEG_QUALITY,
|
||
}],
|
||
output='screen',
|
||
)
|
||
for name in _CAMERAS
|
||
]
|
||
|
||
return LaunchDescription([rosbridge] + republishers)
|