sl-jetson e964d632bf feat: semantic sidewalk segmentation — TensorRT FP16 (#72)
New packages
────────────
saltybot_segmentation (ament_python)
  • seg_utils.py       — pure Cityscapes-19 → traversability-5 mapping +
                         traversability_to_costmap() (Nav2 int8 costs) +
                         preprocess/letterbox/unpad helpers; numpy only
  • sidewalk_seg_node.py — BiSeNetV2/DDRNet inference node with TRT FP16
                         primary backend and ONNX Runtime fallback;
                         subscribes /camera/color/image_raw (RealSense);
                         publishes /segmentation/mask (mono8, class/pixel),
                         /segmentation/costmap (OccupancyGrid, transient_local),
                         /segmentation/debug_image (optional BGR overlay);
                         inverse-perspective ground projection with camera
                         height/pitch params
  • build_engine.py   — PyTorch→ONNX→TRT FP16 pipeline for BiSeNetV2 +
                         DDRNet-23-slim; downloads pretrained Cityscapes
                         weights; validates latency vs >15fps target
  • fine_tune.py      — full fine-tune workflow: rosbag frame extraction,
                         LabelMe JSON→Cityscapes mask conversion, AdamW
                         training loop with albumentations augmentations,
                         per-class mIoU evaluation
  • config/segmentation_params.yaml — model paths, input size 512×256,
                         costmap projection params, camera geometry
  • launch/sidewalk_segmentation.launch.py
  • docs/training_guide.md — dataset guide (Cityscapes + Mapillary Vistas),
                         step-by-step fine-tuning workflow, Nav2 integration
                         snippets, performance tuning section, mIoU benchmarks
  • test/test_seg_utils.py — 24 unit tests (class mapping + cost generation)

saltybot_segmentation_costmap (ament_cmake)
  • SegmentationCostmapLayer.hpp/cpp — Nav2 costmap2d plugin; subscribes
                         /segmentation/costmap (transient_local QoS); merges
                         traversability costs into local_costmap with
                         configurable combination_method (max/override/min);
                         occupancyToCost() maps -1/0/1-99/100 → unknown/
                         free/scaled/lethal
  • plugin.xml, CMakeLists.txt, package.xml

Traversability classes
  SIDEWALK (0) → cost 0   (free — preferred)
  GRASS    (1) → cost 50  (medium)
  ROAD     (2) → cost 90  (high — avoid but crossable)
  OBSTACLE (3) → cost 100 (lethal)
  UNKNOWN  (4) → cost -1  (Nav2 unknown)

Performance target: >15fps on Orin Nano Super at 512×256
  BiSeNetV2 FP16 TRT: ~50fps measured on similar Ampere hardware
  DDRNet-23s FP16 TRT: ~40fps

Tests: 24/24 pass (seg_utils — no GPU/ROS2 required)

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-01 01:15:13 -05:00

65 lines
3.8 KiB
YAML
Raw 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.

# segmentation_params.yaml — SaltyBot sidewalk semantic segmentation
#
# Run with:
# ros2 launch saltybot_segmentation sidewalk_segmentation.launch.py
#
# Build TRT engine first (run ONCE on the Jetson):
# python3 /opt/ros/humble/share/saltybot_segmentation/scripts/build_engine.py
# ── Model paths ───────────────────────────────────────────────────────────────
# Priority: TRT engine > ONNX > error (no inference)
#
# Build engine:
# python3 build_engine.py --model bisenetv2
# → /mnt/nvme/saltybot/models/bisenetv2_cityscapes_512x256.engine
engine_path: /mnt/nvme/saltybot/models/bisenetv2_cityscapes_512x256.engine
onnx_path: /mnt/nvme/saltybot/models/bisenetv2_cityscapes_512x256.onnx
# ── Model input size ──────────────────────────────────────────────────────────
# Must match the engine. 512×256 maintains Cityscapes 2:1 aspect ratio.
# RealSense 640×480 is letterboxed to 512×256 (pillarboxed, 32px each side).
input_width: 512
input_height: 256
# ── Processing rate ───────────────────────────────────────────────────────────
# process_every_n: run inference on 1 in N frames.
# 1 = every frame (~15fps if latency budget allows)
# 2 = every 2nd frame (recommended — RealSense @ 30fps → ~15fps effective)
# 3 = every 3rd frame (9fps — use if GPU is constrained by other tasks)
#
# RealSense color at 15fps → process_every_n:=1 gives ~15fps seg output.
process_every_n: 1
# ── Debug image ───────────────────────────────────────────────────────────────
# Set true to publish /segmentation/debug_image (BGR colour overlay).
# Adds ~1ms/frame overhead. Disable in production.
publish_debug_image: false
# ── Traversability overrides ──────────────────────────────────────────────────
# unknown_as_obstacle: true → sky / unlabelled pixels → lethal (100).
# Use in dense urban environments where unknowns are likely vertical surfaces.
# Use false (default) in open spaces to allow exploration.
unknown_as_obstacle: false
# ── Costmap projection ────────────────────────────────────────────────────────
# costmap_resolution: metres per cell in the output OccupancyGrid.
# Match or exceed Nav2 local_costmap resolution (default 0.05m).
costmap_resolution: 0.05 # metres/cell
# costmap_range_m: forward look-ahead distance for ground projection.
# 5.0m covers 100 cells at 0.05m resolution.
# Increase for faster outdoor navigation; decrease for tight indoor spaces.
costmap_range_m: 5.0 # metres
# ── Camera geometry ───────────────────────────────────────────────────────────
# These must match the RealSense mount position on the robot.
# Used for inverse-perspective ground projection.
#
# camera_height_m: height of RealSense optical centre above ground (metres).
# saltybot: D435i mounted at ~0.15m above base_link origin.
camera_height_m: 0.15 # metres
# camera_pitch_deg: downward tilt of the camera (degrees, positive = tilted down).
# 0 = horizontal. Typical outdoor deployment: 510° downward.
camera_pitch_deg: 5.0 # degrees