1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
//! ROS2 bag reading and writing (sqlite3 and MCAP formats).
//!
//! This module provides comprehensive functionality to read and write ROS2 bag files,
//! supporting both SQLite3 and MCAP storage formats with guaranteed compatibility
//! with the Python rosbags library.
//!
//! ## Features
//!
//! - Read ROS2 bag files in SQLite3 and MCAP formats
//! - Write ROS2 bag files with SQLite3 storage
//! - Parse `metadata.yaml` files with full validation
//! - Filter messages by topic and time range
//! - Compression support (zstd)
//! - 94+ ROS2 message types with CDR deserialization
//! - Cross-compatible with Python rosbags library
//!
//! ## Quick Start
//!
//! ### Reading a bag
//! ```no_run
//! use apex_io::rosbag::Reader;
//! use std::path::Path;
//!
//! # fn main() -> Result<(), Box<dyn std::error::Error>> {
//! let mut reader = Reader::new(Path::new("path/to/bag"))?;
//! reader.open()?;
//!
//! println!("Bag duration: {:.2}s", reader.duration() as f64 / 1e9);
//! println!("Topics: {}", reader.topics().len());
//!
//! for message_result in reader.messages()? {
//! let message = message_result?;
//! println!("Topic: {}, Time: {}", message.connection.topic, message.timestamp);
//! }
//! # Ok(())
//! # }
//! ```
//!
//! ### Writing a bag
//! ```no_run
//! use apex_io::rosbag::{Writer, StoragePlugin};
//! use std::path::Path;
//!
//! # fn main() -> Result<(), Box<dyn std::error::Error>> {
//! let mut writer = Writer::new("output_bag", None, Some(StoragePlugin::Sqlite3))?;
//! writer.open()?;
//!
//! let connection = writer.add_connection(
//! "/my_topic".to_string(),
//! "std_msgs/msg/String".to_string(),
//! None, None, None, None
//! )?;
//!
//! writer.write(&connection, 1_000_000_000u64, b"hello")?;
//! writer.close()?;
//! # Ok(())
//! # }
//! ```
//!
//! ### Fast metadata reading
//! ```no_run
//! use apex_io::rosbag::read_bag_metadata_fast;
//! use std::path::Path;
//!
//! # fn main() -> Result<(), Box<dyn std::error::Error>> {
//! let metadata = read_bag_metadata_fast(Path::new("path/to/bag"))?;
//! println!("Duration: {:.2}s", metadata.duration() as f64 / 1e9);
//! println!("Message count: {}", metadata.message_count());
//! # Ok(())
//! # }
//! ```
/// CDR (Common Data Representation) deserialization.
/// Error types for bag I/O operations.
/// ROS2 message type definitions with CDR deserialization support.
/// Metadata parsing and validation (`metadata.yaml`).
/// Main reader interface.
/// Main writer interface.
/// Storage backend implementations (SQLite3 and MCAP).
/// Core data types and structures.
// Re-export main types for convenience
pub use ;
pub use ;
pub use Reader;
pub use ;
pub use Writer;
/// Read bag metadata from `metadata.yaml` without opening storage files.
///
/// This is ideal for quickly inspecting a bag's duration, message count,
/// and topic list without the overhead of opening storage.
///
/// # Example
/// ```no_run
/// use apex_io::rosbag::read_bag_metadata_fast;
/// use std::path::Path;
///
/// # fn main() -> Result<(), Box<dyn std::error::Error>> {
/// let metadata = read_bag_metadata_fast(Path::new("path/to/bag"))?;
///
/// println!("Duration: {:.2}s", metadata.duration() as f64 / 1e9);
/// println!("Message count: {}", metadata.message_count());
///
/// for topic in &metadata.info().topics_with_message_count {
/// println!("Topic: {} ({}), Count: {}",
/// topic.topic_metadata.name,
/// topic.topic_metadata.message_type,
/// topic.message_count
/// );
/// }
/// # Ok(())
/// # }
/// ```