saltylab-firmware/jetson/docker-compose.yml
sl-jetson a4a2953326 feat: Here4 DroneCAN GPS driver + NTRIP client (RTK ready) — Issue #725
New packages:
- saltybot_dronecan_gps: DroneCAN driver for CubePilot Here4 RTK GPS
  - Subscribes uavcan.equipment.gnss.Fix2 (ID 1063) on can0 at 1Mbps
  - Publishes /gps/fix (NavSatFix), /gps/vel (TwistStamped), /gps/rtk_status
  - Maps DroneCAN fix_type 0-6 → sensor_msgs NavSatStatus + RTK label
  - Optional compass via uavcan.equipment.ahrs.MagneticFieldStrength
- saltybot_ntrip_client: NTRIP RTCM3 → DroneCAN RTCMStream forwarding
  - Connects to rtk2go.com:2101 (configurable), auto-reconnects
  - Forwards corrections to Here4 via uavcan.equipment.gnss.RTCMStream
  - Publishes /ntrip/status (CONNECTED / DISCONNECTED / ERROR:<reason>)

New launch file:
- here4_gps.launch.py: launches both nodes with unified CAN + NTRIP params

Updated:
- can_setup.sh: adds 1Mbps DroneCAN mode (sudo ./can_setup.sh up dronecan)
  keeping 500kbps VESC default; CAN_BITRATE env var still overrides both
- docker-compose.yml: adds here4-gps service with /dev/can0 device passthrough
  and NET_ADMIN cap; resolves leftover merge conflict markers
- outdoor_nav_params.yaml: adds Here4 config section, updates RTK docs

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-04-10 20:42:36 -04:00

