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>
50 lines
2.8 KiB
YAML
50 lines
2.8 KiB
YAML
# saltybot_fleet — default parameters
|
|
#
|
|
# Override per-robot values at launch time:
|
|
# ros2 launch saltybot_fleet fleet_robot.launch.py robot_id:=saltybot_2 robot_namespace:=/saltybot_2
|
|
#
|
|
# Fleet topic layout:
|
|
# /fleet/maps MapChunk — robot → coordinator (compressed grids)
|
|
# /fleet/robots RobotInfo — heartbeat / status (all robots)
|
|
# /fleet/merged_map OccupancyGrid — coordinator → all (merged map)
|
|
# /fleet/exploration_frontiers FrontierArray — coordinator → all (consolidated frontiers)
|
|
# /fleet/status String (JSON) — coordinator health
|
|
#
|
|
# Per-robot topics (namespaced):
|
|
# /<robot_ns>/rtabmap/map OccupancyGrid — local RTAB-Map output
|
|
# /<robot_ns>/rtabmap/odom Odometry — local odometry
|
|
# /<robot_ns>/navigate_to_pose Nav2 action — local navigation
|
|
|
|
# ── Fleet coordinator ──────────────────────────────────────────────────────────
|
|
fleet_manager:
|
|
ros__parameters:
|
|
heartbeat_timeout_sec: 10.0 # seconds before a silent robot is considered lost
|
|
merge_hz: 2.0 # merged map publish rate (Hz)
|
|
frontier_timeout_sec: 60.0 # re-assign frontier if robot silent this long
|
|
map_resolution: 0.05 # all robots MUST match this (RTAB-Map Grid/CellSize)
|
|
|
|
# ── Frontier detector ──────────────────────────────────────────────────────────
|
|
frontier_detector:
|
|
ros__parameters:
|
|
detection_hz: 1.0 # frontier detection rate
|
|
min_frontier_cells: 10 # minimum frontier cluster size (cells)
|
|
|
|
# ── Per-robot: map broadcaster ────────────────────────────────────────────────
|
|
# Override robot_id / robot_namespace per robot at launch.
|
|
map_broadcaster:
|
|
ros__parameters:
|
|
robot_id: 'saltybot_1'
|
|
robot_namespace: '/saltybot_1'
|
|
broadcast_hz: 1.0
|
|
|
|
# ── Per-robot: cooperative explorer ──────────────────────────────────────────
|
|
fleet_explorer:
|
|
ros__parameters:
|
|
robot_id: 'saltybot_1'
|
|
robot_namespace: '/saltybot_1'
|
|
exploration_hz: 0.5 # state machine tick rate
|
|
goal_tolerance_m: 0.5 # distance threshold to declare frontier reached
|
|
nav_timeout_sec: 120.0 # cancel Nav2 goal after this long
|
|
backoff_sec: 5.0 # wait after stall before requesting new frontier
|
|
battery_min_pct: 20.0 # stop exploration below this battery level
|