robotics_signals/sensors/
camera_info.rs

1use crate::standard::Header;
2use cdds_derive::*;
3use cyclonedds_rs::*;
4use serde_derive::{Deserialize, Serialize};
5
6#[repr(C)]
7#[derive(Serialize, Deserialize)]
8pub enum DistortionModel {
9    PlumbBob,
10    RationalPolynomial,
11    Equidistant,
12}
13
14// This message is used to specify a region of interest within an image.
15// When used to specify the ROI setting of the camera when the image was
16// taken, the height and width fields should either match the height and
17// width fields for the associated image; or height = width = 0
18// indicates that the full resolution image was captured.
19#[repr(C)]
20#[derive(Serialize, Deserialize)]
21pub struct RegionOfInterest {
22    /// Leftmost pixel of the ROI
23    /// (0 if the ROI includes the left edge of the image)
24    pub x_offset: u32,
25
26    /// Topmost pixel of the ROI
27    /// (0 if the ROI includes the top edge of the image)
28    pub y_offset: u32,
29    pub height: u32,
30    pub width: u32,
31
32    /// True if a distinct rectified ROI should be calculated from the "raw"
33    /// ROI in this message. Typically this should be False if the full image
34    /// is captured (ROI not used), and True if a subwindow is captured (ROI
35    /// used).
36    pub do_rectify: bool,
37}
38
39/// # Header timestamp should be acquisition time of image
40/// Header frame_id should be optical frame of camera
41/// origin of frame should be optical center of camera
42/// +x should point to the right in the image
43/// +y should point down in the image
44/// +z should point into the plane of the image
45#[repr(C)]
46#[derive(Serialize, Deserialize, Topic)]
47pub struct CameraInfo {
48    ///
49    pub header: Header,
50
51    // Calibration parameters of the camera
52    /// Calibrated width
53    pub height: u32,
54    /// Calibrated height
55    pub width: u32,
56
57    pub distortion_model: DistortionModel,
58
59    /// distortion parameters
60    pub d: Vec<f64>,
61
62    /// Intrinsic camera matrix for the raw images.
63    /// [ fx 0  cx ]
64    /// [ 0  fy cy ]
65    /// [ 0  0   1 ]
66    /// Projectd 3D points in the camera coordinate frame
67    /// to 2D pixel coordinates using the focal lengths (fx,fy)
68    /// and principal point (cx, cy)
69    pub k: [f64; 9],
70
71    /// Rectification matrix for stereo cameras
72    /// A rotation matrix aligning the camera coordinate
73    /// system to the ideal stereo image plane so that
74    /// epipolar lines in both stereo images are parallel
75    pub r: [f64; 9],
76
77    /// # Projection/camera matrix
78    //     [fx'  0  cx' Tx]
79    // P = [ 0  fy' cy' Ty]
80    //     [ 0   0   1   0]
81    // By convention, this matrix specifies the intrinsic (camera) matrix
82    //  of the processed (rectified) image. That is, the left 3x3 portion
83    //  is the normal camera intrinsic matrix for the rectified image.
84    // It projects 3D points in the camera coordinate frame to 2D pixel
85    //  coordinates using the focal lengths (fx', fy') and principal point
86    //  (cx', cy') - these may differ from the values in K.
87    // For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
88    //  also have R = the identity and P[1:3,1:3] = K.
89    // For a stereo pair, the fourth column [Tx Ty 0]' is related to the
90    //  position of the optical center of the second camera in the first
91    //  camera's frame. We assume Tz = 0 so both cameras are in the same
92    //  stereo image plane. The first camera always has Tx = Ty = 0. For
93    //  the right (second) camera of a horizontal stereo pair, Ty = 0 and
94    //  Tx = -fx' * B, where B is the baseline between the cameras.
95    // Given a 3D point [X Y Z]', the projection (x, y) of the point onto
96    //  the rectified image is given by:
97    //  [u v w]' = P * [X Y Z 1]'
98    //         x = u / w
99    //         y = v / w
100    //  This holds for both images of a stereo pair.
101    pub p: [f64; 12],
102
103    // Binning refers here to any camera setting which combines rectangular
104    //  neighborhoods of pixels into larger "super-pixels." It reduces the
105    //  resolution of the output image to
106    //  (width / binning_x) x (height / binning_y).
107    // The default values binning_x = binning_y = 0 is considered the same
108    //  as binning_x = binning_y = 1 (no subsampling).
109    pub binning_x: u32,
110    pub binning_y: u32,
111
112    /// Region of interest (subwindow of full camera resolution), given in
113    ///  full resolution (unbinned) image coordinates. A particular ROI
114    ///  always denotes the same window of pixels on the camera sensor,
115    ///  regardless of binning settings.
116    /// The default setting of roi (all values 0) is considered the same as
117    ///  full resolution (roi.width = width, roi.height = height).
118    pub roi: RegionOfInterest,
119}