Skip to main content

ros2_types/
cdr.rs

1//! CDR (Common Data Representation) serialization support
2//!
3//! This module provides CDR serialization and deserialization for ROS2 messages,
4//! following the RTPS specification v2.5 and DDS X-Types 1.3.
5//!
6//! # CDR Encapsulation Header
7//!
8//! All CDR-encoded data is prefixed with a 4-byte encapsulation header:
9//! - Bytes 0-1: Representation Identifier (encoding format + endianness)
10//! - Bytes 2-3: Options (typically reserved, set to 0x0000)
11//!
12//! # Supported Encodings
13//!
14//! This implementation uses the `cdr_encoding` crate which only supports **plain CDR v1**:
15//! - `CdrLE` (0x0001) - CDR Little Endian ✓
16//! - `CdrBE` (0x0000) - CDR Big Endian ✓
17//!
18//! The following encodings are **NOT supported** and will return an error:
19//! - Parameter List CDR (PL_CDR_BE, PL_CDR_LE)
20//! - XCDR v2 encodings (XCDR2_BE, XCDR2_LE, D_CDR2_*, PL_XCDR2_*)
21//!
22//! # References
23//!
24//! - RTPS v2.5 Section 10.5, Table 10.3 - Representation Identifier values
25//! - DDS X-Types 1.3 Section 7.6.2.1.2 - XCDR encoding identifiers
26
27use crate::error::{Error, Result};
28
29/// CDR Representation Identifier (2 bytes)
30///
31/// Per RTPS v2.5 Section 10.5, Table 10.3 and DDS X-Types 1.3 Section 7.6.2.1.2
32///
33/// The representation identifier specifies the encoding format and byte order
34/// used for the serialized data payload.
35///
36/// # Supported Encodings
37///
38/// Only plain CDR v1 is supported by this implementation:
39/// - [`CdrLE`](Self::CdrLE) - CDR Little Endian (recommended, default)
40/// - [`CdrBE`](Self::CdrBE) - CDR Big Endian
41///
42/// All other encodings (Parameter List, XCDR v2) will fail during serialization/deserialization.
43#[repr(u16)]
44#[derive(Debug, Clone, Copy, PartialEq, Eq)]
45pub enum RepresentationIdentifier {
46    /// CDR Big Endian (v1) - `[0x00, 0x00]` ✓ Supported
47    CdrBE = 0x0000,
48    /// CDR Little Endian (v1) - `[0x00, 0x01]` ✓ Supported
49    CdrLE = 0x0001,
50    /// Parameter List CDR Big Endian - `[0x00, 0x02]` ✗ Not supported
51    PlCdrBE = 0x0002,
52    /// Parameter List CDR Little Endian - `[0x00, 0x03]` ✗ Not supported
53    PlCdrLE = 0x0003,
54    /// XCDR v2 Big Endian (X-Types 1.3) - `[0x00, 0x06]` ✗ Not supported
55    Xcdr2BE = 0x0006,
56    /// XCDR v2 Little Endian (X-Types 1.3) - `[0x00, 0x07]` ✗ Not supported
57    Xcdr2LE = 0x0007,
58    /// Delimited CDR v2 Big Endian - `[0x00, 0x08]` ✗ Not supported
59    DCdr2BE = 0x0008,
60    /// Delimited CDR v2 Little Endian - `[0x00, 0x09]` ✗ Not supported
61    DCdr2LE = 0x0009,
62    /// Parameter List XCDR v2 Big Endian - `[0x00, 0x0a]` ✗ Not supported
63    PlXcdr2BE = 0x000a,
64    /// Parameter List XCDR v2 Little Endian - `[0x00, 0x0b]` ✗ Not supported
65    PlXcdr2LE = 0x000b,
66}
67
68impl RepresentationIdentifier {
69    /// Returns true if this representation uses little-endian byte order
70    pub const fn is_little_endian(&self) -> bool {
71        matches!(
72            self,
73            Self::CdrLE | Self::PlCdrLE | Self::Xcdr2LE | Self::DCdr2LE | Self::PlXcdr2LE
74        )
75    }
76
77    /// Returns true if this representation uses big-endian byte order
78    pub const fn is_big_endian(&self) -> bool {
79        !self.is_little_endian()
80    }
81
82    /// Returns true if this is a plain CDR v1 encoding (CdrBE or CdrLE)
83    ///
84    /// Only plain CDR v1 encodings are supported by this implementation.
85    pub const fn is_plain_cdr(&self) -> bool {
86        matches!(self, Self::CdrBE | Self::CdrLE)
87    }
88
89    /// Returns true if this encoding is supported by the current implementation
90    ///
91    /// Currently only plain CDR v1 (CdrBE, CdrLE) is supported.
92    /// Parameter List and XCDR v2 encodings are not supported.
93    pub const fn is_supported(&self) -> bool {
94        self.is_plain_cdr()
95    }
96
97    /// Returns true if this is a CDR v1 encoding (including Parameter List CDR)
98    pub const fn is_cdr_v1(&self) -> bool {
99        matches!(
100            self,
101            Self::CdrBE | Self::CdrLE | Self::PlCdrBE | Self::PlCdrLE
102        )
103    }
104
105    /// Returns true if this is a CDR v2 / XCDR2 encoding
106    pub const fn is_cdr_v2(&self) -> bool {
107        matches!(
108            self,
109            Self::Xcdr2BE
110                | Self::Xcdr2LE
111                | Self::DCdr2BE
112                | Self::DCdr2LE
113                | Self::PlXcdr2BE
114                | Self::PlXcdr2LE
115        )
116    }
117
118    /// Returns true if this is a Parameter List encoding
119    pub const fn is_parameter_list(&self) -> bool {
120        matches!(
121            self,
122            Self::PlCdrBE | Self::PlCdrLE | Self::PlXcdr2BE | Self::PlXcdr2LE
123        )
124    }
125
126    /// Convert to raw bytes (big-endian as per spec)
127    pub const fn to_bytes(&self) -> [u8; 2] {
128        let val = *self as u16;
129        [(val >> 8) as u8, val as u8]
130    }
131
132    /// Parse from raw bytes
133    pub fn from_bytes(bytes: [u8; 2]) -> Result<Self> {
134        let val = ((bytes[0] as u16) << 8) | (bytes[1] as u16);
135        match val {
136            0x0000 => Ok(Self::CdrBE),
137            0x0001 => Ok(Self::CdrLE),
138            0x0002 => Ok(Self::PlCdrBE),
139            0x0003 => Ok(Self::PlCdrLE),
140            0x0006 => Ok(Self::Xcdr2BE),
141            0x0007 => Ok(Self::Xcdr2LE),
142            0x0008 => Ok(Self::DCdr2BE),
143            0x0009 => Ok(Self::DCdr2LE),
144            0x000a => Ok(Self::PlXcdr2BE),
145            0x000b => Ok(Self::PlXcdr2LE),
146            _ => Err(Error::CdrError(format!(
147                "Unknown representation identifier: 0x{:04x}",
148                val
149            ))),
150        }
151    }
152}
153
154impl Default for RepresentationIdentifier {
155    /// Default to CDR Little Endian (most common for x86/ARM)
156    fn default() -> Self {
157        Self::CdrLE
158    }
159}
160
161/// CDR Encapsulation Header (4 bytes)
162///
163/// Per RTPS v2.5 and DDS X-Types 1.3, all CDR-encoded data is prefixed
164/// with a 4-byte encapsulation header:
165///
166/// ```text
167/// +--------+--------+--------+--------+
168/// | Rep ID (2 bytes)| Options (2 bytes)|
169/// +--------+--------+--------+--------+
170/// ```
171///
172/// # Example
173///
174/// ```
175/// use ros2_types::cdr::{CdrEncapsulationHeader, RepresentationIdentifier};
176///
177/// // Default header (CDR Little Endian)
178/// let header = CdrEncapsulationHeader::default();
179/// assert_eq!(header.to_bytes(), [0x00, 0x01, 0x00, 0x00]);
180///
181/// // Parse header from bytes
182/// let header = CdrEncapsulationHeader::from_bytes(&[0x00, 0x01, 0x00, 0x00]).unwrap();
183/// assert!(header.representation_id.is_little_endian());
184/// ```
185#[derive(Debug, Clone, Copy, PartialEq, Eq)]
186pub struct CdrEncapsulationHeader {
187    /// Representation identifier (encoding format + endianness)
188    pub representation_id: RepresentationIdentifier,
189    /// Options field (typically 0x0000, reserved for future use)
190    pub options: u16,
191}
192
193impl CdrEncapsulationHeader {
194    /// Size of the encapsulation header in bytes
195    pub const SIZE: usize = 4;
196
197    /// Create a new encapsulation header
198    pub const fn new(representation_id: RepresentationIdentifier) -> Self {
199        Self {
200            representation_id,
201            options: 0,
202        }
203    }
204
205    /// Create a header with custom options
206    pub const fn with_options(representation_id: RepresentationIdentifier, options: u16) -> Self {
207        Self {
208            representation_id,
209            options,
210        }
211    }
212
213    /// Serialize to 4 bytes
214    pub const fn to_bytes(&self) -> [u8; 4] {
215        let rep_bytes = self.representation_id.to_bytes();
216        [
217            rep_bytes[0],
218            rep_bytes[1],
219            (self.options >> 8) as u8,
220            self.options as u8,
221        ]
222    }
223
224    /// Parse from bytes
225    ///
226    /// # Errors
227    ///
228    /// Returns `Error::CdrError` if:
229    /// - The slice is shorter than 4 bytes
230    /// - The representation identifier is unknown
231    pub fn from_bytes(bytes: &[u8]) -> Result<Self> {
232        if bytes.len() < Self::SIZE {
233            return Err(Error::CdrError(format!(
234                "CDR encapsulation header requires {} bytes, got {}",
235                Self::SIZE,
236                bytes.len()
237            )));
238        }
239
240        let representation_id = RepresentationIdentifier::from_bytes([bytes[0], bytes[1]])?;
241        let options = ((bytes[2] as u16) << 8) | (bytes[3] as u16);
242
243        Ok(Self {
244            representation_id,
245            options,
246        })
247    }
248}
249
250impl Default for CdrEncapsulationHeader {
251    /// Default to CDR Little Endian with no options
252    fn default() -> Self {
253        Self::new(RepresentationIdentifier::CdrLE)
254    }
255}
256
257/// Trait for CDR serialization/deserialization
258///
259/// This trait provides methods to serialize and deserialize types using
260/// CDR (Common Data Representation) encoding with proper encapsulation headers.
261///
262/// # Implementation
263///
264/// This trait is automatically implemented for any type that implements
265/// `serde::Serialize` and `serde::de::DeserializeOwned`.
266///
267/// # Wire Format
268///
269/// Serialized data includes a 4-byte CDR encapsulation header followed
270/// by the CDR-encoded payload:
271///
272/// ```text
273/// +------------------+----------------------+
274/// | Header (4 bytes) | Payload (N bytes)    |
275/// +------------------+----------------------+
276/// ```
277pub trait CdrSerde: Sized {
278    /// Serialize to CDR-encoded bytes with encapsulation header
279    ///
280    /// The output includes a 4-byte CDR encapsulation header (default: CDR LE)
281    /// followed by the serialized payload.
282    fn serialize(&self) -> Result<Vec<u8>>;
283
284    /// Serialize with a specific encapsulation header
285    fn serialize_with_header(&self, header: CdrEncapsulationHeader) -> Result<Vec<u8>>;
286
287    /// Deserialize from CDR-encoded bytes
288    ///
289    /// Parses the encapsulation header to determine the encoding format
290    /// and deserializes the payload accordingly.
291    ///
292    /// # Errors
293    ///
294    /// Returns `Error::CdrError` if:
295    /// - The input is shorter than 4 bytes
296    /// - The encapsulation header is invalid or unsupported
297    /// - Deserialization fails
298    fn deserialize(bytes: &[u8]) -> Result<Self>;
299}
300
301impl<T: serde::Serialize + serde::de::DeserializeOwned> CdrSerde for T {
302    fn serialize(&self) -> Result<Vec<u8>> {
303        self.serialize_with_header(CdrEncapsulationHeader::default())
304    }
305
306    fn serialize_with_header(&self, header: CdrEncapsulationHeader) -> Result<Vec<u8>> {
307        // Only plain CDR v1 is supported
308        if !header.representation_id.is_supported() {
309            return Err(Error::CdrError(format!(
310                "Unsupported CDR encoding for serialization: {:?}. Only CdrLE and CdrBE are supported.",
311                header.representation_id
312            )));
313        }
314
315        let mut result = header.to_bytes().to_vec();
316
317        let buffer = if header.representation_id.is_little_endian() {
318            cdr_encoding::to_vec::<T, byteorder::LittleEndian>(self)
319                .map_err(|e| Error::CdrError(e.to_string()))?
320        } else {
321            cdr_encoding::to_vec::<T, byteorder::BigEndian>(self)
322                .map_err(|e| Error::CdrError(e.to_string()))?
323        };
324
325        result.extend(buffer);
326        Ok(result)
327    }
328
329    fn deserialize(bytes: &[u8]) -> Result<Self> {
330        let header = CdrEncapsulationHeader::from_bytes(bytes)?;
331
332        // Only plain CDR v1 is supported
333        if !header.representation_id.is_supported() {
334            return Err(Error::CdrError(format!(
335                "Unsupported CDR encoding for deserialization: {:?}. Only CdrLE and CdrBE are supported.",
336                header.representation_id
337            )));
338        }
339
340        let payload = &bytes[CdrEncapsulationHeader::SIZE..];
341
342        if header.representation_id.is_little_endian() {
343            let (value, _) = cdr_encoding::from_bytes::<T, byteorder::LittleEndian>(payload)
344                .map_err(|e| Error::CdrError(e.to_string()))?;
345            Ok(value)
346        } else {
347            let (value, _) = cdr_encoding::from_bytes::<T, byteorder::BigEndian>(payload)
348                .map_err(|e| Error::CdrError(e.to_string()))?;
349            Ok(value)
350        }
351    }
352}
353
354#[cfg(test)]
355mod tests {
356    use super::*;
357
358    #[test]
359    fn test_representation_identifier_bytes() {
360        assert_eq!(RepresentationIdentifier::CdrBE.to_bytes(), [0x00, 0x00]);
361        assert_eq!(RepresentationIdentifier::CdrLE.to_bytes(), [0x00, 0x01]);
362        assert_eq!(RepresentationIdentifier::PlCdrBE.to_bytes(), [0x00, 0x02]);
363        assert_eq!(RepresentationIdentifier::PlCdrLE.to_bytes(), [0x00, 0x03]);
364        assert_eq!(RepresentationIdentifier::Xcdr2BE.to_bytes(), [0x00, 0x06]);
365        assert_eq!(RepresentationIdentifier::Xcdr2LE.to_bytes(), [0x00, 0x07]);
366    }
367
368    #[test]
369    fn test_representation_identifier_roundtrip() {
370        let identifiers = [
371            RepresentationIdentifier::CdrBE,
372            RepresentationIdentifier::CdrLE,
373            RepresentationIdentifier::PlCdrBE,
374            RepresentationIdentifier::PlCdrLE,
375            RepresentationIdentifier::Xcdr2BE,
376            RepresentationIdentifier::Xcdr2LE,
377            RepresentationIdentifier::DCdr2BE,
378            RepresentationIdentifier::DCdr2LE,
379            RepresentationIdentifier::PlXcdr2BE,
380            RepresentationIdentifier::PlXcdr2LE,
381        ];
382
383        for id in identifiers {
384            let bytes = id.to_bytes();
385            let parsed = RepresentationIdentifier::from_bytes(bytes).unwrap();
386            assert_eq!(id, parsed);
387        }
388    }
389
390    #[test]
391    fn test_header_default() {
392        let header = CdrEncapsulationHeader::default();
393        assert_eq!(header.representation_id, RepresentationIdentifier::CdrLE);
394        assert_eq!(header.options, 0);
395        assert_eq!(header.to_bytes(), [0x00, 0x01, 0x00, 0x00]);
396    }
397
398    #[test]
399    fn test_header_roundtrip() {
400        let header = CdrEncapsulationHeader::new(RepresentationIdentifier::Xcdr2LE);
401        let bytes = header.to_bytes();
402        let parsed = CdrEncapsulationHeader::from_bytes(&bytes).unwrap();
403        assert_eq!(header, parsed);
404    }
405
406    #[test]
407    fn test_header_with_options() {
408        let header = CdrEncapsulationHeader::with_options(RepresentationIdentifier::CdrLE, 0x1234);
409        assert_eq!(header.to_bytes(), [0x00, 0x01, 0x12, 0x34]);
410    }
411
412    #[test]
413    fn test_endianness_detection() {
414        assert!(RepresentationIdentifier::CdrLE.is_little_endian());
415        assert!(RepresentationIdentifier::CdrBE.is_big_endian());
416        assert!(RepresentationIdentifier::Xcdr2LE.is_little_endian());
417        assert!(RepresentationIdentifier::Xcdr2BE.is_big_endian());
418    }
419
420    #[test]
421    fn test_cdr_version_detection() {
422        assert!(RepresentationIdentifier::CdrLE.is_cdr_v1());
423        assert!(RepresentationIdentifier::CdrBE.is_cdr_v1());
424        assert!(RepresentationIdentifier::Xcdr2LE.is_cdr_v2());
425        assert!(RepresentationIdentifier::Xcdr2BE.is_cdr_v2());
426    }
427
428    #[test]
429    fn test_supported_encodings() {
430        // Only plain CDR v1 is supported
431        assert!(RepresentationIdentifier::CdrLE.is_supported());
432        assert!(RepresentationIdentifier::CdrBE.is_supported());
433
434        // All others are not supported
435        assert!(!RepresentationIdentifier::PlCdrBE.is_supported());
436        assert!(!RepresentationIdentifier::PlCdrLE.is_supported());
437        assert!(!RepresentationIdentifier::Xcdr2BE.is_supported());
438        assert!(!RepresentationIdentifier::Xcdr2LE.is_supported());
439        assert!(!RepresentationIdentifier::DCdr2BE.is_supported());
440        assert!(!RepresentationIdentifier::DCdr2LE.is_supported());
441        assert!(!RepresentationIdentifier::PlXcdr2BE.is_supported());
442        assert!(!RepresentationIdentifier::PlXcdr2LE.is_supported());
443    }
444
445    #[test]
446    fn test_unsupported_encoding_error() {
447        // Try to deserialize with an unsupported encoding (PL_CDR_LE)
448        let bytes = [0x00, 0x03, 0x00, 0x00, 0x01, 0x02, 0x03, 0x04];
449        let result = CdrEncapsulationHeader::from_bytes(&bytes);
450        assert!(result.is_ok());
451        let header = result.unwrap();
452        assert_eq!(header.representation_id, RepresentationIdentifier::PlCdrLE);
453        assert!(!header.representation_id.is_supported());
454    }
455
456    #[test]
457    fn test_invalid_representation_identifier() {
458        let result = RepresentationIdentifier::from_bytes([0xFF, 0xFF]);
459        assert!(result.is_err());
460    }
461
462    #[test]
463    fn test_header_too_short() {
464        let result = CdrEncapsulationHeader::from_bytes(&[0x00, 0x01]);
465        assert!(result.is_err());
466    }
467}