sl-firmware 6420e07487 feat: rosbridge WebSocket server for web UI (port 9090)
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>
2026-03-01 00:22:02 -05:00

67 lines
3.5 KiB
YAML
Raw Blame History

This file contains ambiguous Unicode characters

This file contains Unicode characters that might be confused with other characters. If you think that this is intentional, you can safely ignore this warning. Use the Escape button to reveal them.

# rosbridge_params.yaml — rosbridge_websocket server configuration
#
# WebSocket endpoint: ws://<jetson-ip>:9090
# Browser client lib: roslibjs (cdn.jsdelivr.net/npm/roslib)
#
# Topic whitelist limits bandwidth and prevents unintended exposure.
# Glob patterns follow Python fnmatch: * matches everything (incl. /).
#
# Bandwidth budget (worst case, all subscriptions active):
# /map ~100 KB/update × 0.2 Hz = ~20 KB/s
# /scan ~5 KB/scan × 5.5 Hz = ~28 KB/s
# /saltybot/imu ~0.2 KB/msg × 50 Hz = ~10 KB/s
# /tf ~1 KB/msg × 10 Hz = ~10 KB/s
# 4× cameras ~20 KB/frame × 5 Hz = ~400 KB/s (JPEG quality 75)
# ─────────────────────────────────────────────────────
# Total ~470 KB/s ≈ 3.8 Mbps
#
# Use throttle_rate in roslibjs subscribe() calls to cap per-topic rates:
# viewer.subscribe({ topic: '/map', throttle_rate: 5000 }) // 0.2 Hz
rosbridge_websocket:
ros__parameters:
# ── Network ──────────────────────────────────────────────────────────────
port: 9090
host: "0.0.0.0" # bind all interfaces (Jetson LAN + USB-C)
address: ""
# ── Authentication ────────────────────────────────────────────────────────
authenticate: false # no auth on local network; enable if exposed
# ── Message size ──────────────────────────────────────────────────────────
# OccupancyGrid /map can exceed 1 MB for large environments.
max_message_size: 10000000 # 10 MB
# ── Topic/service/param whitelists ────────────────────────────────────────
# JSON-encoded glob list. "*" in a glob matches any chars including "/".
# Only topics matching at least one pattern are accessible to clients.
topics_glob: >-
["/map",
"/person/target",
"/person/detections",
"/camera/*/image_raw/compressed",
"/scan",
"/cmd_vel",
"/saltybot/imu",
"/saltybot/balance_state",
"/tf",
"/tf_static"]
services_glob: "[]" # no service calls via WebSocket
params_glob: "[]" # no parameter access via WebSocket
# ── Connection management ─────────────────────────────────────────────────
# Time (s) before dropping a client that stops responding.
unregister_timeout: 10.0
# Fragment timeout: max seconds to wait for all fragments of a large message.
fragment_timeout: 600
# Delay between consecutive outgoing messages (ms). 0 = unlimited.
# Set > 0 (e.g. 10) if browser JS event loop is overwhelmed.
delay_between_messages: 0
# ── Logging ───────────────────────────────────────────────────────────────
# Set to true to log every publish/subscribe call (verbose, dev only).
bson_only_mode: false