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>
67 lines
2.3 KiB
YAML
67 lines
2.3 KiB
YAML
# slam_toolbox — online async SLAM configuration
|
|
# Jetson Orin Nano Super — all Nano rate caps removed.
|
|
#
|
|
# Primary SLAM is now RTAB-Map (slam_rtabmap.launch.py).
|
|
# slam_toolbox retained for LIDAR-only localization against pre-built maps.
|
|
#
|
|
# Input: /scan (LaserScan from RPLIDAR A1M8, ~5.5 Hz)
|
|
# Output: /map (OccupancyGrid)
|
|
|
|
slam_toolbox:
|
|
ros__parameters:
|
|
odom_frame: odom
|
|
map_frame: map
|
|
base_frame: base_link
|
|
scan_topic: /scan
|
|
mode: mapping
|
|
|
|
resolution: 0.05
|
|
max_laser_range: 8.0
|
|
map_update_interval: 1.0 # 1s (was 5s on Nano)
|
|
minimum_travel_distance: 0.2
|
|
minimum_travel_heading: 0.2
|
|
|
|
minimum_time_interval: 0.1 # ~10Hz processing (was 0.5s on Nano)
|
|
transform_timeout: 0.2
|
|
tf_buffer_duration: 30.0
|
|
stack_size_to_use: 40000000
|
|
enable_interactive_mode: false
|
|
|
|
use_scan_matching: true
|
|
use_scan_barycenter: true
|
|
scan_buffer_size: 20
|
|
scan_buffer_maximum_scan_distance: 10.0
|
|
|
|
do_loop_closing: true
|
|
loop_match_minimum_chain_size: 10
|
|
loop_match_maximum_variance_coarse: 3.0
|
|
loop_match_minimum_response_coarse: 0.35
|
|
loop_match_minimum_response_fine: 0.45
|
|
loop_search_maximum_distance: 3.0
|
|
|
|
correlation_search_space_dimension: 0.5
|
|
correlation_search_space_resolution: 0.01
|
|
correlation_search_space_smear_deviation: 0.1
|
|
|
|
loop_search_space_dimension: 8.0
|
|
loop_search_space_resolution: 0.05
|
|
loop_search_space_smear_deviation: 0.03
|
|
|
|
link_match_minimum_response_fine: 0.1
|
|
link_scan_maximum_distance: 1.5
|
|
use_response_expansion: true
|
|
distance_variance_penalty: 0.5
|
|
angle_variance_penalty: 1.0
|
|
fine_search_angle_offset: 0.00349
|
|
coarse_search_angle_offset: 0.349
|
|
coarse_angle_resolution: 0.0349
|
|
minimum_angle_penalty: 0.9
|
|
minimum_distance_penalty: 0.5
|
|
|
|
solver_plugin: solver_plugins::CeresSolver
|
|
ceres_linear_solver: SPARSE_NORMAL_CHOLESKY
|
|
ceres_preconditioner: SCHUR_JACOBI
|
|
ceres_trust_strategy: LEVENBERG_MARQUARDT
|
|
ceres_dogleg_type: TRADITIONAL_DOGLEG
|
|
ceres_loss_function: None
|