saltylab-firmware/jetson/docker-compose.yml
sl-firmware 3a7576939e feat(safety): remote e-stop over 4G MQTT (Issue #63)
STM32 firmware:
- safety.h/c: EstopSource enum, safety_remote_estop/clear/get/active()
  CDC 'E'=ESTOP_REMOTE, 'F'=ESTOP_CELLULAR_TIMEOUT, 'Z'=clear latch
- usbd_cdc_if: cdc_estop_request/cdc_estop_clear_request volatile flags
- status: status_update() +remote_estop param; both LEDs fast-blink 200ms
- main.c: immediate motor cutoff highest-priority; arming gated by
  !safety_remote_estop_active(); motor estop auto-clear gated; telemetry
  'es' field 0-4; status_update() updated to 5 args

Safety: IMMEDIATE motor cutoff, latched until explicit Z + DISARMED,
cannot re-arm via MQTT alone (requires RC arm hold). IWDG-safe.

Jetson bridge:
- remote_estop_node.py: paho-mqtt + pyserial, cellular watchdog 5s
- estop_params.yaml, remote_estop.launch.py
- setup.py / package.xml: register node + paho-mqtt dep
- docker-compose.yml: remote-estop service
- test_remote_estop.py: kill/clear/watchdog/latency unit tests

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-01 00:57:01 -05:00

291 lines
9.6 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.

version: "3.8"
# Jetson Orin Nano Super — ROS2 Humble SLAM stack
# Run with: docker compose up -d
# Requires: NVIDIA Container Toolkit (JetPack 6) on host
services:
# ── Core ROS2 + SLAM node ─────────────────────────────────────────────────
saltybot-ros2:
image: saltybot/ros2-humble:jetson-orin
build:
context: .
dockerfile: Dockerfile
container_name: saltybot-ros2
restart: unless-stopped
runtime: nvidia # JetPack NVIDIA runtime
privileged: false # use device passthrough instead
network_mode: host # ROS2 DDS multicast needs host networking
environment:
- NVIDIA_VISIBLE_DEVICES=all
- NVIDIA_DRIVER_CAPABILITIES=all
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
- ROS_DOMAIN_ID=42
- DISPLAY=${DISPLAY:-:0} # for RViz2 on host X11
volumes:
# X11 socket for RViz2
- /tmp/.X11-unix:/tmp/.X11-unix:rw
# ROS2 workspace (host-mounted for live dev)
- ./ros2_ws/src:/ros2_ws/src:rw
# Persistent SLAM maps on NVMe
- /mnt/nvme/saltybot/maps:/maps
# NVMe data volume
- /mnt/nvme/saltybot:/data:rw
# Config files
- ./config:/config:ro
devices:
# RPLIDAR A1M8 — stable symlink via udev
- /dev/rplidar:/dev/rplidar
# STM32 USB CDC bridge — stable symlink via udev
- /dev/stm32-bridge:/dev/stm32-bridge
# RealSense D435i — USB3 device, needs udev rules
- /dev/bus/usb:/dev/bus/usb
# I2C bus (Orin Nano i2c-7 = 40-pin header pins 3/5)
- /dev/i2c-7:/dev/i2c-7
# CSI cameras via V4L2
- /dev/video0:/dev/video0
- /dev/video2:/dev/video2
- /dev/video4:/dev/video4
- /dev/video6:/dev/video6
command: >
bash -c "
source /opt/ros/humble/setup.bash &&
ros2 launch saltybot_bringup slam_rtabmap.launch.py
"
# ── RPLIDAR driver node ────────────────────────────────────────────────────
rplidar:
image: saltybot/ros2-humble:jetson-orin
build:
context: .
dockerfile: Dockerfile
container_name: saltybot-rplidar
restart: unless-stopped
runtime: nvidia
network_mode: host
environment:
- ROS_DOMAIN_ID=42
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
devices:
- /dev/rplidar:/dev/rplidar
command: >
bash -c "
source /opt/ros/humble/setup.bash &&
ros2 launch rplidar_ros rplidar_a1_launch.py
serial_port:=/dev/rplidar
frame_id:=laser
"
# ── RealSense D435i driver node ────────────────────────────────────────────
realsense:
image: saltybot/ros2-humble:jetson-orin
build:
context: .
dockerfile: Dockerfile
container_name: saltybot-realsense
restart: unless-stopped
runtime: nvidia
network_mode: host
environment:
- ROS_DOMAIN_ID=42
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
devices:
- /dev/bus/usb:/dev/bus/usb
volumes:
- /dev:/dev
command: >
bash -c "
source /opt/ros/humble/setup.bash &&
ros2 launch realsense2_camera rs_launch.py
enable_color:=true
enable_depth:=true
enable_gyro:=true
enable_accel:=true
unite_imu_method:=linear_interpolation
depth_module.profile:=640x480x30
rgb_camera.profile:=640x480x30
"
# ── STM32 bridge node (bidirectional serial↔ROS2) ─────────────────────────
stm32-bridge:
image: saltybot/ros2-humble:jetson-orin
build:
context: .
dockerfile: Dockerfile
container_name: saltybot-stm32-bridge
restart: unless-stopped
runtime: nvidia
network_mode: host
environment:
- ROS_DOMAIN_ID=42
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
devices:
- /dev/stm32-bridge:/dev/stm32-bridge
command: >
bash -c "
source /opt/ros/humble/setup.bash &&
ros2 launch saltybot_bridge bridge.launch.py
mode:=bidirectional
serial_port:=/dev/stm32-bridge
"
# ── 4× IMX219 CSI cameras ─────────────────────────────────────────────────
csi-cameras:
image: saltybot/ros2-humble:jetson-orin
build:
context: .
dockerfile: Dockerfile
container_name: saltybot-csi-cameras
restart: unless-stopped
runtime: nvidia
network_mode: host
privileged: true # CSI camera access requires elevated perms
environment:
- ROS_DOMAIN_ID=42
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
- NVIDIA_VISIBLE_DEVICES=all
- NVIDIA_DRIVER_CAPABILITIES=all
devices:
- /dev/video0:/dev/video0
- /dev/video2:/dev/video2
- /dev/video4:/dev/video4
- /dev/video6:/dev/video6
command: >
bash -c "
source /opt/ros/humble/setup.bash &&
ros2 launch saltybot_cameras csi_cameras.launch.py
width:=640
height:=480
fps:=30
"
# ── Surround vision — 360° bird's-eye view + Nav2 camera obstacle layer ─────
saltybot-surround:
# ── rosbridge WebSocket server ────────────────────────────────────────────
# Serves ROS2 topics to the web dashboard (roslibjs) on ws://jetson:9090
#
# Topics exposed (whitelist in ros2_ws/src/saltybot_bringup/config/rosbridge_params.yaml):
# /map /scan /tf /tf_static /saltybot/imu /saltybot/balance_state
# /cmd_vel /person/* /camera/*/image_raw/compressed
#
# Also runs image_transport/republish nodes to compress 4× CSI camera streams.
# Raw 640×480 YUYV → JPEG-compressed sensor_msgs/CompressedImage.
#
# Install (already in image): apt install ros-humble-rosbridge-server
# ros-humble-image-transport-plugins
rosbridge:
image: saltybot/ros2-humble:jetson-orin
build:
context: .
dockerfile: Dockerfile
container_name: saltybot-surround
restart: unless-stopped
runtime: nvidia
network_mode: host
depends_on:
- csi-cameras # IMX219 /camera/*/image_raw must be publishing
environment:
- NVIDIA_VISIBLE_DEVICES=all
- NVIDIA_DRIVER_CAPABILITIES=all
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
- ROS_DOMAIN_ID=42
volumes:
- ./ros2_ws/src:/ros2_ws/src:rw
- ./config:/config:ro
command: >
bash -c "
source /opt/ros/humble/setup.bash &&
ros2 launch saltybot_surround surround_vision.launch.py
start_cameras:=false
camera_height:=0.30
publish_rate:=5.0
container_name: saltybot-rosbridge
restart: unless-stopped
runtime: nvidia
network_mode: host # port 9090 is directly reachable on host
depends_on:
- saltybot-ros2 # needs /map, /tf published
- stm32-bridge # needs /saltybot/imu, /saltybot/balance_state
- csi-cameras # needs /camera/*/image_raw for compression
environment:
- ROS_DOMAIN_ID=42
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
volumes:
- ./ros2_ws/src:/ros2_ws/src:rw
- ./config:/config:ro
# Port 9090 is accessible on all host interfaces via network_mode: host.
# To restrict to a specific interface, set host: "192.168.x.x" in
# rosbridge_params.yaml instead of using Docker port mappings.
command: >
bash -c "
source /opt/ros/humble/setup.bash &&
source /ros2_ws/install/local_setup.bash 2>/dev/null || true &&
ros2 launch saltybot_bringup rosbridge.launch.py
"
# ── Nav2 autonomous navigation stack ────────────────────────────────────────
# -- Remote e-stop bridge (MQTT over 4G -> STM32 CDC) ----------------------
remote-estop:
image: saltybot/ros2-humble:jetson-orin
build:
context: .
dockerfile: Dockerfile
container_name: saltybot-remote-estop
restart: unless-stopped
runtime: nvidia
network_mode: host
depends_on:
- stm32-bridge
environment:
- ROS_DOMAIN_ID=42
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
devices:
- /dev/stm32-bridge:/dev/stm32-bridge
volumes:
- ./ros2_ws/src:/ros2_ws/src:rw
- ./config:/config:ro
command: >
bash -c "
source /opt/ros/humble/setup.bash &&
source /ros2_ws/install/local_setup.bash 2>/dev/null || true &&
pip install paho-mqtt --quiet 2>/dev/null || true &&
ros2 launch saltybot_bridge remote_estop.launch.py
"
saltybot-nav2:
image: saltybot/ros2-humble:jetson-orin
build:
context: .
dockerfile: Dockerfile
container_name: saltybot-nav2
restart: unless-stopped
runtime: nvidia
network_mode: host
depends_on:
- saltybot-ros2 # RTAB-Map + sensors must be running first
environment:
- NVIDIA_VISIBLE_DEVICES=all
- NVIDIA_DRIVER_CAPABILITIES=all
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
- ROS_DOMAIN_ID=42
volumes:
- ./ros2_ws/src:/ros2_ws/src:rw
- ./config:/config:ro
command: >
bash -c "
source /opt/ros/humble/setup.bash &&
ros2 launch saltybot_bringup nav2.launch.py
"
volumes:
saltybot-maps:
driver: local