Appendix E: Provisional Extension Examples

These provisional extensions are intentionally minimal and subject to breaking changes in future versions. Implementers SHOULD treat all struct layouts as unstable and MUST NOT assume wire compatibility across spec revisions.

Example: Neural Extension (Provisional)

This profile describes neural scene representations — such as NeRFs, Gaussian splats, and neural SDFs — and provides a request/reply pattern for view synthesis. A mapping service might publish a NeuralFieldMeta describing a Gaussian splat covering part of a city block, and an AR client could request novel views from arbitrary camera poses.

The profile intentionally avoids prescribing model internals. model_format is a freeform string that identifies the training framework and version; model weights ride as blobs. This keeps the schema stable across the rapid evolution of neural representation research while giving consumers enough metadata to discover fields, check coverage, and request renders.

NeuralFieldMeta follows the same static-meta pattern as RadSensorMeta and LidarMeta: publish once with RELIABLE + TRANSIENT_LOCAL QoS so late joiners receive the current state. ViewSynthesisRequest and ViewSynthesisResponse follow the request/reply pattern used by SnapshotRequest and SnapshotResponse.

// SPDX-License-Identifier: MIT
// SpatialDDS Neural Profile 1.5 (Provisional Extension)
//
// PROVISIONAL: This profile is subject to breaking changes in future
// versions. Implementers SHOULD treat all struct layouts as unstable
// and MUST NOT assume wire compatibility across spec revisions.

#ifndef SPATIAL_CORE_INCLUDED
#define SPATIAL_CORE_INCLUDED
#include "core.idl"
#endif

module spatial {
  module neural {

    const string MODULE_ID = "spatial.neural/1.5";

    typedef builtin::Time Time;
    typedef spatial::core::PoseSE3 PoseSE3;
    typedef spatial::core::Aabb3 Aabb3;
    typedef spatial::core::BlobRef BlobRef;
    typedef spatial::common::FrameRef FrameRef;

    enum RepresentationType {
      @value(0) NERF,
      @value(1) GAUSSIAN_SPLAT,
      @value(2) NEURAL_SDF,
      @value(3) NEURAL_MESH,
      @value(4) TRIPLANE,
      @value(255) CUSTOM
    };

    enum OutputModality {
      @value(0) RGB,
      @value(1) DEPTH,
      @value(2) NORMALS,
      @value(3) SEMANTICS,
      @value(4) ALPHA
    };

    @extensibility(APPENDABLE) struct NeuralFieldMeta {
      @key string field_id;

      RepresentationType rep_type;
      string model_format;

      FrameRef frame_ref;
      boolean has_extent;
      Aabb3 extent;

      boolean has_quality;
      float quality;
      string checkpoint;

      sequence<BlobRef, 16> model_blobs;

      sequence<OutputModality, 8> supported_outputs;

      boolean has_render_time_ms;
      float render_time_ms;

      Time stamp;
      string schema_version;             // MUST be "spatial.neural/1.5"
    };

    @extensibility(APPENDABLE) struct ViewSynthesisRequest {
      @key string request_id;
      string field_id;

      PoseSE3 camera_pose;
      boolean has_fov_deg;
      float fov_y_deg;
      uint16 width;
      uint16 height;

      sequence<OutputModality, 8> requested_outputs;

      string reply_topic;
      Time stamp;
      uint32 ttl_sec;
    };

    @extensibility(APPENDABLE) struct ViewSynthesisResponse {
      @key string request_id;

      sequence<BlobRef, 8> result_blobs;

      boolean has_render_time_ms;
      float render_time_ms;
      boolean has_quality;
      float quality;

      boolean succeeded;
      string diagnostic;

      Time stamp;
    };

  }; // module neural
};

Example JSON (Informative)

{
  "field_id": "splat/downtown-sf-block-7",
  "rep_type": "GAUSSIAN_SPLAT",
  "model_format": "inria-3dgs-v1",
  "frame_ref": {
    "uuid": "ae6f0a3e-7a3e-4b1e-9b1f-0e9f1b7c1a10",
    "fqn": "earth-fixed"
  },
  "has_extent": true,
  "extent": {
    "min_xyz": [-122.420, 37.790, -5.0],
    "max_xyz": [-122.410, 37.800, 50.0]
  },
  "has_quality": true,
  "quality": 0.85,
  "checkpoint": "epoch-30000",
  "model_blobs": [
    { "blob_id": "gs-weights-001", "role": "weights", "checksum": "sha256:a1b2c3..." },
    { "blob_id": "gs-pointcloud-001", "role": "point_cloud", "checksum": "sha256:d4e5f6..." }
  ],
  "supported_outputs": ["RGB", "DEPTH", "NORMALS"],
  "has_render_time_ms": true,
  "render_time_ms": 12.5,
  "stamp": { "sec": 1714070400, "nanosec": 0 },
  "schema_version": "spatial.neural/1.5"
}

Example: Agent Extension (Provisional)