407 lines
13 KiB
YAML

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
privileged: false
network_mode: host
environment:
- NVIDIA_VISIBLE_DEVICES=all
- NVIDIA_DRIVER_CAPABILITIES=all
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
- ROS_DOMAIN_ID=42
- DISPLAY=${DISPLAY:-:0}
volumes:
- /tmp/.X11-unix:/tmp/.X11-unix:rw
- ./ros2_ws/src:/ros2_ws/src:rw
- /mnt/nvme/saltybot/maps:/maps
- /mnt/nvme/saltybot:/data:rw
- ./config:/config:ro
devices:
- /dev/rplidar:/dev/rplidar
- /dev/esp32-bridge:/dev/esp32-bridge
- /dev/bus/usb:/dev/bus/usb
- /dev/i2c-7:/dev/i2c-7
- /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
"
# ── ESP32-S3 bridge node (bidirectional serial<->ROS2) ───────────────────────
esp32-bridge:
image: saltybot/ros2-humble:jetson-orin
build:
context: .
dockerfile: Dockerfile
container_name: saltybot-esp32-bridge
restart: unless-stopped
runtime: nvidia
network_mode: host
environment:
- ROS_DOMAIN_ID=42
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
devices:
- /dev/esp32-bridge:/dev/esp32-bridge
command: >
bash -c "
source /opt/ros/humble/setup.bash &&
ros2 launch saltybot_bridge bridge.launch.py
mode:=bidirectional
serial_port:=/dev/esp32-bridge
"
# ── 4x 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
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:
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
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 &&
source /ros2_ws/install/local_setup.bash 2>/dev/null || true &&
ros2 launch saltybot_surround surround_vision.launch.py
start_cameras:=false
camera_height:=0.30
publish_rate:=5.0
"
# ── rosbridge WebSocket server — ws://jetson:9090 ──────────────────────────
rosbridge:
image: saltybot/ros2-humble:jetson-orin
build:
context: .
dockerfile: Dockerfile
container_name: saltybot-rosbridge
restart: unless-stopped
runtime: nvidia
network_mode: host
depends_on:
- saltybot-ros2
- esp32-bridge
- csi-cameras
environment:
- ROS_DOMAIN_ID=42
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
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 &&
ros2 launch saltybot_bringup rosbridge.launch.py
"
# -- Remote e-stop bridge (MQTT over 4G -> ESP32-S3 CDC) ---------------------
# Subscribes to saltybot/estop MQTT topic. {"kill":true} -> 'E\r\n' to ESP32-S3.
# Cellular watchdog: 5s MQTT drop in AUTO mode -> 'F\r\n' (ESTOP_CELLULAR_TIMEOUT).
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:
- esp32-bridge
environment:
- ROS_DOMAIN_ID=42
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
devices:
- /dev/esp32-bridge:/dev/esp32-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
"
# ── Nav2 autonomous navigation stack ──────────────────────────────────────
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
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 &&
source /ros2_ws/install/local_setup.bash 2>/dev/null || true &&
ros2 launch saltybot_bringup nav2.launch.py
"
# ── Outdoor navigation — OSM routing + GPS waypoints + geofence ───────────
# Start only for outdoor missions. Usage:
# ros2 param set /osm_router goal_lat 37.7749
# ros2 param set /osm_router goal_lon -122.4194
# ros2 service call /outdoor/plan_route std_srvs/srv/Trigger '{}'
# ros2 service call /outdoor/start_navigation std_srvs/srv/Trigger '{}'
saltybot-outdoor:
image: saltybot/ros2-humble:jetson-orin
build:
context: .
dockerfile: Dockerfile
container_name: saltybot-outdoor
restart: unless-stopped
runtime: nvidia
network_mode: host
depends_on:
- saltybot-nav2
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
- /mnt/nvme/saltybot/osm_cache:/data/osm_cache:rw
devices:
- /dev/sim7600:/dev/sim7600
command: >
bash -c "
source /opt/ros/humble/setup.bash &&
source /ros2_ws/install/local_setup.bash 2>/dev/null || true &&
ros2 launch saltybot_outdoor outdoor_nav.launch.py
use_rtk:=false
fence_active:=true
"
# ── Social-bot AI stack (speech + LLM + TTS + face recognition) ─────────────
# Issue #88: Orin dev environment for social-bot
# Start: docker compose up -d saltybot-social
# Logs: docker compose logs -f saltybot-social
saltybot-social:
image: saltybot/social:latest
build:
context: .
dockerfile: Dockerfile.social
container_name: saltybot-social
restart: unless-stopped
runtime: nvidia
network_mode: host
depends_on:
- esp32-bridge
environment:
- NVIDIA_VISIBLE_DEVICES=all
- NVIDIA_DRIVER_CAPABILITIES=all,audio
- ROS_DOMAIN_ID=42
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
- MODEL_DIR=/models
- PIPER_VOICE_DIR=/models/piper
- LLAMA_N_GPU_LAYERS=20
# Audio device routing (override if mic/speaker cards differ)
- ALSA_MIC_CARD=1
- ALSA_SPEAKER_CARD=2
volumes:
- ./ros2_ws/src:/ros2_ws/src:rw
- ./config:/config:ro
# Persistent model storage on NVMe (survives container restarts)
- /mnt/nvme/saltybot/models:/models:rw
# Enrollment database (face embeddings, voice prints, conversation history)
- /mnt/nvme/saltybot/social_db:/social_db:rw
# SOUL.md personality file
- /mnt/nvme/saltybot/soul:/soul:ro
devices:
# USB mic array (ReSpeaker 2-Mic / 4-Mic or compatible)
- /dev/snd:/dev/snd
# USB webcam / face camera (optional, RealSense preferred)
- /dev/bus/usb:/dev/bus/usb
group_add:
- audio
cap_add:
- SYS_NICE # allow real-time thread priority for audio
ulimits:
rtprio: 95
memlock: -1
command: >
bash -c "
source /opt/ros/humble/setup.bash &&
source /ros2_ws/install/local_setup.bash 2>/dev/null || true &&
ros2 launch saltybot_social social_bot.launch.py
"
# ── Here4 DroneCAN GPS + NTRIP RTK client ────────────────────────────────
# Issue #725 — CubePilot Here4 RTK GPS via DroneCAN (1Mbps, SocketCAN)
# Start: docker compose up -d here4-gps
# Monitor fix: docker compose exec here4-gps ros2 topic echo /gps/rtk_status
# Configure NTRIP: set NTRIP_MOUNT, NTRIP_USER, NTRIP_PASSWORD env vars
here4-gps:
image: saltybot/ros2-humble:jetson-orin
build:
context: .
dockerfile: Dockerfile
container_name: saltybot-here4-gps
restart: unless-stopped
runtime: nvidia
network_mode: host
depends_on:
- saltybot-nav2
environment:
- ROS_DOMAIN_ID=42
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
# NTRIP credentials — set these in your .env or override at runtime
- NTRIP_MOUNT=${NTRIP_MOUNT:-}
- NTRIP_USER=${NTRIP_USER:-}
- NTRIP_PASSWORD=${NTRIP_PASSWORD:-}
volumes:
- ./ros2_ws/src:/ros2_ws/src:rw
- ./config:/config:ro
devices:
- /dev/can0:/dev/can0
cap_add:
- NET_ADMIN # needed for SocketCAN ip link set can0 up inside container
command: >
bash -c "
source /opt/ros/humble/setup.bash &&
source /ros2_ws/install/local_setup.bash 2>/dev/null || true &&
pip install python-dronecan --quiet 2>/dev/null || true &&
ros2 launch saltybot_dronecan_gps here4_gps.launch.py
can_interface:=can0
can_bitrate:=1000000
ntrip_caster:=rtk2go.com
ntrip_mount:=${NTRIP_MOUNT:-}
ntrip_user:=${NTRIP_USER:-}
ntrip_password:=${NTRIP_PASSWORD:-}
"
volumes:
saltybot-maps:
driver: local