CreOS SDK
The CreOS SDK allows you to interact with Avular robots
 
Loading...
Searching...
No Matches
camera_info.hpp
Go to the documentation of this file.
1
8namespace sensor_msgs::msg {
38public:
39 // This message defines meta information for a camera. It should be in a
40 // camera namespace on topic "camera_info" and accompanied by up to five
41 // image topics named:
42 //
43 // image_raw - raw data from the camera driver, possibly Bayer encoded
44 // image - monochrome, distorted
45 // image_color - color, distorted
46 // image_rect - monochrome, rectified
47 // image_rect_color - color, rectified
48 //
49 // The image_pipeline contains packages (image_proc, stereo_image_proc)
50 // for producing the four processed image topics from image_raw and
51 // camera_info. The meaning of the camera parameters are described in
52 // detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
53 //
54 // The image_geometry package provides a user-friendly interface to
55 // common operations using this meta information. If you want to, e.g.,
56 // project a 3d point into image coordinates, we strongly recommend
57 // using image_geometry.
58 //
59 // If the camera is uncalibrated, the matrices D, K, R, P should be left
60 // zeroed out. In particular, clients may assume that K[0] == 0.0
61 // indicates an uncalibrated camera.
62
63 //
64 // Image acquisition info
65 //
66
67 // Time of image acquisition, camera coordinate frame ID
69 // Header frame_id should be optical frame of camera
70 // origin of frame should be optical center of camera
71 // +x should point to the right in the image
72 // +y should point down in the image
73 // +z should point into the plane of the image
74
75
76 //
77 // Calibration Parameters
78 //
79 // These are fixed during camera calibration. Their values will be the
80 // same in all messages until the camera is recalibrated. Note that
81 // self-calibrating systems may "recalibrate" frequently.
82 //
83 // The internal parameters can be used to warp a raw (distorted) image
84 // to:
85 // 1. An undistorted image (requires D and K)
86 // 2. A rectified image (requires D, K, R)
87 // The projection matrix P projects 3D points into the rectified image.
88 //
89
90 // The image dimensions with which the camera was calibrated.
91 // Normally this will be the full camera resolution in pixels.
92 uint32_t height;
93 uint32_t width;
94
95 // The distortion model used. Supported models are listed in
96 // sensor_msgs/distortion_models.hpp. For most cameras, "plumb_bob" - a
97 // simple model of radial and tangential distortion - is sufficent.
98 std::string distortion_model;
99
100 // The distortion parameters, size depending on the distortion model.
101 // For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).
102 std::vector<double> d;
103
104 // Intrinsic camera matrix for the raw (distorted) images.
105 // [fx 0 cx]
106 // K = [ 0 fy cy]
107 // [ 0 0 1]
108 // Projects 3D points in the camera coordinate frame to 2D pixel
109 // coordinates using the focal lengths (fx, fy) and principal point
110 // (cx, cy).
111 std::array<double, 9> k;
112
113 // Rectification matrix (stereo cameras only)
114 // A rotation matrix aligning the camera coordinate system to the ideal
115 // stereo image plane so that epipolar lines in both stereo images are
116 // parallel.
117 std::array<double, 9> r;
118
119 // Projection/camera matrix
120 // [fx' 0 cx' Tx]
121 // P = [ 0 fy' cy' Ty]
122 // [ 0 0 1 0]
123 // By convention, this matrix specifies the intrinsic (camera) matrix
124 // of the processed (rectified) image. That is, the left 3x3 portion
125 // is the normal camera intrinsic matrix for the rectified image.
126 // It projects 3D points in the camera coordinate frame to 2D pixel
127 // coordinates using the focal lengths (fx', fy') and principal point
128 // (cx', cy') - these may differ from the values in K.
129 // For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
130 // also have R = the identity and P[1:3,1:3] = K.
131 // For a stereo pair, the fourth column [Tx Ty 0]' is related to the
132 // position of the optical center of the second camera in the first
133 // camera's frame. We assume Tz = 0 so both cameras are in the same
134 // stereo image plane. The first camera always has Tx = Ty = 0. For
135 // the right (second) camera of a horizontal stereo pair, Ty = 0 and
136 // Tx = -fx' * B, where B is the baseline between the cameras.
137 // Given a 3D point [X Y Z]', the projection (x, y) of the point onto
138 // the rectified image is given by:
139 // [u v w]' = P * [X Y Z 1]'
140 // x = u / w
141 // y = v / w
142 // This holds for both images of a stereo pair.
143 std::array<double, 12> p;
144
145
146 //
147 // Operational Parameters
148 //
149 // These define the image region actually captured by the camera
150 // driver. Although they affect the geometry of the output image, they
151 // may be changed freely without recalibrating the camera.
152 //
153
154 // Binning refers here to any camera setting which combines rectangular
155 // neighborhoods of pixels into larger "super-pixels." It reduces the
156 // resolution of the output image to
157 // (width / binning_x) x (height / binning_y).
158 // The default values binning_x = binning_y = 0 is considered the same
159 // as binning_x = binning_y = 1 (no subsampling).
160 uint32_t binning_x;
161 uint32_t binning_y;
162
163 // Region of interest (subwindow of full camera resolution), given in
164 // full resolution (unbinned) image coordinates. A particular ROI
165 // always denotes the same window of pixels on the camera sensor,
166 // regardless of binning settings.
167 // The default setting of roi (all values 0) is considered the same as
168 // full resolution (roi.width = width, roi.height = height).
170};
171} // namespace sensor_msgs::msg
ROS message class definition for CameraInfo.
Definition camera_info.hpp:37
std_msgs::msg::Header header
Header timestamp should be acquisition time of image.
Definition camera_info.hpp:68
std::array< double, 9 > k
3x3 row-major matrix
Definition camera_info.hpp:111
std::array< double, 12 > p
3x4 row-major matrix
Definition camera_info.hpp:143
std::array< double, 9 > r
3x3 row-major matrix
Definition camera_info.hpp:117
ROS message class definition for RegionOfInterest.
Definition region_of_interest.hpp:20
ROS message class definition for Header.
Definition header.hpp:17
message definitions of the sensor_msgs package
Definition battery_state.hpp:8