Expand description
cxx::bridge core for the Isaac Sim Rust SDK.
Exposes a process-wide consumer registry and producer registry that
adapters (dora, rerun, custom) plug into. The bridge cdylib entry points
(forward_*, poll_cmd_vel) are gated behind the cdylib feature so
the rlib path compiles on any machine without Isaac Sim installed.
Structs§
- Camera
Depth - Type-level marker for the per-pixel depth (metres, float32) camera channel.
- Camera
Depth Meta - C++-compatible metadata structs shared across the cxx::bridge boundary. Fields are named after physical quantities and need no further prose.
- Camera
Info - Type-level marker for the camera-info (calibration metadata) channel.
- Camera
Info Frame - One camera-info dispatch. Bundles the matrix and distortion slices
alongside the small
CameraInfoMetaso consumer callbacks don’t have to thread eight separate parameters. - Camera
Info Meta - C++-compatible metadata structs shared across the cxx::bridge boundary. Fields are named after physical quantities and need no further prose.
- Camera
Rgb - Type-level marker for the RGB camera sensor channel.
- Camera
RgbMeta - C++-compatible metadata structs shared across the cxx::bridge boundary. Fields are named after physical quantities and need no further prose.
- CmdVel
- C++-compatible metadata structs shared across the cxx::bridge boundary. Fields are named after physical quantities and need no further prose.
- CmdVel
Channel - Type-level marker for the cmd_vel articulation channel.
- Imu
- Type-level marker for the IMU sensor channel. One sample per
dispatch carries linear acceleration, angular velocity, and
orientation packed into
ImuMeta— no variable-sized payload. - ImuMeta
- C++-compatible metadata structs shared across the cxx::bridge boundary. Fields are named after physical quantities and need no further prose.
- Lidar
Flat Scan - Type-level marker for the 2D RTX LiDAR FlatScan sensor channel.
- Lidar
Flat Scan Meta - C++-compatible metadata structs shared across the cxx::bridge boundary. Fields are named after physical quantities and need no further prose.
- Lidar
Point Cloud - Type-level marker for the 3D RTX LiDAR PointCloud sensor channel.
- Lidar
Point Cloud Meta - C++-compatible metadata structs shared across the cxx::bridge boundary. Fields are named after physical quantities and need no further prose.
- Odometry
- Type-level marker for the chassis odometry channel. One sample per
dispatch carries position, orientation, and body-frame velocities
packed into
OdometryMeta— no variable-sized payload. - Odometry
Meta - C++-compatible metadata structs shared across the cxx::bridge boundary. Fields are named after physical quantities and need no further prose.
- Producer
Registry - Per-target_id registry of producer slots. Each cmd_vel-shaped sensor (or controller target) gets its own keyed slot so multiple targets can co-exist and the C++ poll path looks up by target_id.
- Producer
Slot - Lock-free single-slot store for a “latest-wins” producer.
- Source
Filter - Filter for the per-source routing key adapters use to demultiplex dispatches from multiple sensors of the same type.
Traits§
- Sensor
- Type-level identifier for a sensor domain.
Functions§
- camera_
depth_ consumer_ count - Number of currently registered depth camera consumers.
- camera_
info_ consumer_ count - Number of currently registered camera-info consumers.
- camera_
rgb_ consumer_ count - Number of currently registered RGB camera consumers.
- cmd_
vel_ consumer_ count - Number of registered cmd_vel observers (adapters watching the actuation stream).
- cmd_
vel_ producer_ count - Number of distinct articulation targets that have registered a producer slot.
- dispatch_
camera_ depth - Fan out a single depth camera frame to all registered consumers.
- dispatch_
camera_ info - Fan out a single camera-info frame to all registered consumers.
- dispatch_
camera_ rgb - Fan out a single RGB camera frame to all registered consumers.
- dispatch_
imu - Fan out a single IMU frame to all registered consumers.
- dispatch_
lidar_ flatscan - Fan out a single
LidarFlatScanframe to all registered consumers. Called byforward_lidar_flatscanafter logging; also callable directly from tests or synthetic sources that bypass the C++ bridge path. - dispatch_
lidar_ pointcloud - Fan out a single
LidarPointCloudframe to all registered consumers. - dispatch_
odometry - Fan out a single odometry frame to all registered consumers.
- imu_
consumer_ count - Number of currently registered IMU consumers.
- lidar_
flatscan_ consumer_ count - Number of currently registered
LidarFlatScanconsumers. - lidar_
pointcloud_ consumer_ count - Number of currently registered
LidarPointCloudconsumers. - odometry_
consumer_ count - Number of currently registered odometry consumers.
- peek_
cmd_ vel - Rust-friendly variant of
poll_cmd_velfor tests + adapter inspection. ReturnsSome(CmdVel)when a producer is registered and has published at least once;Noneotherwise. - register_
camera_ depth_ consumer - Register a callback to receive every depth camera frame the bridge dispatches. The closure runs on the bridge thread; keep it bounded.
- register_
camera_ info_ consumer - Register a callback to receive every camera-info frame the bridge dispatches. The closure runs on the bridge thread; keep it bounded.
- register_
camera_ rgb_ consumer - Register a callback to receive every RGB camera frame the bridge dispatches. The closure runs on the bridge thread; keep it bounded.
- register_
cmd_ vel_ consumer - Register a consumer that observes every Twist published into any
cmd_vel producer slot. The closure receives
(target_id, &CmdVel)— filter ontarget_idif you only care about one articulation. - register_
cmd_ vel_ producer - Register (or fetch) a cmd_vel producer for
target_id(typically the articulation prim path). Multiple writers can hold their own Arc to the slot — lastpublishwins. - register_
imu_ consumer - Register a callback to receive every IMU frame the bridge dispatches. The closure runs on the bridge thread; keep it bounded.
- register_
lidar_ flatscan_ consumer - Register a callback to receive every
LidarFlatScanframe the bridge dispatches. The closure runs on the bridge thread; keep it bounded. Registrations accumulate for the lifetime of the process — there is no unregister; drop the adapter runner to stop receiving frames. - register_
lidar_ pointcloud_ consumer - Register a callback to receive every
LidarPointCloudframe the bridge dispatches. The closure runs on the bridge thread; keep it bounded. - register_
odometry_ consumer - Register a callback to receive every chassis odometry frame the bridge dispatches. The closure runs on the bridge thread; keep it bounded.