This profile provides lightweight task coordination for AI agents and planners operating over the SpatialDDS bus. It covers two layers:

  • Single-task lifecycle. A planner publishes TaskRequest messages describing spatial tasks — navigate to a location, observe a region, build a map — and agents claim and report progress via TaskStatus.
  • Fleet coordination. Agents advertise availability and capabilities via AgentStatus. When multiple agents can handle a task, they may publish TaskOffer bids. The coordinator selects an agent via TaskAssignment. If an agent cannot finish, it publishes TaskHandoff with continuation context so the next agent picks up where it left off.

The design is deliberately minimal. Task-specific parameters are carried as freeform JSON in params fields, avoiding premature schema commitment for the wide variety of agent capabilities in robotics, drone fleets, AR-guided workflows, and AI services. Spatial targeting reuses the existing PoseSE3, FrameRef, and SpatialUri types so tasks can reference any addressable resource on the bus.

The profile defines what information agents and coordinators exchange, not how allocation decisions are made. A round-robin dispatcher, a market-based auction, a centralized optimizer, and a human dispatcher all consume the same typed messages. The allocation algorithm is an application-layer concern.

// SPDX-License-Identifier: MIT
// SpatialDDS Agent Profile 1.5 (Provisional Extension)
//
// PROVISIONAL: This profile is subject to breaking changes in future
// versions. Implementers SHOULD treat all struct layouts as unstable
// and MUST NOT assume wire compatibility across spec revisions.

#ifndef SPATIAL_CORE_INCLUDED
#define SPATIAL_CORE_INCLUDED
#include "core.idl"
#endif

module spatial {
  module agent {

    const string MODULE_ID = "spatial.agent/1.5";

    typedef builtin::Time Time;
    typedef spatial::core::PoseSE3 PoseSE3;
    typedef spatial::core::FramedPose FramedPose;
    typedef spatial::common::FrameRef FrameRef;
    typedef string SpatialUri;

    // ---- Task types ----
    // Broad categories of spatial tasks an agent might execute.
    // CUSTOM allows deployment-specific task types with params.
    enum TaskType {
      @value(0) NAVIGATE,         // Move to a target pose or region
      @value(1) OBSERVE,          // Collect sensor data at/around a target
      @value(2) MANIPULATE,       // Physically interact with an object
      @value(3) MAP,              // Build or extend a spatial map
      @value(4) DELIVER,          // Transport an item to a target
      @value(5) REPORT,           // Generate and publish a data report
      @value(255) CUSTOM          // Deployment-specific; describe in params
    };

    // ---- Task lifecycle states ----
    enum TaskState {
      @value(0) PENDING,          // Published, not yet accepted
      @value(1) ACCEPTED,         // Agent has claimed the task
      @value(2) IN_PROGRESS,      // Execution underway
      @value(3) COMPLETED,        // Successfully finished
      @value(4) FAILED,           // Execution failed
      @value(5) CANCELLED         // Withdrawn by requester or agent
    };

    // ---- Priority levels ----
    enum TaskPriority {
      @value(0) LOW,
      @value(1) NORMAL,
      @value(2) HIGH,
      @value(3) CRITICAL
    };

    // ---- Task request ----
    // A planner or coordinator publishes a task for agents to claim.
    // Keyed by task_id so DDS KEEP_LAST gives the latest version.
    @extensibility(APPENDABLE) struct TaskRequest {
      @key string task_id;               // Unique task identifier

      TaskType type;                     // What kind of task
      TaskPriority priority;

      string requester_id;               // Agent or service requesting the task

      // Spatial target (optional -- not all tasks are spatially targeted)
      boolean has_target_pose;
      PoseSE3 target_pose;               // Goal pose (valid when flag true)
      boolean has_target_frame;
      FrameRef target_frame;             // Frame for target_pose (valid when flag true)
      boolean has_target_uri;
      SpatialUri target_uri;             // URI of target resource -- anchor, content,
                                         // service, or any addressable entity
                                         // (valid when flag true)

      // Task-specific parameters -- freeform JSON
      // Avoids premature schema commitment for diverse agent capabilities.
      // Examples:
      //   NAVIGATE: {"speed_mps": 1.5, "altitude_m": 30}
      //   OBSERVE:  {"sensor": "cam_front", "duration_sec": 60, "coverage_overlap": 0.3}
      //   MAP:      {"resolution_m": 0.05, "region_radius_m": 50}
      //   REPORT:   {"format": "json", "include_images": true}
      string params;                     // JSON object string; empty if no params

      // Timing
      boolean has_deadline;
      Time deadline;                     // Task must complete by this time
                                         // (valid when has_deadline == true)
      Time stamp;                        // Publication time
      uint32 ttl_sec;                    // Task offer expires after this
    };

    // ---- Task status ----
    // The executing agent (or the requester for CANCELLED) publishes
    // status updates. Keyed by task_id for KEEP_LAST per task.
    @extensibility(APPENDABLE) struct TaskStatus {
      @key string task_id;               // Mirrors TaskRequest.task_id

      TaskState state;
      string agent_id;                   // Agent executing (or that attempted);
                                         // empty if PENDING

      // Progress (optional -- meaningful for IN_PROGRESS)
      boolean has_progress;
      float progress;                    // 0..1 (valid when has_progress == true)

      // Result (optional -- meaningful for COMPLETED)
      boolean has_result_uri;
      SpatialUri result_uri;             // URI to result artifact (map, report, etc.)
                                         // (valid when has_result_uri == true)

