apex-io
High-performance file I/O for robotics data — pose graphs (G2O, TORO, BAL) and ROS2 bag files (SQLite3 and MCAP), with optional live DDS topic subscription.
Origin
The ROS2 bag reading and writing functionality in this crate was originally developed as a
standalone Rust library at rosbags-rs and has
since been merged into apex-io. Bags produced and read by this crate are interoperable with
the ros2 bag CLI.
Overview
- Pose graph I/O — G2O and TORO (2D/3D SLAM), BAL (bundle adjustment)
- ROS2 bag reading — SQLite3 and MCAP formats, topic + time-range filtering, raw and deserialized APIs
- ROS2 bag writing — SQLite3 and MCAP with optional zstd compression
- Live DDS subscription — async topic listener for running ROS2 systems (optional
ddsfeature) - 94+ ROS2 message types — CDR deserialization for
geometry_msgs,sensor_msgs,nav_msgs,std_msgs,tf2_msgs, and more - Memory-mapped + parallel parsing — fast I/O on large files via
memmap2andrayon - CLI binaries —
bag_info,bag_filter,extract_topic_data,write_dummy_bag,dds_multi_listener
Supported Formats
| Format | Description | Read | Write |
|---|---|---|---|
| G2O | General Graph Optimization (SE2 + SE3) | ✓ | ✓ |
| TORO | Tree-based netwORk Optimizer (SE2 only) | ✓ | ✓ |
| BAL | Bundle Adjustment in the Large | ✓ | — |
| ROS2 bag / SQLite3 | .db3 storage format |
✓ | ✓ |
| ROS2 bag / MCAP | .mcap storage format |
✓ | ✓ |
Installation
# Core: pose graphs + ROS2 bag reader/writer
[]
= "0.2.0"
# With Rerun visualization helpers
= { = "0.2.0", = ["visualization"] }
# With live DDS topic subscription (requires a DDS runtime)
= { = "0.2.0", = ["dds"] }
Note:
apex-iodepends onapex-manifolds(for SE2/SE3 types). Both crates must be available on crates.io. If you are using the workspace they are handled automatically.
ROS2 Bag Reading
Basic — iterate all messages
use Reader;
let mut reader = new?;
reader.open?;
// Bag-level metadata
println!;
println!;
println!;
println!;
// List topics
for topic in reader.topics
// Iterate every message
for msg in reader.messages?
reader.close?;
Filter by topic
use Reader;
let mut reader = new?;
reader.open?;
// Select connections whose topic matches the filter
let conns = reader.connections;
let imu_conns: = conns.iter
.filter
.cloned
.collect;
for msg in reader.messages_filtered?
Filter by time range
use Reader;
let mut reader = new?;
reader.open?;
// Times are in nanoseconds since epoch
let start_ns: u64 = 1_700_000_000_000_000_000;
let end_ns: u64 = 1_700_000_005_000_000_000; // 5 seconds later
for msg in reader.messages_filtered?
Combined: topic + time filter
use Reader;
let mut reader = new?;
reader.open?;
let conns = reader.connections;
let cam_conns: = conns.iter
.filter
.cloned
.collect;
let start_ns = reader.start_time;
let end_ns = start_ns + 10_000_000_000; // first 10 seconds
for msg in reader.messages_filtered?
High-performance raw mode (no deserialization)
use Reader;
let mut reader = new?;
reader.open?;
// raw_messages_filtered skips CDR deserialization — useful for copying or forwarding
for raw in reader.raw_messages_filtered?
// Or batch-collect everything at once (single allocation, no iterator overhead)
let batch = reader.read_raw_messages_batch?;
println!;
Fast metadata-only reading
use read_bag_metadata_fast;
// Reads only metadata.yaml — never opens the .db3 or .mcap file
let meta = read_bag_metadata_fast?;
println!;
println!;
println!;
for topic in &meta.info.topics_with_message_count
ROS2 Bag Writing
Write a minimal bag
use ;
let mut writer = new?;
writer.open?;
// Register a topic before writing to it
let conn = writer.add_connection?;
// Write raw CDR-serialized bytes with a nanosecond timestamp
let timestamp_ns: u64 = 1_700_000_000_000_000_000;
writer.write?;
writer.close?;
Write to MCAP format with zstd compression
use ;
let mut writer = new?;
writer.open?;
// Enable file-level zstd compression
writer.set_compression?;
let conn = writer.add_connection?;
for in payloads.iter.enumerate
writer.close?;
Write multiple topics
use ;
let mut writer = new?;
writer.open?;
let imu_conn = writer.add_connection?;
let odom_conn = writer.add_connection?;
// Interleave messages from different topics
writer.write?;
writer.write?;
writer.write?;
writer.close?;
Live DDS Subscription
Enable the dds feature and have a running ROS2 node on the same DDS domain.
= { = "0.2.0", = ["dds"] }
Subscribe to a single topic
use ;
use ;
let config = DdsSubscriberConfig ;
let subscriber = new?;
// `listen` spawns a background thread and returns a channel receiver
let rx = subscriber.listen?;
// Process messages as they arrive
for raw_msg in rx
Subscribe to multiple topics
Use a thread per topic and collect via a shared channel, or use the dds_multi_listener binary:
use ;
use mpsc;
use thread;
let topics = vec!;
let = channel;
for in topics
// Unified receive loop across all topics
for msg in rx
Topic name conversion
ROS2 topic names are automatically converted to DDS topic names:
use DdsSubscriber;
// "/imu/data" → "rt/imu/data"
let dds_topic = ros2_to_dds_topic;
Pose Graph Formats
G2O Format
The G2O (General Graph Optimization) format supports both 2D (SE2) and 3D (SE3) pose graphs.
File structure:
VERTEX_SE2 id x y theta
VERTEX_SE3:QUAT id x y z qx qy qz qw
EDGE_SE2 from to dx dy dtheta info_xx info_xy info_yy info_xt info_yt info_tt
EDGE_SE3:QUAT from to dx dy dz dqx dqy dqz dqw [21 info matrix values]
use ;
// Load
let graph = load?;
println!;
// Iterate SE3 vertices
for in &graph.vertices_se3
// Iterate SE3 edges
for edge in &graph.edges_se3
// Write back
write?;
TORO Format
TORO supports SE2 (2D) graphs only. Writing SE3 data returns an error.
File structure:
VERTEX2 id x y theta
EDGE2 from to dx dy dtheta info_xx info_xy info_yy info_xt info_yt info_tt
use ;
let graph = load?;
for in &graph.vertices_se2
write?;
Auto-detect format
use load_graph;
let graph = load_graph?; // .g2o → G2oLoader
let graph = load_graph?; // .graph → ToroLoader
BAL Format (Bundle Adjustment)
File structure:
num_cameras num_points num_observations
camera_idx point_idx pixel_x pixel_y # one observation per line
...
# then 9 camera parameters per camera (rotation x/y/z, translation x/y/z, focal, k1, k2)
# then 3 point coordinates per point (x, y, z)
use BalLoader;
let dataset = load?;
println!;
for in dataset.cameras.iter.enumerate
for obs in &dataset.observations
CLI Binaries
All binaries ship with the crate. Run them via:
bag_info — inspect bag metadata (fast, no storage file opened)
Reads only metadata.yaml. Output: version, storage format, compression, file sizes, duration,
start/end timestamps, message count, and per-topic breakdown.
bag_filter — copy and filter a bag
# Filter by topic
# Filter by time range (nanoseconds since epoch)
# Convert SQLite3 → MCAP
# All options combined with compression
extract_topic_data — export to CSV or PNG
# Extract any topic to CSV (one row per message)
# Extract image topic to PNG files (one file per frame)
write_dummy_bag — create a demo bag
# Write to ./demo_bag with 29+ message types
# Custom output path
download_datasets — download public SLAM datasets
Downloads G2O, TORO, and BAL benchmark datasets configured in datasets.toml.
dds_multi_listener — live multi-topic DDS listener (dds feature required)
Connects to a running ROS2 system and prints incoming messages. Requires a compatible DDS runtime (CycloneDDS, FastDDS) and active ROS2 nodes on the same domain.
Data Structures
Graph
ROS2 bag core types
QoS Profile
Performance
| Technique | Applied to |
|---|---|
Memory-mapped file I/O (memmap2) |
All loaders — avoids loading full file into heap |
Parallel parsing (rayon) |
Files > 1 000 lines — multi-core acceleration |
| Raw message API | Bag reading without CDR deserialization overhead |
| Batch read | read_raw_messages_batch — single allocation, no iterator overhead |
| Metadata-only path | read_bag_metadata_fast — zero storage file I/O |
| Pre-allocated collections | Estimated capacity from file size to minimize reallocs |
Error Handling
Pose graph — IoError
| Variant | Description |
|---|---|
Io(io::Error) |
Underlying I/O error |
Parse { line, message } |
Parse error with line number |
UnsupportedVertexType(String) |
Unknown vertex type in file |
UnsupportedEdgeType(String) |
Unknown edge type in file |
InvalidNumber { line, value } |
Failed to parse a number |
MissingFields { line } |
Insufficient fields on a line |
DuplicateVertex { id } |
Vertex ID collision |
InvalidQuaternion { line, norm } |
Non-unit quaternion |
UnsupportedFormat(String) |
Unrecognized file extension |
FileCreationFailed { path, reason } |
Output file creation failed |
ROS2 bag — BagError
BagError covers metadata parsing, storage backend (SQLite3/MCAP), CDR deserialization,
compression, and connection mismatch failures. All variants include enough context (file path,
topic, byte offset) for actionable diagnostics.
Visualization Feature
= { = "0.2.0", = ["visualization"] }
// SE2 vertex → Rerun types
let pos_2d: = vertex_se2.to_rerun_position_2d;
let pos_3d: Vec3 = vertex_se2.to_rerun_position_3d;
// SE3 vertex → Rerun types
let : = vertex_se3.to_rerun_transform;
Dependencies
| Crate | Purpose |
|---|---|
apex-manifolds |
Lie group types (SE2, SE3) |
nalgebra |
Linear algebra (vectors, matrices) |
memmap2 |
Memory-mapped file I/O |
rayon |
Parallel parsing |
thiserror |
Error type derivation |
tracing |
Structured logging |
serde, serde_json |
Serialization |
serde_yaml |
YAML metadata parsing (ROS2 bags) |
chrono |
Timestamps in file headers |
byteorder |
CDR byte-order handling |
bytes |
Efficient byte buffers |
hex |
Hex encoding for diagnostics |
image |
PNG export for image topics |
rusqlite |
SQLite3 storage backend |
zstd |
Compression support |
mcap |
MCAP storage backend |
clap |
CLI argument parsing |
ureq |
Dataset download |
rerun |
Visualization (optional — visualization feature) |
rustdds, tokio, futures |
Live DDS subscription (optional — dds feature) |
References
- rosbags-rs — original standalone ROS2 bag library (now merged here)
- g2o: General Framework for Graph Optimization
- TORO: Tree-based netwORk Optimizer
- Bundle Adjustment in the Large
- Bundler: Structure from Motion
- ROS2 bag file format
- MCAP format
License
Apache-2.0