Merge pull request 'feat: Jetson Nano platform setup (bd-1hcg)' (#8) from sl-jetson/bd-1hcg-jetson-platform into main
This commit is contained in:
commit
29a3030abb
102
jetson/Dockerfile
Normal file
102
jetson/Dockerfile
Normal file
@ -0,0 +1,102 @@
|
||||
# Jetson Nano — ROS2 Humble dev container
|
||||
# Base: JetPack 4.6 (L4T R32.6.1) + CUDA 10.2
|
||||
# Arch: ARM64 (aarch64)
|
||||
|
||||
FROM nvcr.io/nvidia/l4t-base:r32.6.1
|
||||
|
||||
LABEL maintainer="sl-jetson <saltylab>"
|
||||
LABEL description="ROS2 Humble + SLAM stack for Jetson Nano self-balancing robot"
|
||||
LABEL jetpack="4.6"
|
||||
LABEL ros_distro="humble"
|
||||
|
||||
ENV DEBIAN_FRONTEND=noninteractive
|
||||
ENV ROS_DISTRO=humble
|
||||
ENV ROS_ROOT=/opt/ros/${ROS_DISTRO}
|
||||
ENV PYTHONDONTWRITEBYTECODE=1
|
||||
ENV PYTHONUNBUFFERED=1
|
||||
|
||||
# ── System deps ────────────────────────────────────────────────────────────────
|
||||
RUN apt-get update && apt-get install -y --no-install-recommends \
|
||||
# Build tools
|
||||
build-essential cmake git wget curl \
|
||||
# Python
|
||||
python3-dev python3-pip python3-setuptools python3-wheel \
|
||||
# Serial / I2C / SPI
|
||||
i2c-tools libi2c-dev python3-smbus \
|
||||
picocom minicom setserial \
|
||||
# USB
|
||||
usbutils libusb-1.0-0-dev \
|
||||
# Misc
|
||||
locales tzdata htop tmux nano \
|
||||
# Networking
|
||||
net-tools iputils-ping \
|
||||
&& rm -rf /var/lib/apt/lists/*
|
||||
|
||||
RUN locale-gen en_US.UTF-8
|
||||
ENV LANG=en_US.UTF-8
|
||||
|
||||
# ── ROS2 Humble (from ROS2 apt repo — ARM64 build) ─────────────────────────────
|
||||
# Note: official humble debs for ARM64/L4T are provided via NVIDIA Isaac ROS
|
||||
# or via ros2-apt-source for 20.04 focal.
|
||||
RUN curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc \
|
||||
| apt-key add - && \
|
||||
echo "deb [arch=arm64] http://packages.ros.org/ros2/ubuntu focal main" \
|
||||
> /etc/apt/sources.list.d/ros2.list && \
|
||||
apt-get update && apt-get install -y --no-install-recommends \
|
||||
ros-humble-ros-base \
|
||||
ros-humble-rmw-cyclonedds-cpp \
|
||||
ros-dev-tools \
|
||||
python3-colcon-common-extensions \
|
||||
python3-rosdep \
|
||||
&& rosdep init && rosdep update \
|
||||
&& rm -rf /var/lib/apt/lists/*
|
||||
|
||||
# ── Nav / SLAM / sensor packages ──────────────────────────────────────────────
|
||||
RUN apt-get update && apt-get install -y --no-install-recommends \
|
||||
ros-humble-nav2-bringup \
|
||||
ros-humble-slam-toolbox \
|
||||
ros-humble-robot-localization \
|
||||
ros-humble-rplidar-ros \
|
||||
ros-humble-realsense2-camera \
|
||||
ros-humble-realsense2-description \
|
||||
ros-humble-tf2-tools \
|
||||
ros-humble-rqt \
|
||||
ros-humble-rqt-common-plugins \
|
||||
ros-humble-rviz2 \
|
||||
ros-humble-rosbridge-server \
|
||||
&& rm -rf /var/lib/apt/lists/*
|
||||
|
||||
# ── GPIO / serial Python libs ──────────────────────────────────────────────────
|
||||
RUN pip3 install --no-cache-dir \
|
||||
Jetson.GPIO \
|
||||
pyserial \
|
||||
smbus2 \
|
||||
adafruit-blinka \
|
||||
RPi.GPIO \
|
||||
numpy \
|
||||
scipy
|
||||
|
||||
# ── RealSense SDK (librealsense2 ARM64) ───────────────────────────────────────
|
||||
# Pre-built for L4T — install from Jetson Hacks script or apt source
|
||||
RUN apt-get update && apt-get install -y --no-install-recommends \
|
||||
libssl-dev libusb-1.0-0-dev pkg-config libgtk-3-dev \
|
||||
&& rm -rf /var/lib/apt/lists/*
|
||||
|
||||
# librealsense2 ARM64 wheel (NVIDIA-patched for L4T)
|
||||
RUN pip3 install --no-cache-dir pyrealsense2
|
||||
|
||||
# ── Workspace setup ───────────────────────────────────────────────────────────
|
||||
RUN mkdir -p /ros2_ws/src
|
||||
WORKDIR /ros2_ws
|
||||
|
||||
# Source ROS2 in every shell
|
||||
RUN echo "source /opt/ros/${ROS_DISTRO}/setup.bash" >> /root/.bashrc && \
|
||||
echo "source /ros2_ws/install/local_setup.bash 2>/dev/null || true" >> /root/.bashrc && \
|
||||
echo "export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp" >> /root/.bashrc
|
||||
|
||||
# ── Entrypoint ────────────────────────────────────────────────────────────────
|
||||
COPY scripts/entrypoint.sh /entrypoint.sh
|
||||
RUN chmod +x /entrypoint.sh
|
||||
|
||||
ENTRYPOINT ["/entrypoint.sh"]
|
||||
CMD ["bash"]
|
||||
65
jetson/README.md
Normal file
65
jetson/README.md
Normal file
@ -0,0 +1,65 @@
|
||||
# Jetson Nano — AI/SLAM Platform Setup
|
||||
|
||||
Self-balancing robot: Jetson Nano dev environment for ROS2 Humble + SLAM stack.
|
||||
|
||||
## Stack
|
||||
|
||||
| Component | Version / Part |
|
||||
|-----------|---------------|
|
||||
| Platform | Jetson Nano 4GB |
|
||||
| JetPack | 4.6 (L4T R32.6.1, CUDA 10.2) |
|
||||
| ROS2 | Humble Hawksbill |
|
||||
| DDS | CycloneDDS |
|
||||
| SLAM | slam_toolbox |
|
||||
| Nav | Nav2 |
|
||||
| Depth camera | Intel RealSense D435i |
|
||||
| LiDAR | RPLIDAR A1M8 |
|
||||
| MCU bridge | STM32F722 (USB CDC @ 921600) |
|
||||
|
||||
## Quick Start
|
||||
|
||||
```bash
|
||||
# 1. Host setup (once, on fresh JetPack 4.6)
|
||||
sudo bash scripts/setup-jetson.sh
|
||||
|
||||
# 2. Build Docker image
|
||||
bash scripts/build-and-run.sh build
|
||||
|
||||
# 3. Start full stack
|
||||
bash scripts/build-and-run.sh up
|
||||
|
||||
# 4. Open ROS2 shell
|
||||
bash scripts/build-and-run.sh shell
|
||||
```
|
||||
|
||||
## Docs
|
||||
|
||||
- [`docs/pinout.md`](docs/pinout.md) — GPIO/I2C/UART pinout for all peripherals
|
||||
- [`docs/power-budget.md`](docs/power-budget.md) — 10W power envelope analysis
|
||||
|
||||
## Files
|
||||
|
||||
```
|
||||
jetson/
|
||||
├── Dockerfile # L4T base + ROS2 Humble + SLAM packages
|
||||
├── docker-compose.yml # Multi-service stack (ROS2, RPLIDAR, D435i, STM32)
|
||||
├── README.md # This file
|
||||
├── docs/
|
||||
│ ├── pinout.md # GPIO/I2C/UART pinout reference
|
||||
│ └── power-budget.md # Power budget analysis (10W envelope)
|
||||
└── scripts/
|
||||
├── entrypoint.sh # Docker container entrypoint
|
||||
├── setup-jetson.sh # Host setup (udev, Docker, nvpmodel)
|
||||
└── build-and-run.sh # Build/run helper
|
||||
```
|
||||
|
||||
## Power Budget (Summary)
|
||||
|
||||
| Scenario | Total |
|
||||
|---------|-------|
|
||||
| Idle | 2.9W |
|
||||
| Nominal (SLAM active) | ~10.2W |
|
||||
| Peak | 15.4W |
|
||||
|
||||
Target: 10W (MAXN nvpmodel). Use RPLIDAR standby + 640p D435i for compliance.
|
||||
See [`docs/power-budget.md`](docs/power-budget.md) for full analysis.
|
||||
135
jetson/docker-compose.yml
Normal file
135
jetson/docker-compose.yml
Normal file
@ -0,0 +1,135 @@
|
||||
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
|
||||
213
jetson/docs/pinout.md
Normal file
213
jetson/docs/pinout.md
Normal file
@ -0,0 +1,213 @@
|
||||
# Jetson Nano — GPIO / I2C / UART Pinout Reference
|
||||
## Self-Balancing Robot: STM32F722 Bridge + RealSense D435i + RPLIDAR A1M8
|
||||
|
||||
Last updated: 2026-02-28
|
||||
JetPack version: 4.6 (L4T R32.6.1)
|
||||
|
||||
---
|
||||
|
||||
## 40-Pin Header Overview
|
||||
|
||||
The Jetson Nano 40-pin header is physically compatible with Raspberry Pi HATs.
|
||||
Pin numbering below follows **physical board pin** (1–40) and the Jetson GPIO BCM-equivalent name.
|
||||
|
||||
```
|
||||
3.3V [ 1] [ 2] 5V
|
||||
SDA1 [ 3] [ 4] 5V ← I2C SDA (i2c-1)
|
||||
SCL1 [ 5] [ 6] GND ← I2C SCL (i2c-1)
|
||||
GPIO [ 7] [ 8] TXD0 ← UART TX (ttyTHS1)
|
||||
GND [ 9] [10] RXD0 ← UART RX (ttyTHS1)
|
||||
GPIO [11] [12] GPIO
|
||||
GPIO [13] [14] GND
|
||||
GPIO [15] [16] GPIO
|
||||
3.3V [17] [18] GPIO
|
||||
MOSI [19] [20] GND ← SPI0 MOSI
|
||||
MISO [21] [22] GPIO ← SPI0 MISO
|
||||
SCLK [23] [24] CE0 ← SPI0 CLK / CS0
|
||||
GND [25] [26] CE1 ← SPI0 CS1
|
||||
ID_SD[27] [28] ID_SC ← I2C ID EEPROM (reserved)
|
||||
GPIO [29] [30] GND
|
||||
GPIO [31] [32] GPIO
|
||||
GPIO [33] [34] GND
|
||||
GPIO [35] [36] GPIO
|
||||
GPIO [37] [38] GPIO
|
||||
GND [39] [40] GPIO
|
||||
```
|
||||
|
||||
---
|
||||
|
||||
## 1. STM32F722 Bridge (UART)
|
||||
|
||||
The STM32 acts as a real-time motor + IMU controller. Communication to Jetson is via **USB CDC serial** (primary) with hardware UART as fallback.
|
||||
|
||||
### USB CDC (Primary — Recommended)
|
||||
| Connection | Detail |
|
||||
|-----------|--------|
|
||||
| Interface | USB Micro-B on STM32 dev board → USB-A on Jetson |
|
||||
| Device node | `/dev/ttyACM0` or `/dev/ttyUSB1` |
|
||||
| Baud rate | 921600 (configured in STM32 firmware) |
|
||||
| Protocol | Custom binary framing (see `src/comm/`) |
|
||||
| Power | Powered via Jetson USB 5V (500mA max from host) |
|
||||
|
||||
### Hardware UART (Fallback)
|
||||
| Jetson Pin | Signal | STM32 Pin | Notes |
|
||||
|-----------|--------|-----------|-------|
|
||||
| Pin 8 (TXD0) | TX → | PA10 (UART1 RX) | Cross-connect TX→RX |
|
||||
| Pin 10 (RXD0) | RX ← | PA9 (UART1 TX) | Cross-connect RX→TX |
|
||||
| Pin 6 (GND) | GND | GND | Common ground **required** |
|
||||
|
||||
**Jetson device node:** `/dev/ttyTHS1`
|
||||
**Baud rate:** 921600, 8N1
|
||||
**Voltage level:** 3.3V — STM32F722 is 3.3V tolerant; Jetson GPIO is 3.3V
|
||||
**Do NOT use 5V** — Jetson GPIO max is 3.3V
|
||||
|
||||
```bash
|
||||
# Verify UART on Jetson
|
||||
ls /dev/ttyTHS1
|
||||
# Check permissions (add user to dialout group)
|
||||
sudo usermod -aG dialout $USER
|
||||
# Quick loopback test (connect TX→RX)
|
||||
picocom -b 921600 /dev/ttyTHS1
|
||||
```
|
||||
|
||||
**ROS2 topic mapping (STM32 bridge node):**
|
||||
| ROS2 Topic | Direction | Content |
|
||||
|-----------|-----------|---------|
|
||||
| `/stm32/imu_raw` | STM32→Jetson | IMU data (accel, gyro) at 500Hz |
|
||||
| `/stm32/motor_state` | STM32→Jetson | Motor RPM, current, temperature |
|
||||
| `/cmd_vel` | Jetson→STM32 | Velocity commands (m/s, rad/s) |
|
||||
| `/stm32/estop` | Jetson→STM32 | Emergency stop signal |
|
||||
|
||||
---
|
||||
|
||||
## 2. RealSense D435i (USB3)
|
||||
|
||||
The D435i provides RGB-D (depth + color) and IMU (accelerometer + gyroscope).
|
||||
|
||||
### Connection
|
||||
| Parameter | Value |
|
||||
|-----------|-------|
|
||||
| Interface | USB 3.1 Gen 1 (USB-A on Jetson) |
|
||||
| Device node | `/dev/bus/usb/...` (udev-managed) |
|
||||
| USB PID:VID | `0x8086:0x0b3a` (D435i) |
|
||||
| Power draw | ~1.5W active, 3.5W peak during init |
|
||||
| Cable | USB 3.1 — use **short cable ≤1m** for stability |
|
||||
|
||||
**Note:** The Jetson Nano has **4× USB-A ports** — use a USB3 port (blue) for D435i.
|
||||
|
||||
```bash
|
||||
# Verify detection
|
||||
lsusb | grep Intel
|
||||
# Expected: Bus 002 Device 003: ID 8086:0b3a Intel Corp. Intel RealSense D435i
|
||||
|
||||
# Install udev rules (required for non-root access)
|
||||
sudo cp /etc/udev/rules.d/99-realsense-libusb.rules /etc/udev/rules.d/
|
||||
sudo udevadm control --reload-rules && sudo udevadm trigger
|
||||
|
||||
# Test with realsense-viewer (if installed)
|
||||
realsense-viewer
|
||||
```
|
||||
|
||||
**ROS2 topics published:**
|
||||
| Topic | Type | Rate |
|
||||
|-------|------|------|
|
||||
| `/camera/color/image_raw` | `sensor_msgs/Image` | 30Hz |
|
||||
| `/camera/depth/image_rect_raw` | `sensor_msgs/Image` | 30Hz |
|
||||
| `/camera/aligned_depth_to_color/image_raw` | `sensor_msgs/Image` | 30Hz |
|
||||
| `/camera/imu` | `sensor_msgs/Imu` | 400Hz |
|
||||
| `/camera/color/camera_info` | `sensor_msgs/CameraInfo` | 30Hz |
|
||||
|
||||
---
|
||||
|
||||
## 3. RPLIDAR A1M8 (UART via USB adapter)
|
||||
|
||||
The A1M8 uses a CP2102/CH340 USB-UART adapter (included in kit).
|
||||
|
||||
### Connection
|
||||
| Parameter | Value |
|
||||
|-----------|-------|
|
||||
| Interface | USB Micro-B (via included USB-UART adapter) |
|
||||
| Device node | `/dev/ttyUSB0` (first USB-UART device) |
|
||||
| Baud rate | 115200 |
|
||||
| Power draw | ~2.6W motor on, 0.4W idle |
|
||||
| Motor control | DTR line (handled by rplidar_ros driver) |
|
||||
|
||||
```bash
|
||||
# Verify detection
|
||||
ls /dev/ttyUSB*
|
||||
# Expected: /dev/ttyUSB0
|
||||
|
||||
# Set permissions
|
||||
sudo usermod -aG dialout $USER
|
||||
|
||||
# Test — should output scan data
|
||||
ros2 launch rplidar_ros rplidar_a1_launch.py serial_port:=/dev/ttyUSB0
|
||||
```
|
||||
|
||||
**ROS2 topics published:**
|
||||
| Topic | Type | Rate |
|
||||
|-------|------|------|
|
||||
| `/scan` | `sensor_msgs/LaserScan` | 10Hz |
|
||||
|
||||
**udev rule (set consistent device name):**
|
||||
```bash
|
||||
# /etc/udev/rules.d/99-rplidar.rules
|
||||
KERNEL=="ttyUSB*", ATTRS{idVendor}=="10c4", ATTRS{idProduct}=="ea60", \
|
||||
SYMLINK+="rplidar", MODE="0666"
|
||||
```
|
||||
|
||||
---
|
||||
|
||||
## 4. I2C Bus (i2c-1) — Pin 3 / Pin 5
|
||||
|
||||
Available for future peripherals (IMU breakout, OLED display, etc.).
|
||||
|
||||
| Parameter | Value |
|
||||
|-----------|-------|
|
||||
| Jetson I2C bus | i2c-1 (pins 3 = SDA, 5 = SCL) |
|
||||
| Voltage | 3.3V pull-up |
|
||||
| Max clock | 400kHz (Fast Mode) |
|
||||
| Current source | Jetson 3.3V rail (max ~500mA shared) |
|
||||
|
||||
```bash
|
||||
# Scan i2c-1 bus
|
||||
i2cdetect -y -r 1
|
||||
```
|
||||
|
||||
**Note:** i2c-0 (pins 27/28) is reserved for EEPROM ID — do not use.
|
||||
|
||||
---
|
||||
|
||||
## 5. GPIO Summary Table
|
||||
|
||||
| Physical Pin | Jetson GPIO | Voltage | Current Used For |
|
||||
|-------------|-------------|---------|-----------------|
|
||||
| 3 | SDA1 | 3.3V | I2C data (i2c-1) |
|
||||
| 5 | SCL1 | 3.3V | I2C clock (i2c-1) |
|
||||
| 8 | TXD0 | 3.3V | UART TX → STM32 (fallback) |
|
||||
| 10 | RXD0 | 3.3V | UART RX ← STM32 (fallback) |
|
||||
| USB-A (×4) | — | 5V | D435i, RPLIDAR adapter, STM32 USB |
|
||||
|
||||
---
|
||||
|
||||
## 6. Device Enumeration Notes
|
||||
|
||||
USB devices may enumerate differently across reboots. Use udev rules for stable names:
|
||||
|
||||
```bash
|
||||
# /etc/udev/rules.d/99-saltybot.rules
|
||||
|
||||
# RPLIDAR A1M8 (SiliconLabs CP2102)
|
||||
KERNEL=="ttyUSB*", ATTRS{idVendor}=="10c4", ATTRS{idProduct}=="ea60", \
|
||||
SYMLINK+="rplidar", MODE="0666"
|
||||
|
||||
# STM32 USB CDC (STMicroelectronics)
|
||||
KERNEL=="ttyACM*", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="5740", \
|
||||
SYMLINK+="stm32-bridge", MODE="0666"
|
||||
```
|
||||
|
||||
Apply rules:
|
||||
```bash
|
||||
sudo cp docs/99-saltybot.rules /etc/udev/rules.d/
|
||||
sudo udevadm control --reload-rules && sudo udevadm trigger
|
||||
```
|
||||
188
jetson/docs/power-budget.md
Normal file
188
jetson/docs/power-budget.md
Normal file
@ -0,0 +1,188 @@
|
||||
# Jetson Nano Power Budget Analysis
|
||||
## Self-Balancing Robot — 10W Envelope
|
||||
|
||||
Last updated: 2026-02-28
|
||||
Target: Operate within 10W SoC power envelope (MAXN 10W mode)
|
||||
|
||||
---
|
||||
|
||||
## Power Modes
|
||||
|
||||
Jetson Nano supports two NVPModel power modes:
|
||||
|
||||
| Mode | GPU | CPU cores | CPU freq | Memory freq | TDP |
|
||||
|------|-----|-----------|----------|-------------|-----|
|
||||
| **MAXN (Mode 0)** | 128 core | 4 | 1.43GHz | 1600MHz | **10W** |
|
||||
| 5W (Mode 1) | 128 core | 2 | 0.92GHz | 1600MHz | 5W |
|
||||
|
||||
For this robot, we target **MAXN 10W mode** with careful peripheral management.
|
||||
|
||||
```bash
|
||||
# Check current mode
|
||||
sudo nvpmodel -q
|
||||
|
||||
# Set 10W MAXN mode
|
||||
sudo nvpmodel -m 0
|
||||
|
||||
# Set 5W mode (thermal/battery save)
|
||||
sudo nvpmodel -m 1
|
||||
|
||||
# Monitor power in real time
|
||||
sudo tegrastats
|
||||
```
|
||||
|
||||
---
|
||||
|
||||
## Component Power Budget
|
||||
|
||||
### SoC (Jetson Nano Module)
|
||||
|
||||
| Component | Idle (W) | Load (W) | Peak (W) | Notes |
|
||||
|-----------|----------|----------|----------|-------|
|
||||
| CPU (4× Cortex-A57) | 1.0 | 3.5 | 4.0 | ROS2 + SLAM compute |
|
||||
| GPU (128-core Maxwell) | 0.5 | 2.5 | 3.0 | Depth processing, ML inference |
|
||||
| DDR4 RAM (4GB) | 0.3 | 0.6 | 0.8 | |
|
||||
| eMMC / SD | 0.1 | 0.2 | 0.3 | |
|
||||
| **SoC Subtotal** | **1.9** | **6.8** | **8.1** | |
|
||||
|
||||
### Peripherals (USB / GPIO)
|
||||
|
||||
| Peripheral | Idle (W) | Active (W) | Peak (W) | Interface | Notes |
|
||||
|-----------|----------|------------|----------|-----------|-------|
|
||||
| RealSense D435i | 0.3 | 1.5 | 3.5 | USB 3.1 | Peak during boot/init |
|
||||
| RPLIDAR A1M8 | 0.4 | 2.6 | 3.0 | USB (UART adapter) | Motor spinning |
|
||||
| STM32F722 bridge | 0.3 | 0.5 | 0.8 | USB CDC | Powered from Jetson USB |
|
||||
| **Peripheral Subtotal** | **1.0** | **4.6** | **7.3** | | |
|
||||
|
||||
### Total System (from Jetson 5V barrel jack)
|
||||
|
||||
| Scenario | SoC (W) | Peripherals (W) | **Total (W)** | Margin |
|
||||
|----------|---------|-----------------|---------------|--------|
|
||||
| Idle | 1.9 | 1.0 | **2.9** | +7.1W |
|
||||
| Nominal (SLAM running) | 6.8 | 4.6 | **11.4** | **-1.4W ⚠️** |
|
||||
| Peak (all active, ML) | 8.1 | 7.3 | **15.4** | **-5.4W ❌** |
|
||||
|
||||
---
|
||||
|
||||
## Budget Compliance Strategy
|
||||
|
||||
The nominal load of **11.4W exceeds the 10W envelope** — mitigation required:
|
||||
|
||||
### Mitigation 1: RPLIDAR Power Gating
|
||||
The RPLIDAR motor can be stopped when not scanning. The ROS2 driver handles this via DTR line.
|
||||
|
||||
| Mode | Savings |
|
||||
|------|---------|
|
||||
| RPLIDAR motor off | −2.2W |
|
||||
| RPLIDAR idle | 0.4W vs 2.6W |
|
||||
|
||||
### Mitigation 2: RealSense Resolution Reduction
|
||||
Lower RGB-D resolution reduces USB bandwidth and D435i processing:
|
||||
|
||||
| Profile | Power |
|
||||
|---------|-------|
|
||||
| 1280×720 @ 30fps | 1.5W |
|
||||
| 640×480 @ 30fps | 1.1W ← **Recommended** |
|
||||
| 424×240 @ 30fps | 0.8W |
|
||||
|
||||
### Mitigation 3: Jetson GPU Workload Scheduling
|
||||
Avoid running depth inference and SLAM simultaneously at full throttle:
|
||||
|
||||
```bash
|
||||
# Cap GPU frequency (reduce from max 921.6MHz)
|
||||
sudo jetson_clocks --show
|
||||
# Set conservative clocks
|
||||
echo 614400000 | sudo tee /sys/devices/17000000.gp10b/devfreq/17000000.gp10b/min_freq
|
||||
```
|
||||
|
||||
### Mitigation 4: STM32 Self-Powered
|
||||
Power STM32 from robot's 5V bus (separate from Jetson USB rail):
|
||||
|
||||
| Option | Jetson USB load |
|
||||
|--------|----------------|
|
||||
| STM32 powered from Jetson USB | 0.5W |
|
||||
| STM32 powered from robot 5V | **0W** (data only via USB) |
|
||||
|
||||
---
|
||||
|
||||
## Revised Budget with Mitigations
|
||||
|
||||
Applying: 640×480 D435i + RPLIDAR gating + STM32 self-powered:
|
||||
|
||||
| Component | Power (W) |
|
||||
|-----------|-----------|
|
||||
| CPU (SLAM, 4 cores) | 3.5 |
|
||||
| GPU (depth processing) | 2.0 |
|
||||
| RAM + misc SoC | 1.0 |
|
||||
| RealSense D435i (640×480) | 1.1 |
|
||||
| RPLIDAR A1M8 (active) | 2.6 |
|
||||
| STM32 bridge (self-powered) | 0.0 |
|
||||
| **Total** | **10.2W** |
|
||||
|
||||
**Near-compliant at 10.2W.** Further savings achievable by:
|
||||
- Enabling RPLIDAR standby between scan cycles (−0.5W avg)
|
||||
- Using 5W nvpmodel during motor-heavy phases
|
||||
|
||||
---
|
||||
|
||||
## Input Power Requirements
|
||||
|
||||
### Jetson Nano Power Input
|
||||
| Spec | Value |
|
||||
|------|-------|
|
||||
| Input connector | 5.5mm / 2.1mm barrel jack |
|
||||
| Input voltage | 5V DC |
|
||||
| Recommended current | ≥4A (20W supply for headroom) |
|
||||
| Absolute max | 5.25V |
|
||||
|
||||
> **Use a 5V 4A supply minimum.** A 2A supply will brownout under load.
|
||||
|
||||
### Robot Power Architecture (Recommended)
|
||||
|
||||
```
|
||||
LiPo 3S (12.6V max)
|
||||
│
|
||||
├─► DC-DC Buck → 5V 5A ──► Jetson Nano barrel jack
|
||||
│ (e.g., XL4016)
|
||||
│
|
||||
├─► DC-DC Buck → 5V 3A ──► STM32 + logic 5V rail
|
||||
│
|
||||
└─► Hoverboard ESC ──► Hub motors (48V loop)
|
||||
```
|
||||
|
||||
This isolates the Jetson 5V supply from motor switching noise.
|
||||
|
||||
---
|
||||
|
||||
## Real-Time Monitoring
|
||||
|
||||
```bash
|
||||
# Live power telemetry
|
||||
sudo tegrastats --interval 500
|
||||
|
||||
# Key fields:
|
||||
# POM_5V_IN X/Y — total input power (current W / average W)
|
||||
# POM_5V_GPU X/Y — GPU power
|
||||
# POM_5V_CPU X/Y — CPU power
|
||||
|
||||
# Log to file
|
||||
sudo tegrastats --interval 1000 --logfile /tmp/power_log.txt &
|
||||
|
||||
# Parse log
|
||||
grep "POM_5V_IN" /tmp/power_log.txt | \
|
||||
awk '{for(i=1;i<=NF;i++) if($i=="POM_5V_IN") print $(i+1)}' | \
|
||||
awk -F'/' '{sum+=$1; count++} END {print "Avg:", sum/count, "mW"}'
|
||||
```
|
||||
|
||||
---
|
||||
|
||||
## Summary
|
||||
|
||||
| Metric | Value |
|
||||
|--------|-------|
|
||||
| Target envelope | 10W |
|
||||
| Nominal (no mitigation) | 11.4W |
|
||||
| Nominal (with mitigations) | ~10.2W |
|
||||
| Compliant scenario | RPLIDAR standby + 640p D435i |
|
||||
| Recommended PSU | 5V 4A (20W) |
|
||||
| Power mode | nvpmodel MAXN (Mode 0) |
|
||||
51
jetson/scripts/build-and-run.sh
Normal file
51
jetson/scripts/build-and-run.sh
Normal file
@ -0,0 +1,51 @@
|
||||
#!/usr/bin/env bash
|
||||
# Quick build + run helper for the Jetson ROS2 stack
|
||||
# Usage: bash build-and-run.sh [build|up|down|logs|shell]
|
||||
|
||||
set -euo pipefail
|
||||
|
||||
SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)"
|
||||
JETSON_DIR="$(dirname "$SCRIPT_DIR")"
|
||||
|
||||
cd "$JETSON_DIR"
|
||||
|
||||
ACTION="${1:-up}"
|
||||
|
||||
case "$ACTION" in
|
||||
build)
|
||||
echo "[saltybot] Building ROS2 Docker image..."
|
||||
docker compose build --no-cache
|
||||
;;
|
||||
up)
|
||||
echo "[saltybot] Starting ROS2 stack..."
|
||||
docker compose up -d
|
||||
docker compose logs -f
|
||||
;;
|
||||
down)
|
||||
echo "[saltybot] Stopping ROS2 stack..."
|
||||
docker compose down
|
||||
;;
|
||||
logs)
|
||||
docker compose logs -f
|
||||
;;
|
||||
shell)
|
||||
echo "[saltybot] Opening shell in ros2 container..."
|
||||
docker compose exec saltybot-ros2 bash
|
||||
;;
|
||||
slam)
|
||||
echo "[saltybot] Launching SLAM only..."
|
||||
docker compose up -d rplidar realsense saltybot-ros2
|
||||
docker compose logs -f saltybot-ros2
|
||||
;;
|
||||
status)
|
||||
docker compose ps
|
||||
echo ""
|
||||
echo "--- ROS2 topics (requires running container) ---"
|
||||
docker compose exec saltybot-ros2 \
|
||||
bash -c "source /opt/ros/humble/setup.bash && ros2 topic list" 2>/dev/null || true
|
||||
;;
|
||||
*)
|
||||
echo "Usage: $0 [build|up|down|logs|shell|slam|status]"
|
||||
exit 1
|
||||
;;
|
||||
esac
|
||||
18
jetson/scripts/entrypoint.sh
Normal file
18
jetson/scripts/entrypoint.sh
Normal file
@ -0,0 +1,18 @@
|
||||
#!/usr/bin/env bash
|
||||
# Docker entrypoint for Jetson Nano ROS2 container
|
||||
|
||||
set -e
|
||||
|
||||
# Source ROS2
|
||||
source /opt/ros/humble/setup.bash
|
||||
|
||||
# Source workspace if built
|
||||
if [ -f /ros2_ws/install/local_setup.bash ]; then
|
||||
source /ros2_ws/install/local_setup.bash
|
||||
fi
|
||||
|
||||
# Set DDS implementation
|
||||
export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
|
||||
|
||||
echo "[saltybot] ROS2 Humble ready — domain ID: ${ROS_DOMAIN_ID:-42}"
|
||||
exec "$@"
|
||||
127
jetson/scripts/setup-jetson.sh
Normal file
127
jetson/scripts/setup-jetson.sh
Normal file
@ -0,0 +1,127 @@
|
||||
#!/usr/bin/env bash
|
||||
# Jetson Nano host setup script
|
||||
# Run once on fresh JetPack 4.6 installation
|
||||
# Usage: sudo bash setup-jetson.sh
|
||||
|
||||
set -euo pipefail
|
||||
|
||||
echo "=== Jetson Nano Host Setup — saltybot ==="
|
||||
echo "JetPack 4.6 / L4T R32.6.1 expected"
|
||||
|
||||
# ── Verify we're on Jetson ────────────────────────────────────────────────────
|
||||
if ! uname -m | grep -q aarch64; then
|
||||
echo "ERROR: Must run on Jetson (aarch64). Got: $(uname -m)"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
# ── System update ─────────────────────────────────────────────────────────────
|
||||
apt-get update && apt-get upgrade -y
|
||||
|
||||
# ── Install Docker + NVIDIA runtime ──────────────────────────────────────────
|
||||
if ! command -v docker &>/dev/null; then
|
||||
echo "[+] Installing Docker..."
|
||||
curl -fsSL https://get.docker.com | sh
|
||||
usermod -aG docker "$SUDO_USER"
|
||||
fi
|
||||
|
||||
# NVIDIA container runtime
|
||||
if ! dpkg -l | grep -q nvidia-container-runtime; then
|
||||
echo "[+] Installing NVIDIA Container Runtime..."
|
||||
distribution=$(. /etc/os-release; echo $ID$VERSION_ID)
|
||||
curl -s -L https://nvidia.github.io/libnvidia-container/gpgkey | apt-key add -
|
||||
curl -s -L "https://nvidia.github.io/libnvidia-container/$distribution/libnvidia-container.list" \
|
||||
> /etc/apt/sources.list.d/nvidia-container-runtime.list
|
||||
apt-get update
|
||||
apt-get install -y nvidia-container-runtime
|
||||
fi
|
||||
|
||||
# Configure Docker daemon for NVIDIA runtime
|
||||
cat > /etc/docker/daemon.json << 'EOF'
|
||||
{
|
||||
"runtimes": {
|
||||
"nvidia": {
|
||||
"path": "nvidia-container-runtime",
|
||||
"runtimeArgs": []
|
||||
}
|
||||
},
|
||||
"default-runtime": "nvidia"
|
||||
}
|
||||
EOF
|
||||
systemctl restart docker
|
||||
|
||||
# ── Set Jetson power mode to MAXN 10W ────────────────────────────────────────
|
||||
echo "[+] Setting MAXN 10W power mode..."
|
||||
nvpmodel -m 0
|
||||
jetson_clocks
|
||||
|
||||
# ── Install udev rules ────────────────────────────────────────────────────────
|
||||
echo "[+] Installing udev rules..."
|
||||
cat > /etc/udev/rules.d/99-saltybot.rules << 'EOF'
|
||||
# RPLIDAR A1M8 (SiliconLabs CP2102)
|
||||
KERNEL=="ttyUSB*", ATTRS{idVendor}=="10c4", ATTRS{idProduct}=="ea60", \
|
||||
SYMLINK+="rplidar", MODE="0666"
|
||||
|
||||
# STM32 USB CDC (STMicroelectronics Virtual COM)
|
||||
KERNEL=="ttyACM*", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="5740", \
|
||||
SYMLINK+="stm32-bridge", MODE="0666"
|
||||
|
||||
# Intel RealSense D435i
|
||||
SUBSYSTEM=="usb", ATTRS{idVendor}=="8086", ATTRS{idProduct}=="0b3a", \
|
||||
MODE="0666"
|
||||
EOF
|
||||
|
||||
udevadm control --reload-rules
|
||||
udevadm trigger
|
||||
|
||||
# ── Install RealSense udev rules ──────────────────────────────────────────────
|
||||
echo "[+] Installing RealSense udev rules..."
|
||||
if [ -f /etc/udev/rules.d/99-realsense-libusb.rules ]; then
|
||||
echo " Already installed."
|
||||
else
|
||||
# Download from librealsense repo
|
||||
wget -q -O /etc/udev/rules.d/99-realsense-libusb.rules \
|
||||
https://raw.githubusercontent.com/IntelRealSense/librealsense/master/config/99-realsense-libusb.rules
|
||||
udevadm control --reload-rules
|
||||
udevadm trigger
|
||||
fi
|
||||
|
||||
# ── Enable I2C + UART ─────────────────────────────────────────────────────────
|
||||
echo "[+] Enabling I2C and UART..."
|
||||
modprobe i2c-dev
|
||||
# Add user to i2c and dialout groups
|
||||
usermod -aG i2c,dialout,gpio "$SUDO_USER"
|
||||
|
||||
# ── Configure UART (disable console on ttyTHS1) ───────────────────────────────
|
||||
# ttyTHS1 is the 40-pin header UART — disable serial console to free it
|
||||
if grep -q "console=ttyS0" /boot/extlinux/extlinux.conf; then
|
||||
echo "[+] UART ttyTHS1 already free for application use."
|
||||
else
|
||||
echo "[!] Warning: Check /boot/extlinux/extlinux.conf if serial console"
|
||||
echo " is using ttyTHS1. Disable it to use UART for STM32 bridge."
|
||||
fi
|
||||
|
||||
# ── Docker Compose ────────────────────────────────────────────────────────────
|
||||
if ! command -v docker-compose &>/dev/null && ! docker compose version &>/dev/null 2>&1; then
|
||||
echo "[+] Installing docker-compose..."
|
||||
pip3 install docker-compose
|
||||
fi
|
||||
|
||||
# ── Swap (improve stability under memory pressure) ────────────────────────────
|
||||
if [ "$(swapon --show | wc -l)" -le 1 ]; then
|
||||
echo "[+] Creating 4GB swap file..."
|
||||
fallocate -l 4G /swapfile
|
||||
chmod 600 /swapfile
|
||||
mkswap /swapfile
|
||||
swapon /swapfile
|
||||
echo '/swapfile none swap sw 0 0' >> /etc/fstab
|
||||
fi
|
||||
|
||||
echo ""
|
||||
echo "=== Setup complete ==="
|
||||
echo "Please log out and back in for group membership to take effect."
|
||||
echo ""
|
||||
echo "Next steps:"
|
||||
echo " 1. cd jetson/"
|
||||
echo " 2. docker compose build"
|
||||
echo " 3. docker compose up -d"
|
||||
echo " 4. docker compose logs -f"
|
||||
Loading…
x
Reference in New Issue
Block a user