      // Diagnostics
      string diagnostic;                 // Empty on success; error/status description
                                         // on FAILED or CANCELLED

      Time stamp;                        // Status update time
    };

    // ================================================================
    // FLEET COORDINATION
    // ================================================================
    //
    // Types that enable multi-agent task allocation over the DDS bus.
    // These define the information agents and coordinators exchange,
    // not the allocation algorithm. A round-robin dispatcher, a
    // market-based auction, and a centralized optimizer all consume
    // the same typed messages.

    // ---- Agent operational state ----
    enum AgentState {
      @value(0) IDLE,             // available for new tasks
      @value(1) BUSY,             // executing a task
      @value(2) CHARGING,         // recharging / refueling
      @value(3) RETURNING,        // returning to base / staging area
      @value(4) ERROR,            // fault condition -- not available
      @value(5) OFFLINE           // graceful shutdown / maintenance
    };

    // ---- Agent status advertisement ----
    // Each agent publishes its current status at regular intervals.
    // Keyed by agent_id; KEEP_LAST(1) per key with TRANSIENT_LOCAL
    // so new coordinators immediately see all active agents.
    //
    // This is the fleet-level complement to disco::Announce. Announce
    // tells you "a service exists with these profiles and coverage."
    // AgentStatus tells you "this specific agent is available, here's
    // what it can do right now, and here's its current state."
    @extensibility(APPENDABLE) struct AgentStatus {
      @key string agent_id;              // unique agent identifier

      string name;                       // human-readable (e.g., "Drone Unit 14")
      AgentState state;                  // current operational state

      // Capabilities -- which task types this agent can execute
      sequence<TaskType, 16> capable_tasks;

      // Current position (optional)
      boolean has_pose;
      FramedPose pose;                   // current pose with frame and uncertainty
                                         // (valid when has_pose == true)

      boolean has_geopose;
      spatial::core::GeoPose geopose;    // current geo-position (valid when flag true)

      // Resource levels (optional -- agent-type dependent)
      boolean has_battery_pct;
      float   battery_pct;               // [0..1] remaining charge

      boolean has_payload_kg;
      float   payload_kg;                // current payload mass
      boolean has_payload_capacity_kg;
      float   payload_capacity_kg;       // maximum payload mass

      boolean has_range_remaining_m;
      float   range_remaining_m;         // estimated remaining operational range (meters)

      // Current task (if BUSY)
      boolean has_current_task_id;
      string  current_task_id;           // task_id of current assignment

      // Queue depth -- how many tasks are queued behind the current one
      boolean has_queue_depth;
      uint32  queue_depth;

      // Extensible metadata (sensor suite, speed limits, special equipment, etc.)
      sequence<spatial::common::MetaKV, 16> attributes;

      Time   stamp;
      uint32 ttl_sec;                    // status expires if not refreshed
    };


    // ---- Task offer (agent -> coordinator) ----
    // An agent that can handle a TaskRequest publishes a TaskOffer
    // indicating its willingness and estimated cost. The coordinator
    // evaluates offers and publishes a TaskAssignment.
    //
    // This is optional. Simple deployments can skip offers entirely
    // and have the coordinator assign directly based on AgentStatus.
    // Offers enable decentralized decision-making where agents have
    // better local knowledge than the coordinator.
    @extensibility(APPENDABLE) struct TaskOffer {
      @key string offer_id;              // unique offer identifier
      string task_id;                    // references TaskRequest.task_id
      string agent_id;                   // offering agent

      // Estimated cost / fitness (lower is better; semantics are deployment-defined)
      float  cost;                       // e.g., estimated time (sec), energy (J), or normalized score

      // Estimated time to reach the task target
      boolean has_eta_sec;
      float   eta_sec;                   // estimated seconds to reach target

      // Distance to task target
      boolean has_distance_m;
      float   distance_m;                // straight-line or path distance (meters)

      // Agent's current resource snapshot at time of offer
      boolean has_battery_pct;
      float   battery_pct;

      // Freeform justification or constraints
      string  params;                    // JSON string; e.g., {"route": "via-corridor-A"}

      Time   stamp;
      uint32 ttl_sec;                    // offer expires if not accepted
    };


    // ---- Task assignment (coordinator -> agent) ----
    // The coordinator evaluates AgentStatus and/or TaskOffer messages
    // and publishes a TaskAssignment binding a task to a specific agent.
    // The assigned agent should respond with TaskStatus(ACCEPTED).
    //
    // Keyed by task_id -- at most one assignment per task.
    @extensibility(APPENDABLE) struct TaskAssignment {
      @key string task_id;               // references TaskRequest.task_id
      string agent_id;                   // assigned agent
      string coordinator_id;             // who made the assignment

      // Optional: selected offer reference
      boolean has_offer_id;
      string  offer_id;                  // references TaskOffer.offer_id (if offer-based)

      // Optional: override or refinement of the original TaskRequest params
      boolean has_params_override;
      string  params_override;           // JSON string; merged with TaskRequest.params

      Time   stamp;
    };


