Appendix D: Extension Profiles
These extensions provide domain-specific capabilities beyond the Core profile. The Sensing Common module supplies reusable sensing metadata, ROI negotiation structures, and codec/payload descriptors that the specialized sensor profiles build upon. The VIO profile carries raw and fused IMU/magnetometer samples. The Vision profile shares camera metadata, encoded frames, and optional feature tracks for perception pipelines. The SLAM Frontend profile adds features and keyframes for SLAM and SfM pipelines. The Semantics profile allows 2D and 3D object detections to be exchanged for AR, robotics, and analytics use cases. The Radar profile streams radar tensors, derived detections, and optional ROI control. The Lidar profile transports compressed point clouds, associated metadata, and optional detections for mapping and perception workloads. The AR+Geo profile adds GeoPose, frame transforms, and geo-anchoring structures, which allow clients to align local coordinate systems with global reference frames and support persistent AR content.
Common Type Aliases
Shared numeric array typedefs used across SpatialDDS modules.
// SPDX-License-Identifier: MIT
// SpatialDDS Common Type Aliases 1.4
#ifndef SPATIAL_COMMON_TYPES_INCLUDED
#define SPATIAL_COMMON_TYPES_INCLUDED
module builtin {
@extensibility(FINAL) struct Time {
int32 sec; // seconds since UNIX epoch (UTC)
uint32 nanosec; // nanoseconds [0, 1e9)
};
};
module spatial {
module common {
typedef double BBox2D[4];
typedef double Aabb3D[6];
typedef double Vec3[3];
typedef double Mat3x3[9];
typedef double Mat6x6[36];
typedef double QuaternionXYZW[4]; // GeoPose order (x, y, z, w)
enum CovarianceType {
@value(0) COV_NONE,
@value(3) COV_POS3,
@value(6) COV_POSE6
};
};
};
#endif // SPATIAL_COMMON_TYPES_INCLUDED
Geometry Primitives
Stable frame references shared across profiles.
#ifndef SPATIAL_GEOMETRY_INCLUDED
#define SPATIAL_GEOMETRY_INCLUDED
// SPDX-License-Identifier: MIT
// SpatialDDS Geometry 1.0
module spatial {
module geometry {
// Stable, typo-proof frame identity (breaking change).
// Equality is by uuid; fqn is a normalized, human-readable alias.
@extensibility(APPENDABLE) struct FrameRef {
uint8 uuid[16]; // REQUIRED: stable identifier for the frame
string fqn; // REQUIRED: normalized FQN, e.g., "oarc/rig01/cam_front"
};
}; // module geometry
};
#endif // SPATIAL_GEOMETRY_INCLUDED
Sensing Common Extension
Shared base types, enums, and ROI negotiation utilities reused by all sensing profiles (radar, lidar, vision).
// SPDX-License-Identifier: MIT
// SpatialDDS Sensing Common 1.4 (Extension module)
#ifndef SPATIAL_CORE_INCLUDED
#define SPATIAL_CORE_INCLUDED
#include "core.idl"
#endif
module spatial { module sensing { module common {
const string MODULE_ID = "spatial.sensing.common/1.4";
// --- Standard sizing tiers ---
// Use these to bound sequences for detections and other per-frame arrays.
const uint32 SZ_TINY = 64;
const uint32 SZ_SMALL = 256;
const uint32 SZ_MEDIUM = 2048;
const uint32 SZ_LARGE = 8192;
const uint32 SZ_XL = 32768;
// Reuse Core primitives (time, pose, blob references)
typedef spatial::core::Time Time;
typedef spatial::core::PoseSE3 PoseSE3;
typedef spatial::core::BlobRef BlobRef;
typedef spatial::geometry::FrameRef FrameRef;
// ---- Axes & Regions (for tensors or scans) ----
enum AxisEncoding {
@value(0) CENTERS,
@value(1) LINSPACE
};
// Compact parametric axis definition
@extensibility(APPENDABLE) struct Linspace {
double start; // first point
double step; // spacing (may be negative for descending axes)
uint32 count; // number of samples (>=1)
};
// Discriminated union: carries only one encoding on wire
@extensibility(APPENDABLE) union AxisSpec switch (AxisEncoding) {
case CENTERS: sequence<double, 65535> centers;
case LINSPACE: Linspace lin;
};
@extensibility(APPENDABLE) struct Axis {
string name; // "range","azimuth","elevation","doppler","time","channel"
string unit; // "m","deg","m/s","Hz","s",...
AxisSpec spec; // encoding of the axis samples (centers or linspace)
};
@extensibility(APPENDABLE) struct ROI {
// Range bounds (meters). When has_range == false, consumers MUST ignore range_min/range_max.
boolean has_range;
float range_min;
float range_max;
// Azimuth bounds (degrees). When has_azimuth == false, azimuth bounds are unspecified.
boolean has_azimuth;
float az_min;
float az_max;
// Elevation bounds (degrees). When has_elevation == false, elevation bounds are unspecified.
boolean has_elevation;
float el_min;
float el_max;
// Doppler bounds (m/s). When has_doppler == false, doppler_min/doppler_max are unspecified.
boolean has_doppler;
float dop_min;
float dop_max;
// Image-plane ROI for vision (pixels). When has_image_roi == false, u/v bounds are unspecified.
boolean has_image_roi;
int32 u_min;
int32 v_min;
int32 u_max;
int32 v_max;
// Indicates this ROI covers the entire valid domain of its axes. When true, all numeric bounds may be ignored.
boolean global;
};
// ---- Codecs / Payload kinds (shared enums) ----
enum Codec {
@value(0) CODEC_NONE,
@value(1) LZ4,
@value(2) ZSTD,
@value(3) GZIP,
@value(10) DRACO, // geometry compression
@value(20) JPEG,
@value(21) H264,
@value(22) H265,
@value(23) AV1,
@value(40) FP8Q,
@value(41) FP4Q,
@value(42) AE_V1
};
enum PayloadKind {
@value(0) DENSE_TILES, // tiled dense blocks (e.g., tensor tiles)
@value(1) SPARSE_COO, // sparse indices + values
@value(2) LATENT, // learned latent vectors
@value(10) BLOB_GEOMETRY, // PCC/PLY/glTF+Draco
@value(11) BLOB_RASTER // JPEG/GOP chunk(s)
};
enum SampleType { // post-decode voxel/point sample type
@value(0) U8_MAG,
@value(1) F16_MAG,
@value(2) CF16,
@value(3) CF32,
@value(4) MAGPHASE_S8
};
// ---- Stream identity & calibration header shared by sensors ----
@extensibility(APPENDABLE) struct StreamMeta {
@key string stream_id; // stable id for this sensor stream
FrameRef frame_ref; // mounting frame (Core frame naming)
PoseSE3 T_bus_sensor; // extrinsics (sensor in bus frame)
double nominal_rate_hz; // advertised cadence
string schema_version; // MUST be "spatial.sensing.common/1.4"
};
// ---- Frame index header shared by sensors (small, on-bus) ----
@extensibility(APPENDABLE) struct FrameHeader {
@key string stream_id;
uint64 frame_seq;
Time t_start;
Time t_end;
// Optional sensor pose at acquisition (moving platforms)
boolean has_sensor_pose;
PoseSE3 sensor_pose;
// data pointers: heavy bytes referenced as blobs
sequence<BlobRef, SZ_SMALL> blobs;
};
// ---- Quality & health (uniform across sensors) ----
enum Health {
@value(0) OK,
@value(1) DEGRADED,
@value(2) ERROR
};
@extensibility(APPENDABLE) struct FrameQuality {
boolean has_snr_db;
float snr_db; // valid when has_snr_db == true
float percent_valid; // 0..100
Health health;
string note; // short diagnostic
};
// ---- ROI request/reply (control-plane pattern) ----
@extensibility(APPENDABLE) struct ROIRequest {
@key string stream_id;
uint64 request_id;
Time t_start; Time t_end;
ROI roi;
boolean wants_payload_kind; PayloadKind desired_payload_kind;
boolean wants_codec; Codec desired_codec;
boolean wants_sample_type; SampleType desired_sample_type;
int32 max_bytes; // -1 for unlimited
};
@extensibility(APPENDABLE) struct ROIReply {
@key string stream_id;
uint64 request_id;
// Typically returns new frames whose blobs contain only the ROI
sequence<spatial::sensing::common::FrameHeader, 64> frames;
};
}; }; };
Standard Sequence Bounds (Normative)
| Payload | Recommended Bound | Rationale |
|---|---|---|
| 2D Detections (per frame) | SZ_MEDIUM (2048) |
Typical object detectors |
| 3D Detections (LiDAR) | SZ_SMALL (256) |
Clusters/objects, not raw points |
| Radar Detections (micro-dets) | SZ_XL (32768) |
Numerous sparse returns per frame |
| Keypoints/Tracks (per frame) | SZ_LARGE (8192) |
Feature-rich frames |
Producers SHOULD choose the smallest tier that covers real workloads; exceeding these bounds requires a new profile minor.
Axis Encoding (Normative)
The Axis struct embeds a discriminated union to ensure only one encoding is transmitted on the wire.
enum AxisEncoding { CENTERS = 0, LINSPACE = 1 };
@extensibility(APPENDABLE) struct Linspace { double start; double step; uint32 count; };
@extensibility(APPENDABLE) union AxisSpec switch (AxisEncoding) {
case CENTERS: sequence<double, 65535> centers;
case LINSPACE: Linspace lin;
default: ;
};
@extensibility(APPENDABLE) struct Axis { string name; string unit; AxisSpec spec; };
CENTERS— Explicit sample positions carried asdoublevalues.LINSPACE— Uniform grid defined bystart + i * stepfori ∈ [0, count‑1].- Negative
stepindicates descending axes. countMUST be ≥ 1 andstep * (count – 1) + startyields the last coordinate.
The legacy start, step, centers, and has_centers fields are removed to eliminate ambiguity.
VIO / Inertial Extension
Raw IMU/mag samples, 9-DoF bundles, and fused state outputs.
// SPDX-License-Identifier: MIT
// SpatialDDS VIO/Inertial 1.4
#ifndef SPATIAL_CORE_INCLUDED
#define SPATIAL_CORE_INCLUDED
#include "core.idl"
#endif
module spatial {
module vio {
const string MODULE_ID = "spatial.vio/1.4";
typedef spatial::core::Time Time;
typedef spatial::geometry::FrameRef FrameRef;
// IMU calibration
@extensibility(APPENDABLE) struct ImuInfo {
@key string imu_id;
FrameRef frame_ref;
double accel_noise_density; // (m/s^2)/√Hz
double gyro_noise_density; // (rad/s)/√Hz
double accel_random_walk; // (m/s^3)/√Hz
double gyro_random_walk; // (rad/s^2)/√Hz
Time stamp;
};
// Raw IMU sample
@extensibility(APPENDABLE) struct ImuSample {
@key string imu_id;
spatial::common::Vec3 accel; // m/s^2
spatial::common::Vec3 gyro; // rad/s
Time stamp;
string source_id;
uint64 seq;
};
// Magnetometer
@extensibility(APPENDABLE) struct MagnetometerSample {
@key string mag_id;
spatial::common::Vec3 mag; // microtesla
Time stamp;
FrameRef frame_ref;
string source_id;
uint64 seq;
};
// Convenience raw 9-DoF bundle
@extensibility(APPENDABLE) struct SensorFusionSample {
@key string fusion_id; // e.g., device id
spatial::common::Vec3 accel; // m/s^2
spatial::common::Vec3 gyro; // rad/s
spatial::common::Vec3 mag; // microtesla
Time stamp;
FrameRef frame_ref;
string source_id;
uint64 seq;
};
// Fused state (orientation ± position)
enum FusionMode {
@value(0) ORIENTATION_3DOF,
@value(1) ORIENTATION_6DOF,
@value(2) POSE_6DOF
};
enum FusionSourceKind {
@value(0) EKF,
@value(1) AHRS,
@value(2) VIO,
@value(3) IMU_ONLY,
@value(4) MAG_AIDED,
@value(5) AR_PLATFORM
};
@extensibility(APPENDABLE) struct FusedState {
@key string fusion_id;
FusionMode mode;
FusionSourceKind source_kind;
spatial::common::QuaternionXYZW q; // quaternion (x,y,z,w) in GeoPose order
boolean has_position;
spatial::common::Vec3 t; // meters, in frame_ref
boolean has_gravity;
spatial::common::Vec3 gravity; // m/s^2
boolean has_lin_accel;
spatial::common::Vec3 lin_accel; // m/s^2
boolean has_gyro_bias;
spatial::common::Vec3 gyro_bias; // rad/s
boolean has_accel_bias;
spatial::common::Vec3 accel_bias; // m/s^2
boolean has_cov_orient;
spatial::common::Mat3x3 cov_orient; // 3x3 covariance
boolean has_cov_pos;
spatial::common::Mat3x3 cov_pos; // 3x3 covariance
Time stamp;
FrameRef frame_ref;
string source_id;
uint64 seq;
double quality; // 0..1
};
}; // module vio
};
Vision Extension
Camera intrinsics, video frames, and keypoints/tracks for perception and analytics pipelines. ROI semantics follow Sensing Common presence flags (no NaN sentinels; axes use the CENTERS/LINSPACE union encoding).
// SPDX-License-Identifier: MIT
// SpatialDDS Vision (sensing.vision) 1.4 — Extension profile
#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 vision {
// Module identifier for discovery and schema registration
const string MODULE_ID = "spatial.sensing.vision/1.4";
// Reuse Core + Sensing Common
typedef spatial::core::Time Time;
typedef spatial::core::PoseSE3 PoseSE3;
typedef spatial::core::BlobRef BlobRef;
typedef spatial::geometry::FrameRef FrameRef;
typedef spatial::sensing::common::Codec Codec; // JPEG/H264/H265/AV1, etc.
typedef spatial::sensing::common::PayloadKind PayloadKind; // use BLOB_RASTER for frames/GOPs
typedef spatial::sensing::common::SampleType SampleType;
typedef spatial::sensing::common::Axis Axis;
typedef spatial::sensing::common::ROI ROI;
typedef spatial::sensing::common::StreamMeta StreamMeta;
typedef spatial::sensing::common::FrameHeader FrameHeader;
typedef spatial::sensing::common::FrameQuality FrameQuality;
typedef spatial::sensing::common::ROIRequest ROIRequest;
typedef spatial::sensing::common::ROIReply ROIReply;
// ROI bounds follow Sensing Common presence flags.
// Axis samples are encoded via the Sensing Common union (CENTERS or LINSPACE).
// Camera / imaging specifics
enum CamModel {
@value(0) PINHOLE,
@value(1) FISHEYE_EQUIDISTANT,
@value(2) KB_4,
@value(3) OMNI
};
enum Distortion {
@value(0) NONE,
@value(1) RADTAN,
@value(2) KANNALA_BRANDT
};
enum PixFormat {
@value(0) UNKNOWN,
@value(1) YUV420,
@value(2) RGB8,
@value(3) BGR8,
@value(4) RGBA8,
@value(10) RAW10,
@value(12) RAW12,
@value(16) RAW16
};
enum ColorSpace {
@value(0) SRGB,
@value(1) REC709,
@value(2) REC2020,
@value(10) LINEAR
};
enum RigRole {
@value(0) LEFT,
@value(1) RIGHT,
@value(2) CENTER,
@value(3) AUX
};
@extensibility(APPENDABLE) struct CamIntrinsics {
CamModel model;
uint16 width; uint16 height;
float fx; float fy; float cx; float cy;
Distortion dist;
sequence<float,16> dist_params; // k1,k2,p1,p2,k3,... or KB params
float shutter_us; // exposure time
float readout_us; // rolling-shutter line time (0=global)
PixFormat pix; ColorSpace color;
string calib_version; // hash or tag
};
// Static description — RELIABLE + TRANSIENT_LOCAL (late joiners receive the latest meta)
@extensibility(APPENDABLE) struct VisionMeta {
@key string stream_id;
StreamMeta base; // frame_ref, T_bus_sensor, nominal_rate_hz
CamIntrinsics K; // intrinsics
RigRole role; // for stereo/rigs
string rig_id; // shared id across synchronized cameras
// Default payload (frames ride as blobs)
Codec codec; // JPEG/H264/H265/AV1 or NONE
PixFormat pix; // for RAW payloads
ColorSpace color;
string schema_version; // MUST be "spatial.sensing.vision/1.4"
};
// Per-frame index — BEST_EFFORT + KEEP_LAST=1 (large payloads referenced via blobs)
@extensibility(APPENDABLE) struct VisionFrame {
@key string stream_id;
uint64 frame_seq;
FrameHeader hdr; // t_start/t_end, optional sensor_pose, blobs[]
// May override meta per-frame
Codec codec;
PixFormat pix;
ColorSpace color;
boolean has_line_readout_us;
float line_readout_us; // valid when has_line_readout_us == true
boolean rectified; // true if pre-rectified to pinhole
FrameQuality quality; // shared health/SNR notes
};
// Optional lightweight derivatives (for VIO/SfM/analytics)
@extensibility(APPENDABLE) struct Keypoint2D { float u; float v; float score; };
@extensibility(APPENDABLE) struct Track2D {
uint64 id;
sequence<Keypoint2D, spatial::sensing::common::SZ_LARGE> trail;
};
// Detections topic — BEST_EFFORT
@extensibility(APPENDABLE) struct VisionDetections {
@key string stream_id;
uint64 frame_seq;
Time stamp;
sequence<Keypoint2D, spatial::sensing::common::SZ_LARGE> keypoints;
sequence<Track2D, spatial::sensing::common::SZ_MEDIUM> tracks;
// Masks/boxes can be added in Semantics profile to keep Vision lean
};
}; }; };
SLAM Frontend Extension
Per-keyframe features, matches, landmarks, tracks, and camera calibration.
// SPDX-License-Identifier: MIT
// SpatialDDS SLAM Frontend 1.4
#ifndef SPATIAL_CORE_INCLUDED
#define SPATIAL_CORE_INCLUDED
#include "core.idl"
#endif
module spatial {
module slam_frontend {
const string MODULE_ID = "spatial.slam_frontend/1.4";
// Reuse core: Time, etc.
typedef spatial::core::Time Time;
typedef spatial::geometry::FrameRef FrameRef;
// Camera calibration
enum DistortionModelKind {
@value(0) NONE,
@value(1) RADTAN,
@value(2) EQUIDISTANT,
@value(3) KANNALA_BRANDT
};
@extensibility(APPENDABLE) struct CameraInfo {
@key string camera_id;
uint32 width; uint32 height; // pixels
double fx; double fy; // focal (px)
double cx; double cy; // principal point (px)
DistortionModelKind dist_kind;
sequence<double, 8> dist; // model params (bounded)
FrameRef frame_ref; // camera frame
Time stamp; // calib time (or 0 if static)
};
// 2D features & descriptors per keyframe
@extensibility(APPENDABLE) struct Feature2D {
double u; double v; // pixel coords
float scale; // px
float angle; // rad [0,2π)
float score; // detector response
};
@extensibility(APPENDABLE) struct KeyframeFeatures {
@key string node_id; // keyframe id
string camera_id;
string desc_type; // "ORB32","BRISK64","SPT256Q",...
uint32 desc_len; // bytes per descriptor
boolean row_major; // layout hint
sequence<Feature2D, 4096> keypoints; // ≤4096
sequence<uint8, 1048576> descriptors; // ≤1 MiB packed bytes
Time stamp;
string source_id;
uint64 seq;
};
// Optional cross-frame matches
@extensibility(APPENDABLE) struct FeatureMatch {
string node_id_a; uint32 idx_a;
string node_id_b; uint32 idx_b;
float score; // similarity or distance
};
@extensibility(APPENDABLE) struct MatchSet {
@key string match_id; // e.g., "kf_12<->kf_18"
sequence<FeatureMatch, 8192> matches;
Time stamp;
string source_id;
};
// Sparse 3D landmarks & tracks (optional)
@extensibility(APPENDABLE) struct Landmark {
@key string lm_id;
string map_id;
spatial::common::Vec3 p;
boolean has_cov;
spatial::common::Mat3x3 cov; // 3x3 pos covariance (row-major)
sequence<uint8, 4096> desc; // descriptor bytes
string desc_type;
Time stamp;
string source_id;
uint64 seq;
};
@extensibility(APPENDABLE) struct TrackObs {
string node_id; // observing keyframe
double u; double v; // pixel coords
};
@extensibility(APPENDABLE) struct Tracklet {
@key string track_id;
boolean has_lm_id; // true when lm_id is populated
string lm_id; // link to Landmark when present
sequence<TrackObs, 64> obs; // ≤64 obs
string source_id;
Time stamp;
};
}; // module slam_frontend
};
Semantics / Perception Extension
2D detections tied to keyframes; 3D oriented boxes in world frames (optionally tiled).
// SPDX-License-Identifier: MIT
// SpatialDDS Semantics 1.4
#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 semantics {
const string MODULE_ID = "spatial.semantics/1.4";
typedef spatial::core::Time Time;
typedef spatial::core::TileKey TileKey;
typedef spatial::geometry::FrameRef FrameRef;
// 2D detections per keyframe (image space)
@extensibility(APPENDABLE) struct Detection2D {
@key string det_id; // unique per publisher
string node_id; // keyframe id
string camera_id; // camera
string class_id; // ontology label
float score; // [0..1]
spatial::common::BBox2D bbox; // [u_min,v_min,u_max,v_max] (px)
boolean has_mask; // if a pixel mask exists
string mask_blob_id; // BlobChunk ref (role="mask")
Time stamp;
string source_id;
};
@extensibility(APPENDABLE) struct Detection2DSet {
@key string set_id; // batch id (e.g., node_id + seq)
string node_id;
string camera_id;
sequence<Detection2D, spatial::sensing::common::SZ_SMALL> dets; // ≤256
Time stamp;
string source_id;
};
// 3D detections in world/local frame (scene space)
@extensibility(APPENDABLE) struct Detection3D {
@key string det_id;
FrameRef frame_ref; // e.g., "map" (pose known elsewhere)
boolean has_tile;
TileKey tile_key; // valid when has_tile = true
string class_id; // semantic label
float score; // [0..1]
// Oriented bounding box in frame_ref
spatial::common::Vec3 center; // m
spatial::common::Vec3 size; // width,height,depth (m)
spatial::common::QuaternionXYZW q; // orientation (x,y,z,w) in GeoPose order
// Uncertainty (optional)
boolean has_covariance;
spatial::common::Mat3x3 cov_pos; // 3x3 position covariance (row-major)
spatial::common::Mat3x3 cov_rot; // 3x3 rotation covariance (row-major)
// Optional instance tracking
boolean has_track_id;
string track_id;
Time stamp;
string source_id;
};
@extensibility(APPENDABLE) struct Detection3DSet {
@key string set_id; // batch id
FrameRef frame_ref; // common frame for the set
boolean has_tile;
TileKey tile_key; // valid when has_tile = true
sequence<Detection3D, spatial::sensing::common::SZ_SMALL> dets; // ≤128
Time stamp;
string source_id;
};
}; // module semantics
};
Radar Extension
Radar tensor metadata, frame indices, ROI negotiation, and derived detection sets. ROI semantics follow Sensing Common presence flags (no NaN sentinels; axes use the CENTERS/LINSPACE union encoding).
// SPDX-License-Identifier: MIT
// SpatialDDS Radar (RAD) 1.4 — Extension profile
#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 rad {
// Module identifier for discovery and schema registration
const string MODULE_ID = "spatial.sensing.rad/1.4";
// Reuse Core + Sensing Common types
typedef spatial::core::Time Time;
typedef spatial::core::PoseSE3 PoseSE3;
typedef spatial::core::BlobRef BlobRef;
typedef spatial::geometry::FrameRef FrameRef;
typedef spatial::sensing::common::Axis Axis;
typedef spatial::sensing::common::ROI ROI;
typedef spatial::sensing::common::Codec Codec;
typedef spatial::sensing::common::PayloadKind PayloadKind;
typedef spatial::sensing::common::SampleType SampleType;
typedef spatial::sensing::common::StreamMeta StreamMeta;
typedef spatial::sensing::common::FrameHeader FrameHeader;
typedef spatial::sensing::common::FrameQuality FrameQuality;
typedef spatial::sensing::common::ROIRequest ROIRequest;
typedef spatial::sensing::common::ROIReply ROIReply;
// ROI bounds follow Sensing Common presence flags.
// Axis samples are encoded via the Sensing Common union (CENTERS or LINSPACE).
// Layout of the RAD tensor
enum RadTensorLayout {
@value(0) RA_D,
@value(1) R_AZ_EL_D,
@value(255) CUSTOM
};
// Static description — RELIABLE + TRANSIENT_LOCAL (late joiners receive the latest meta)
@extensibility(APPENDABLE) struct RadMeta {
@key string stream_id; // stable id for this radar stream
StreamMeta base; // frame_ref, T_bus_sensor, nominal_rate_hz
RadTensorLayout layout; // order of axes
sequence<Axis, 8> axes; // axis definitions (range/az/el/doppler)
SampleType voxel_type; // pre-compression sample type (e.g., CF16, U8_MAG)
string physical_meaning; // e.g., "post 3D-FFT complex baseband"
string schema_version; // MUST be "spatial.sensing.rad/1.4"
// Default payload settings for frames
PayloadKind payload_kind; // DENSE_TILES, SPARSE_COO, or LATENT
Codec codec; // LZ4, ZSTD, FP8Q, AE_V1, ...
boolean has_quant_scale;
float quant_scale; // valid when has_quant_scale == true
uint32 tile_size[4]; // for DENSE_TILES; unused dims = 1
};
// Per-frame index — BEST_EFFORT + KEEP_LAST=1 (large payloads referenced via blobs)
@extensibility(APPENDABLE) struct RadFrame {
@key string stream_id;
uint64 frame_seq;
FrameHeader hdr; // t_start/t_end, optional sensor_pose, blobs[]
PayloadKind payload_kind; // may override defaults
Codec codec; // may override defaults
SampleType voxel_type_after_decode; // post-decode type (e.g., CF16 → MAG_F16)
boolean has_quant_scale;
float quant_scale; // valid when has_quant_scale == true
FrameQuality quality; // SNR/valid%/health note
string proc_chain; // e.g., "FFT3D->hann->OS-CFAR"
};
// Lightweight derivative for fast fusion/tracking (optional)
@extensibility(APPENDABLE) struct RadDetection {
spatial::common::Vec3 xyz_m; // Cartesian point in base.frame_ref
boolean has_v_r_mps;
double v_r_mps; // valid when has_v_r_mps == true
float intensity; // reflectivity/magnitude
float quality; // 0..1
};
// Detections topic — BEST_EFFORT
@extensibility(APPENDABLE) struct RadDetectionSet {
@key string stream_id;
uint64 frame_seq;
FrameRef frame_ref; // coordinate frame of xyz_m
sequence<RadDetection, spatial::sensing::common::SZ_XL> dets;
Time stamp;
};
}; }; };
Lidar Extension
Lidar metadata, compressed point cloud frames, and detections. ROI semantics follow Sensing Common presence flags (no NaN sentinels; axes use the CENTERS/LINSPACE union encoding).
// SPDX-License-Identifier: MIT
// SpatialDDS LiDAR (sensing.lidar) 1.4 — Extension profile
#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 lidar {
// Module identifier for discovery and schema registration
const string MODULE_ID = "spatial.sensing.lidar/1.4";
// Reuse Core + Sensing Common
typedef spatial::core::Time Time;
typedef spatial::core::PoseSE3 PoseSE3;
typedef spatial::core::BlobRef BlobRef;
typedef spatial::geometry::FrameRef FrameRef;
typedef spatial::sensing::common::Codec Codec;
typedef spatial::sensing::common::PayloadKind PayloadKind; // use BLOB_GEOMETRY for clouds
typedef spatial::sensing::common::SampleType SampleType; // optional for per-point extras
typedef spatial::sensing::common::Axis Axis;
typedef spatial::sensing::common::ROI ROI;
typedef spatial::sensing::common::StreamMeta StreamMeta;
typedef spatial::sensing::common::FrameHeader FrameHeader;
typedef spatial::sensing::common::FrameQuality FrameQuality;
typedef spatial::sensing::common::ROIRequest ROIRequest;
typedef spatial::sensing::common::ROIReply ROIReply;
// ROI bounds follow Sensing Common presence flags.
// Axis samples are encoded via the Sensing Common union (CENTERS or LINSPACE).
// Device + data model
enum LidarType {
@value(0) SPINNING_2D,
@value(1) MULTI_BEAM_3D,
@value(2) SOLID_STATE
};
enum CloudEncoding {
@value(0) PCD,
@value(1) PLY,
@value(2) LAS,
@value(3) LAZ,
@value(10) GLTF_DRACO,
@value(20) MPEG_PCC,
@value(255) CUSTOM_BIN
};
enum PointLayout { // intensity, ring, normal
@value(0) XYZ_I,
@value(1) XYZ_I_R,
@value(2) XYZ_I_R_N
};
// Static description — RELIABLE + TRANSIENT_LOCAL (late joiners receive the latest meta)
@extensibility(APPENDABLE) struct LidarMeta {
@key string stream_id;
StreamMeta base; // frame_ref, T_bus_sensor, nominal_rate_hz
LidarType type;
uint16 n_rings; // 0 if N/A
float min_range_m; float max_range_m;
float horiz_fov_deg_min; float horiz_fov_deg_max;
float vert_fov_deg_min; float vert_fov_deg_max;
// Default payload for frames (clouds ride as blobs)
CloudEncoding encoding; // PCD/PLY/LAS/LAZ/etc.
Codec codec; // ZSTD/LZ4/DRACO/…
PointLayout layout; // expected fields when decoded
string schema_version; // MUST be "spatial.sensing.lidar/1.4"
};
// Per-frame index — BEST_EFFORT + KEEP_LAST=1 (large payloads referenced via blobs)
@extensibility(APPENDABLE) struct LidarFrame {
@key string stream_id;
uint64 frame_seq;
FrameHeader hdr; // t_start/t_end, optional sensor_pose, blobs[]
CloudEncoding encoding; // may override meta
Codec codec; // may override meta
PointLayout layout; // may override meta
// Optional quick hints (for health/telemetry)
boolean has_average_range_m;
float average_range_m; // valid when has_average_range_m == true
boolean has_percent_valid;
float percent_valid; // valid when has_percent_valid == true (0..100)
boolean has_quality;
FrameQuality quality; // valid when has_quality == true
};
// Lightweight derivative for immediate fusion/tracking (optional)
@extensibility(APPENDABLE) struct LidarDetection {
spatial::common::Vec3 xyz_m;
float intensity;
uint16 ring;
float quality; // 0..1
};
// Detections topic — BEST_EFFORT
@extensibility(APPENDABLE) struct LidarDetectionSet {
@key string stream_id;
uint64 frame_seq;
FrameRef frame_ref; // coordinate frame of xyz_m
sequence<LidarDetection, spatial::sensing::common::SZ_SMALL> dets;
Time stamp;
};
}; }; };
AR + Geo Extension
Geo-fixed nodes for easy consumption by AR clients & multi-agent alignment.
// SPDX-License-Identifier: MIT
// SpatialDDS AR+Geo 1.4
#ifndef SPATIAL_CORE_INCLUDED
#define SPATIAL_CORE_INCLUDED
#include "core.idl"
#endif
module spatial {
module argeo {
const string MODULE_ID = "spatial.argeo/1.4";
typedef spatial::core::Time Time;
typedef spatial::core::PoseSE3 PoseSE3;
typedef spatial::core::GeoPose GeoPose;
typedef spatial::geometry::FrameRef FrameRef;
@extensibility(APPENDABLE) struct NodeGeo {
string map_id;
@key string node_id; // same id as core::Node
PoseSE3 pose; // local pose in map frame
GeoPose geopose; // corresponding global pose (WGS84/ECEF/ENU/NED)
boolean has_cov;
spatial::common::Mat6x6 cov; // 6x6 covariance in local frame
Time stamp;
FrameRef frame_ref; // local frame
string source_id;
uint64 seq;
uint64 graph_epoch;
};
}; // module argeo
};