saltylab-firmware/jetson/docs/power-budget.md
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

189 lines
5.1 KiB
Markdown
Raw Permalink 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.

# 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) |