    // ---- Task handoff ----
    // When an agent cannot complete a task (low battery, leaving coverage,
    // hardware fault), it publishes a TaskHandoff before or alongside
    // TaskStatus(FAILED/CANCELLED). The coordinator uses this to
    // re-assign the task with context preserved.
    @extensibility(APPENDABLE) struct TaskHandoff {
      @key string handoff_id;            // unique handoff identifier
      string task_id;                    // original task being handed off
      string from_agent_id;              // agent releasing the task
      string reason;                     // human-readable (e.g., "battery below 15%")

      // Progress context for the next agent
      boolean has_progress;
      float   progress;                  // [0..1] how far the task got

      // Where the task was left off
      boolean has_last_pose;
      FramedPose last_pose;              // agent's pose at handoff, with frame and uncertainty
                                         // (valid when has_last_pose == true)

      // Task-specific continuation context -- whatever the next agent needs
      // to pick up where this one left off.
      string  context;                   // JSON string; e.g., {"waypoints_remaining": [...]}

      // Optional: preferred successor
      boolean has_preferred_agent_id;
      string  preferred_agent_id;        // agent the handoff prefers as successor

      Time   stamp;
    };

  }; // module agent
};

Example JSON (Informative)

Task Request:

{
  "task_id": "task/survey-block-7",
  "type": "OBSERVE",
  "priority": "HIGH",
  "requester_id": "planner/fleet-coordinator",
  "has_target_pose": true,
  "target_pose": {
    "t": [-122.415, 37.795, 30.0],
    "q": [0.0, 0.0, 0.0, 1.0]
  },
  "has_target_frame": true,
  "target_frame": {
    "uuid": "ae6f0a3e-7a3e-4b1e-9b1f-0e9f1b7c1a10",
    "fqn": "earth-fixed"
  },
  "has_target_uri": false,
  "params": "{\"sensor\": \"cam_nadir\", \"duration_sec\": 120, \"overlap\": 0.4}",
  "has_deadline": true,
  "deadline": { "sec": 1714074000, "nanosec": 0 },
  "stamp": { "sec": 1714070400, "nanosec": 0 },
  "ttl_sec": 300
}

Task Status:

{
  "task_id": "task/survey-block-7",
  "state": "IN_PROGRESS",
  "agent_id": "drone/unit-14",
  "has_progress": true,
  "progress": 0.45,
  "has_result_uri": false,
  "diagnostic": "",
  "stamp": { "sec": 1714071200, "nanosec": 0 }
}

Topic Layout

Type Topic QoS Notes
TaskRequest spatialdds/agent/tasks/task_request/v1 RELIABLE + TRANSIENT_LOCAL, KEEP_LAST(1) per key Coordinator publishes tasks.
TaskStatus spatialdds/agent/tasks/task_status/v1 RELIABLE + VOLATILE, KEEP_LAST(1) per key Agent reports lifecycle state.
AgentStatus spatialdds/agent/fleet/agent_status/v1 RELIABLE + TRANSIENT_LOCAL, KEEP_LAST(1) per key Agent advertises availability. Late joiners see all agents.
TaskOffer spatialdds/agent/fleet/task_offer/v1 RELIABLE + VOLATILE, KEEP_LAST(1) per key Optional: agent bids on a task.
TaskAssignment spatialdds/agent/fleet/task_assignment/v1 RELIABLE + TRANSIENT_LOCAL, KEEP_LAST(1) per key Coordinator assigns task to agent.
TaskHandoff spatialdds/agent/fleet/task_handoff/v1 RELIABLE + VOLATILE, KEEP_ALL Agent requests task transfer with context.

QoS defaults for agent topics

Topic Reliability Durability History
task_request RELIABLE TRANSIENT_LOCAL KEEP_LAST(1) per key
task_status RELIABLE VOLATILE KEEP_LAST(1) per key
agent_status RELIABLE TRANSIENT_LOCAL KEEP_LAST(1) per key
task_offer RELIABLE VOLATILE KEEP_LAST(1) per key
task_assignment RELIABLE TRANSIENT_LOCAL KEEP_LAST(1) per key
task_handoff RELIABLE VOLATILE KEEP_ALL

Agent Status:

{
  "agent_id": "drone/unit-14",
  "name": "Drone Unit 14",
  "state": "IDLE",
  "capable_tasks": ["NAVIGATE", "OBSERVE", "MAP"],
  "has_pose": true,
  "pose": {
    "pose": { "t": [12.5, -3.2, 1.1], "q": [0.0, 0.0, 0.0, 1.0] },
    "frame_ref": { "uuid": "ae6f0a3e-7a3e-4b1e-9b1f-0e9f1b7c1a10", "fqn": "facility-west/enu" },
    "cov": { "type": "COV_NONE" },
    "stamp": { "sec": 1714071000, "nanosec": 0 }
  },
  "has_geopose": false,
  "has_battery_pct": true,
  "battery_pct": 0.72,
  "has_payload_kg": true,
  "payload_kg": 0.0,
  "has_payload_capacity_kg": true,
  "payload_capacity_kg": 2.5,
  "has_range_remaining_m": true,
  "range_remaining_m": 4200.0,
  "has_current_task_id": false,
  "has_queue_depth": true,
  "queue_depth": 0,
  "stamp": { "sec": 1714071000, "nanosec": 0 },
  "ttl_sec": 30
}

Task Offer:

