saltylab-firmware/jetson/config/realsense_d435i.yaml
sl-perception 6b798cc890 feat: update SLAM stack for Jetson Orin Nano Super (67 TOPS, JetPack 6)
Platform upgrade: Jetson Nano 4GB → Orin Nano Super 8GB (March 1, 2026)
All Nano-era constraints removed — power/rate/resolution limits obsolete.

Dockerfile: l4t-jetpack:r36.2.0 (JetPack 6 / Ubuntu 22.04 / CUDA 12.x),
  ROS2 Humble via native apt, added ros-humble-rtabmap-ros,
  ros-humble-v4l2-camera for future IMX219 CSI (Phase 2c)

New: slam_rtabmap.launch.py — Orin primary SLAM entry point
  RTAB-Map with subscribe_scan (RPLIDAR) + subscribe_rgbd (D435i)
  Replaces slam_toolbox as docker-compose default

New: config/rtabmap_params.yaml — Orin-optimized
  DetectionRate 10Hz, MaxFeatures 1000, Grid/3D true,
  TimeThr 0 (no limit), Mem/STMSize 0 (unlimited)

Updated: config/realsense_d435i.yaml — 848x480x30, pointcloud enabled
Updated: config/slam_toolbox_params.yaml — 10Hz rate, 1s map interval
Updated: SLAM-SETUP-PLAN.md — full rewrite for Orin: arch diagram,
  Phase 2c IMX219 plan (4x 160° CSI surround), 25W power budget

docker-compose.yml: image tag jetson-orin, default → slam_rtabmap.launch.py

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-02-28 21:13:55 -05:00

34 lines
1.1 KiB
YAML

# RealSense D435i configuration — Jetson Orin Nano Super
#
# Previous Nano 4GB settings (640x480x15, no point cloud) replaced.
# Orin Nano Super has ample Ampere GPU headroom for 848x480x30fps + point cloud.
#
# Reference topics:
# /camera/color/image_raw 848x480 30 Hz RGB8
# /camera/depth/image_rect_raw 848x480 30 Hz Z16
# /camera/aligned_depth_to_color/image_raw 848x480 30 Hz Z16
# /camera/color/camera_info 848x480 30 Hz
# /camera/depth/camera_info 848x480 30 Hz
# /camera/imu ~400 Hz (gyro@400Hz + accel@100Hz fused)
# /camera/points PointCloud2 30 Hz
camera:
ros__parameters:
depth_module.profile: "848x480x30"
rgb_camera.profile: "848x480x30"
enable_depth: true
enable_color: true
enable_infra1: false
enable_infra2: false
enable_gyro: true
enable_accel: true
unite_imu_method: 2 # linear_interpolation
align_depth.enable: true
pointcloud.enable: true # Orin Ampere GPU handles this without issue
publish_tf: true
tf_publish_rate: 0.0