sl-perception b9b866854f feat(fleet): multi-robot SLAM — map sharing + cooperative exploration (Issue #134)
New packages:
  saltybot_fleet_msgs — 4 msgs (RobotInfo, MapChunk, Frontier, FrontierArray)
                        + 2 srvs (RegisterRobot, RequestFrontier)
  saltybot_fleet      — 4 nodes + 2 launch files + config + CLI tool

Nodes:
  map_broadcaster_node  — zlib-compress local OccupancyGrid → /fleet/maps @ 1Hz
                          + /fleet/robots heartbeat with battery/status
  fleet_manager_node    — robot registry, MapMerger (multi-grid SE2-aligned merge),
                          frontier aggregation, /fleet/request_frontier service,
                          heartbeat timeout + stale frontier re-assignment
  frontier_detector_node — scipy label-based frontier detection on merged map
                           → /fleet/exploration_frontiers_raw
  fleet_explorer_node   — Nav2 NavigateToPose cooperative exploration state machine:
                          IDLE→request→NAVIGATING→ARRIVED→IDLE + STALLED backoff

Supporting modules:
  map_compressor.py    — binary serialise + zlib OccupancyGrid encode/decode
  map_merger.py        — SE(2)-transform-aware multi-grid merge with conservative
                         obstacle inflation (occupied beats free on conflict)
  frontier_detector.py — numpy frontier mask + scipy connected-components + scoring
  landmark_aligner.py  — ArUco-landmark SE(2) estimation (Horn 2D least-squares)
                         to align robot map frames into common fleet_map frame

Topic layout:
  /fleet/maps                    MapChunk       per-robot compressed grids
  /fleet/robots                  RobotInfo      heartbeats + status
  /fleet/merged_map              OccupancyGrid  coordinator merged output
  /fleet/exploration_frontiers   FrontierArray  consolidated frontiers
  /fleet/status                  String (JSON)  coordinator health
  /<robot_ns>/rtabmap/map        input per robot
  /<robot_ns>/rtabmap/odom       input per robot
  /<robot_ns>/navigate_to_pose   Nav2 action per robot

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-02 09:36:17 -05:00

21 lines
802 B
Plaintext
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.

# Robot discovery and status — published to /fleet/robots at 1 Hz by each robot.
# Used for DDS peer discovery without a central broker.
builtin_interfaces/Time stamp
string robot_id # e.g. "saltybot_1"
string namespace # e.g. "/saltybot_1"
geometry_msgs/PoseStamped pose # current best-estimate pose (map frame)
# Status flags
uint8 STATUS_IDLE = 0
uint8 STATUS_MAPPING = 1
uint8 STATUS_EXPLORING = 2
uint8 STATUS_RETURNING = 3
uint8 STATUS_LOST = 4
uint8 status
float32 battery_pct # 0.0100.0; -1 = unknown
float32 map_coverage_m2 # explored area in square metres
uint32 keyframe_count # RTAB-Map keyframes in local DB
string active_frontier # frontier ID currently being explored, "" if none