{
  "offer_id": "offer/unit-14/survey-block-7",
  "task_id": "task/survey-block-7",
  "agent_id": "drone/unit-14",
  "cost": 142.5,
  "has_eta_sec": true,
  "eta_sec": 45.0,
  "has_distance_m": true,
  "distance_m": 310.0,
  "has_battery_pct": true,
  "battery_pct": 0.72,
  "params": "{\"route\": \"direct\", \"estimated_energy_pct\": 0.18}",
  "stamp": { "sec": 1714071005, "nanosec": 0 },
  "ttl_sec": 30
}

Task Assignment:

{
  "task_id": "task/survey-block-7",
  "agent_id": "drone/unit-14",
  "coordinator_id": "planner/fleet-coordinator",
  "has_offer_id": true,
  "offer_id": "offer/unit-14/survey-block-7",
  "has_params_override": false,
  "stamp": { "sec": 1714071010, "nanosec": 0 }
}

Task Handoff:

{
  "task_id": "task/survey-block-7",
  "handoff_id": "handoff/unit-14/survey-block-7/001",
  "from_agent_id": "drone/unit-14",
  "reason": "battery below 15%",
  "has_progress": true,
  "progress": 0.63,
  "has_last_pose": true,
  "last_pose": {
    "pose": { "t": [45.2, 12.8, 30.0], "q": [0.0, 0.0, 0.38, 0.92] },
    "frame_ref": { "uuid": "ae6f0a3e-7a3e-4b1e-9b1f-0e9f1b7c1a10", "fqn": "earth-fixed" },
    "cov": { "type": "COV_NONE" },
    "stamp": { "sec": 1714072800, "nanosec": 0 }
  },
  "context": "{\"waypoints_remaining\": [[50.1, 15.0, 30.0], [55.3, 18.2, 30.0]], \"images_captured\": 147}",
  "has_preferred_agent_id": false,
  "stamp": { "sec": 1714072800, "nanosec": 0 }
}

Example: RF Beam Sensing Extension (Provisional)

This profile provides typed transport for phased-array beam power measurements used in ISAC research. It defines static array metadata (RfBeamMeta), per-sweep power vectors (RfBeamFrame), and multi-array batches (RfBeamArraySet). The design follows the Meta/Frame pattern used elsewhere in the sensing profiles and is intentionally provisional.

// SPDX-License-Identifier: MIT
// SpatialDDS RF Beam Sensing Profile 1.5 (Provisional Extension)
//
// PROVISIONAL: This profile is subject to breaking changes in future
// versions. Implementers SHOULD treat all struct layouts as unstable
// and MUST NOT assume wire compatibility across spec revisions.

#ifndef SPATIAL_CORE_INCLUDED
#define SPATIAL_CORE_INCLUDED
#include "core.idl"
#endif
#ifndef SPATIAL_SENSING_COMMON_INCLUDED
#define SPATIAL_SENSING_COMMON_INCLUDED
#include "common.idl"
#endif

module spatial { module sensing { module rf_beam {

  // Module identifier for discovery and schema registration
  const string MODULE_ID = "spatial.sensing.rf_beam/1.5";

  // Reuse Core + Sensing Common types
  typedef builtin::Time                          Time;
  typedef spatial::core::PoseSE3                 PoseSE3;
  typedef spatial::core::BlobRef                 BlobRef;
  typedef spatial::common::FrameRef              FrameRef;

  typedef spatial::sensing::common::StreamMeta   StreamMeta;
  typedef spatial::sensing::common::FrameHeader  FrameHeader;
  typedef spatial::sensing::common::FrameQuality FrameQuality;
  typedef spatial::sensing::common::Codec        Codec;
  typedef spatial::sensing::common::SampleType   SampleType;

  // ---- Beam sweep classification ----
  enum BeamSweepType {
    @value(0) EXHAUSTIVE,           // full codebook sweep (e.g., 64 beams)
    @value(1) HIERARCHICAL,         // multi-stage: wide beams -> narrow refinement
    @value(2) TRACKING,             // narrow sweep around predicted beam
    @value(3) PARTIAL,              // subset of codebook (AI-selected beams)
    @value(255) OTHER
  };

  // ---- Power measurement unit ----
  enum PowerUnit {
    @value(0) DBM,                  // decibels relative to 1 milliwatt (default)
    @value(1) LINEAR_MW,            // milliwatts (linear scale)
    @value(2) RSRP,                 // Reference Signal Received Power (3GPP)
    @value(255) OTHER_UNIT
  };

  // ---- Static array description ----
  // RELIABLE + TRANSIENT_LOCAL (late joiners receive the latest meta)
  @extensibility(APPENDABLE) struct RfBeamMeta {
    @key string stream_id;               // stable id for this beam stream
    StreamMeta base;                     // frame_ref, T_bus_sensor, nominal_rate_hz

    // --- Carrier ---
    float   center_freq_ghz;             // carrier frequency (e.g., 60.0, 28.0, 140.0)
    boolean has_bandwidth;
    float   bandwidth_ghz;               // valid when has_bandwidth == true (e.g., 0.02 for 20 MHz)

    // --- Phased array description ---
    uint16  n_elements;                  // antenna elements in the array (e.g., 16)
    uint16  n_beams;                     // codebook size (e.g., 64, 128, 256)

