saltylab-firmware/jetson/docker-compose.yml
sl-jetson c47ac41573 feat: Jetson Nano platform setup and Docker env (bd-1hcg)
- Dockerfile: L4T R32.6.1 (JetPack 4.6) base + ROS2 Humble + SLAM stack
  (slam_toolbox, Nav2, rplidar_ros, realsense2_camera, robot_localization)
- docker-compose.yml: multi-service stack (ROS2, RPLIDAR A1M8, D435i, STM32 bridge)
  with device passthrough, host networking for DDS, persistent map volume
- docs/pinout.md: full GPIO/I2C/UART pinout for STM32F722 bridge (USB CDC +
  UART fallback), RealSense D435i (USB3), RPLIDAR A1M8, udev rules
- docs/power-budget.md: 10W envelope analysis with per-component breakdown,
  mitigation strategies (RPLIDAR gating, D435i 640p, nvpmodel modes)
- scripts/setup-jetson.sh: host one-shot setup (Docker, nvidia-container-runtime,
  udev rules, MAXN power mode, swap)
- scripts/build-and-run.sh: build/up/down/shell/slam/status helper

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-02-28 12:46:14 -05:00

136 lines
4.2 KiB
YAML

version: "3.8"
# Jetson Nano — ROS2 Humble SLAM stack
# Run with: docker compose up -d
# Requires: NVIDIA Container Runtime (nvidia-docker2) on host
services:
# ── Core ROS2 + SLAM node ─────────────────────────────────────────────────
saltybot-ros2:
image: saltybot/ros2-humble:jetson-nano
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:/ros2_ws/src:rw
# Persistent SLAM maps
- saltybot-maps:/maps
# Config files
- ./config:/config:ro
devices:
# RPLIDAR A1M8 — typically /dev/ttyUSB0
- /dev/ttyUSB0:/dev/ttyUSB0
# STM32 UART bridge — typically /dev/ttyUSB1 or /dev/ttyACM0
- /dev/ttyUSB1:/dev/ttyUSB1
# RealSense D435i — USB3 device, needs udev rules
- /dev/bus/usb:/dev/bus/usb
# I2C bus (Jetson i2c-1 = pins 3/5)
- /dev/i2c-1:/dev/i2c-1
# GPIO (via Jetson.GPIO)
- /sys/class/gpio:/sys/class/gpio
command: >
bash -c "
source /opt/ros/humble/setup.bash &&
ros2 launch saltybot_bringup slam.launch.py
"
# ── RPLIDAR driver node ────────────────────────────────────────────────────
rplidar:
image: saltybot/ros2-humble:jetson-nano
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/ttyUSB0:/dev/ttyUSB0
command: >
bash -c "
source /opt/ros/humble/setup.bash &&
ros2 launch rplidar_ros rplidar_a1_launch.py
serial_port:=/dev/ttyUSB0
frame_id:=laser
"
# ── RealSense D435i driver node ────────────────────────────────────────────
realsense:
image: saltybot/ros2-humble:jetson-nano
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 (custom serial↔ROS2 bridge) ─────────────────────────
stm32-bridge:
image: saltybot/ros2-humble:jetson-nano
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/ttyUSB1:/dev/ttyUSB1
command: >
bash -c "
source /opt/ros/humble/setup.bash &&
ros2 run saltybot_stm32_bridge bridge_node
--ros-args
-p serial_port:=/dev/ttyUSB1
-p baud_rate:=921600
"
volumes:
saltybot-maps:
driver: local