    // --- Spatial coverage ---
    float   fov_az_deg;                  // total azimuth FoV covered by codebook (e.g., 90)
    boolean has_fov_el;
    float   fov_el_deg;                  // valid when has_fov_el == true (e.g., 30)

    // --- Array identity within a rig (for multi-array setups) ---
    boolean has_array_index;
    uint8   array_index;                 // valid when has_array_index == true; 0-based
    string  array_label;                 // human-readable label (e.g., "front", "left", "rear", "right")

    // --- Codebook description (informative) ---
    string  codebook_type;               // e.g., "DFT-64", "DFT-oversampled-128", "hierarchical-3stage"

    // --- MIMO configuration (optional, for hybrid arrays) ---
    boolean has_mimo_config;
    uint16  n_tx;                        // valid when has_mimo_config == true
    uint16  n_rx;                        // valid when has_mimo_config == true

    // --- Power unit convention ---
    PowerUnit power_unit;                // unit for power in RfBeamFrame (default: DBM)

    string  schema_version;              // MUST be "spatial.sensing.rf_beam/1.5"
  };

  // ---- Per-sweep beam power measurement ----
  // BEST_EFFORT + KEEP_LAST=1
  @extensibility(APPENDABLE) struct RfBeamFrame {
    @key string stream_id;
    uint64 frame_seq;
    FrameHeader hdr;                     // t_start/t_end, optional sensor_pose, blobs[]

    BeamSweepType sweep_type;

    // --- Power vector ---
    // One entry per beam in codebook order (index 0 = beam 0, etc.)
    // Length MUST equal RfBeamMeta.n_beams for EXHAUSTIVE sweeps.
    // For PARTIAL/TRACKING sweeps, length <= n_beams; beam_indices
    // maps each entry to its codebook position.
    sequence<float, 1024> power;         // received power per beam (unit per RfBeamMeta.power_unit)

    // Sparse sweep support: when sweep_type != EXHAUSTIVE,
    // beam_indices maps power[i] to codebook index beam_indices[i].
    // Empty when sweep_type == EXHAUSTIVE (implicit 0..n_beams-1).
    sequence<uint16, 1024> beam_indices; // codebook indices; empty for exhaustive sweeps

    // --- Derived fields ---
    boolean has_best_beam;
    uint16  best_beam_idx;               // valid when has_best_beam == true
    float   best_beam_power;             // valid when has_best_beam == true (same unit)

    // --- Link state (ISAC-specific) ---
    boolean has_blockage_state;
    boolean is_blocked;                  // valid when has_blockage_state == true
    float   blockage_confidence;         // valid when has_blockage_state == true (0.0..1.0)

    // --- Signal quality (optional) ---
    boolean has_snr_db;
    float   snr_db;                      // valid when has_snr_db == true

    // --- Frame quality ---
    boolean has_quality;
    FrameQuality quality;                // valid when has_quality == true
  };

  // ---- Multi-array synchronized set ----
  // For rigs with multiple phased arrays (e.g., V2V with 4x arrays for 360 deg coverage).
  // Batches one RfBeamFrame per array at the same time step.
  // BEST_EFFORT + KEEP_LAST=1
  @extensibility(APPENDABLE) struct RfBeamArraySet {
    @key string set_id;                  // stable id for this array set
    uint64 frame_seq;
    Time   stamp;                        // common timestamp for all arrays

    sequence<RfBeamFrame, 8> arrays;     // one per phased array in the rig

    // Cross-array best beam (global index = array_index * n_beams + beam_idx)
    boolean has_overall_best;
    uint16  overall_best_array_idx;      // valid when has_overall_best == true
    uint16  overall_best_beam_idx;       // valid when has_overall_best == true
    float   overall_best_power;          // valid when has_overall_best == true
  };

}; }; };

Example: Radio Fingerprint Extension (Provisional)

This profile provides typed transport for radio-environment observations used by radio-assisted localization and indoor positioning pipelines. It targets commodity radios (WiFi, BLE, UWB, cellular) and closes the "radio via freeform metadata only" gap by introducing schema-enforced observation structs.

The profile defines transport only. It does not define positioning, trilateration, filtering, or sensor-fusion algorithms.

Module ID: spatial.sensing.radio/1.5
Dependency: spatial.sensing.common@1.x
Status: Provisional (K-R1 maturity gate)

Overview

RadioSensorMeta follows the static Meta pattern (RELIABLE + TRANSIENT_LOCAL) and publishes sensor capabilities. RadioScan is the streaming message carrying per-scan observations. Each scan is a snapshot of visible transmitters for one radio technology at one scan instant/window.

Relationship to sensing.rf_beam

sensing.rf_beam covers phased-array mmWave beam power vectors and ISAC-style beam management.
sensing.radio covers commodity radio fingerprints and ranging observations (WiFi/BLE/UWB/cellular).
They are complementary and may be published together by the same node.

Profile Scope Typical Frequency Key Measurement
sensing.rf_beam mmWave phased arrays (28/60/140 GHz) 10 Hz per sweep Per-beam power vector
sensing.radio WiFi/BLE/UWB/cellular 0.1–10 Hz per scan Per-transmitter RSSI/RTT/AoA/Range

IDL (Provisional)

// SPDX-License-Identifier: MIT
// SpatialDDS Radio Fingerprint (sensing.radio) 1.5 — Provisional Extension
//
// PROVISIONAL: This profile is subject to breaking changes in future
// versions. Implementers SHOULD treat all struct layouts as unstable
// and MUST NOT assume wire compatibility across spec revisions.

#ifndef SPATIAL_CORE_INCLUDED
#define SPATIAL_CORE_INCLUDED
#include "core.idl"
#endif
#ifndef SPATIAL_SENSING_COMMON_INCLUDED
#define SPATIAL_SENSING_COMMON_INCLUDED
#include "common.idl"
#endif

module spatial { module sensing { module radio {

  const string MODULE_ID = "spatial.sensing.radio/1.5";

  typedef builtin::Time                          Time;
  typedef spatial::core::PoseSE3                 PoseSE3;
  typedef spatial::common::FrameRef              FrameRef;
  typedef spatial::common::MetaKV                MetaKV;
  typedef spatial::sensing::common::StreamMeta   StreamMeta;

  enum RadioType {
    @value(0)   WIFI,
    @value(1)   BLE,
    @value(2)   BT_CLASSIC,
    @value(3)   UWB,
    @value(4)   CELLULAR,
    @value(5)   LORA,
    @value(255) OTHER_RADIO
  };

  enum WifiBand {
    @value(0) BAND_UNKNOWN,
    @value(1) BAND_2_4GHZ,
    @value(2) BAND_5GHZ,
    @value(3) BAND_6GHZ,
    @value(4) BAND_60GHZ
  };

  enum RadioMeasurementKind {
    @value(0)  RSSI,
    @value(1)  RTT_NS,
    @value(2)  AOA_DEG,
    @value(3)  RANGE_M,
    @value(4)  RSRP,
    @value(5)  CSI_REF,
    @value(255) OTHER_MEASURE
  };

  @extensibility(APPENDABLE) struct RadioObservation {
    string               identifier;
    RadioMeasurementKind measurement_kind;
    float                value;

    boolean  has_frequency;
    float    frequency_mhz;
    boolean  has_band;
    WifiBand band;
    boolean  has_ssid;
    string   ssid;
    boolean  has_channel;
    uint16   channel;

    boolean  has_major_minor;
    uint16   major;
    uint16   minor;
    boolean  has_tx_power;
    int8     tx_power_dbm;

    boolean  has_range;
    float    range_m;
    boolean  has_range_std;
    float    range_std_m;

    boolean  has_aoa_azimuth;
    float    aoa_azimuth_deg;
    boolean  has_aoa_elevation;
    float    aoa_elevation_deg;

    boolean  has_noise_floor;
    float    noise_floor_dbm;
    boolean  has_measurement_count;
    uint8    measurement_count;
  };

  @extensibility(APPENDABLE) struct RadioScan {
    @key string sensor_id;
    RadioType   radio_type;
    uint64      scan_seq;
    Time        stamp;

    boolean     has_scan_duration;
    float       scan_duration_s;

    sequence<RadioObservation, 256> observations;

    boolean     has_aggregation_window;
    float       aggregation_window_s;

    string      source_id;

    boolean     has_sensor_pose;
    PoseSE3     sensor_pose;
    FrameRef    pose_frame_ref;

    string      schema_version; // MUST be "spatial.sensing.radio/1.5"
  };

  @extensibility(APPENDABLE) struct RadioSensorMeta {
    @key string sensor_id;
    StreamMeta  base;

    RadioType   radio_type;

    boolean     has_rssi;
    boolean     has_rtt;
    boolean     has_aoa;
    boolean     has_csi;

    boolean     has_wifi_bands;
    sequence<WifiBand, 4> supported_bands;

    boolean     has_ble_version;
    string      ble_version;

    string      device_model;
    string      platform;

    boolean     has_max_observations;
    uint16      max_observations;
    boolean     has_typical_scan_duration;
    float       typical_scan_duration_s;

    string      schema_version; // MUST be "spatial.sensing.radio/1.5"
  };

}; }; };

Observation Semantics (Normative)

measurement_kind determines the unit and interpretation of RadioObservation.value.

Kind Value Units Typical Source
RSSI dBm WiFi and BLE scans
RTT_NS nanoseconds WiFi FTM, UWB TWR
AOA_DEG degrees UWB/BLE AoA
RANGE_M meters Derived range
RSRP dBm Cellular
CSI_REF n/a (value unused) CSI blob reference workflows

A single RadioScan MAY include mixed measurement_kind values.

Identifier Conventions (Normative)

RadioType Identifier Format Example
WIFI BSSID, lowercase colon-separated hex aa:bb:cc:dd:ee:ff
BLE UUID (uppercase with hyphens) or MAC 12345678-1234-1234-1234-123456789ABC
UWB Short address or session ID 0x1A2B
CELLULAR MCC-MNC-LAC-CID 310-260-12345-67890

Consumers performing fingerprint matching SHOULD normalize identifiers before comparison.

Scan Timing and Aggregation (Normative)

  • stamp MUST represent the midpoint of the scan window.
  • If has_scan_duration == true, scan_duration_s MUST report the full scan-window duration.
  • If has_aggregation_window == true, aggregation_window_s reports the total time window used to aggregate observations from multiple scans.
  • Producers publishing raw scans SHOULD leave has_aggregation_window = false.

Privacy Considerations (Normative Guidance)

Radio identifiers can expose device/network identity. Producers in privacy-sensitive deployments SHOULD: - anonymize or hash identifiers where permitted, - avoid publishing SSIDs unless explicitly needed, and - document identifier handling and retention policy.

Topic Patterns

Topic Message Type QoS
spatialdds/<scene>/radio/<sensor_id>/scan/v1 RadioScan RADIO_SCAN_RT
spatialdds/<scene>/radio/<sensor_id>/meta/v1 RadioSensorMeta RELIABLE + TRANSIENT_LOCAL

Example JSON (Informative)

WiFi scan:

{
  "sensor_id": "hololens2-wifi-01",
  "radio_type": "WIFI",
  "scan_seq": 42,
  "stamp": { "sec": 1714071012, "nanosec": 500000000 },
  "has_scan_duration": true,
  "scan_duration_s": 2.1,
  "observations": [
    {
      "identifier": "aa:bb:cc:dd:ee:01",
      "measurement_kind": "RSSI",
      "value": -52.0,
      "has_frequency": true,
      "frequency_mhz": 5180.0,
      "has_band": true,
      "band": "BAND_5GHZ",
      "has_ssid": true,
      "ssid": "ETH-WiFi",
      "has_channel": true,
      "channel": 36
    }
  ],
  "has_aggregation_window": true,
  "aggregation_window_s": 4.0,
  "source_id": "lamar-cab-hololens-session-17",
  "schema_version": "spatial.sensing.radio/1.5"
}

UWB ranging round:

{
  "sensor_id": "uwb-tag-reader-01",
  "radio_type": "UWB",
  "scan_seq": 5017,
  "stamp": { "sec": 1714071020, "nanosec": 250000000 },
  "observations": [
    {
      "identifier": "0x1A2B",
      "measurement_kind": "RANGE_M",
      "value": 3.21,
      "has_range": true,
      "range_m": 3.21,
      "has_range_std": true,
      "range_std_m": 0.08,
      "has_aoa_azimuth": true,
      "aoa_azimuth_deg": 23.5
    }
  ],
  "source_id": "warehouse-uwb-reader-alpha",
  "schema_version": "spatial.sensing.radio/1.5"
}

Maturity Gate (K-R1)

Promotion to stable requires: 1. At least one conformance dataset exercising WiFi and BLE paths with at least 20 checks passing. 2. At least one independent implementation ingesting reference WiFi/BLE files through RadioScan. 3. No breaking IDL changes for six months after initial publication.

Integration Notes (Informative)

Discovery integration: Neural and agent services advertise via Announce with ServiceKind::OTHER. To signal neural or agent capabilities, services SHOULD include feature flags in caps.features such as neural.field_meta, neural.view_synth, or agent.tasking.

Topic naming: following spatialdds/<domain>/<stream>/<type>/<version>:

Message Suggested Topic Pattern
NeuralFieldMeta spatialdds/neural/<field_id>/field_meta/v1
ViewSynthesisRequest spatialdds/neural/<field_id>/view_synth_req/v1
ViewSynthesisResponse Uses reply_topic from request
TaskRequest spatialdds/agent/tasks/task_request/v1
TaskStatus spatialdds/agent/tasks/task_status/v1
AgentStatus spatialdds/agent/fleet/agent_status/v1
TaskOffer spatialdds/agent/fleet/task_offer/v1
TaskAssignment spatialdds/agent/fleet/task_assignment/v1
TaskHandoff spatialdds/agent/fleet/task_handoff/v1
RadioSensorMeta spatialdds/<scene>/radio/<sensor_id>/meta/v1
RadioScan spatialdds/<scene>/radio/<sensor_id>/scan/v1

QoS suggestions (informative):

Message Reliability Durability History
NeuralFieldMeta RELIABLE TRANSIENT_LOCAL KEEP_LAST(1) per key
ViewSynthesisRequest RELIABLE VOLATILE KEEP_ALL
ViewSynthesisResponse RELIABLE VOLATILE KEEP_LAST(1) per key
TaskRequest RELIABLE TRANSIENT_LOCAL KEEP_LAST(1) per key
TaskStatus RELIABLE VOLATILE KEEP_LAST(1) per key
AgentStatus RELIABLE TRANSIENT_LOCAL KEEP_LAST(1) per key
TaskOffer RELIABLE VOLATILE KEEP_LAST(1) per key
TaskAssignment RELIABLE TRANSIENT_LOCAL KEEP_LAST(1) per key
TaskHandoff RELIABLE VOLATILE KEEP_ALL
RadioSensorMeta RELIABLE TRANSIENT_LOCAL KEEP_LAST(1) per key
RadioScan BEST_EFFORT VOLATILE KEEP_LAST(1)

Profile matrix: spatial.neural/1.5, spatial.agent/1.5, spatial.sensing.rf_beam/1.5, and spatial.sensing.radio/1.5 are provisional Appendix E profiles. When promoted to stable in a future version, they move to Appendix D.