YARP
Yet Another Robot Platform
CameraInfo.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  * All rights reserved.
4  *
5  * This software may be modified and distributed under the terms of the
6  * BSD-3-Clause license. See the accompanying LICENSE file for details.
7  */
8 
9 // This is an automatically generated file.
10 
11 // Generated from the following "sensor_msgs/CameraInfo" msg definition:
12 // # This message defines meta information for a camera. It should be in a
13 // # camera namespace on topic "camera_info" and accompanied by up to five
14 // # image topics named:
15 // #
16 // # image_raw - raw data from the camera driver, possibly Bayer encoded
17 // # image - monochrome, distorted
18 // # image_color - color, distorted
19 // # image_rect - monochrome, rectified
20 // # image_rect_color - color, rectified
21 // #
22 // # The image_pipeline contains packages (image_proc, stereo_image_proc)
23 // # for producing the four processed image topics from image_raw and
24 // # camera_info. The meaning of the camera parameters are described in
25 // # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
26 // #
27 // # The image_geometry package provides a user-friendly interface to
28 // # common operations using this meta information. If you want to, e.g.,
29 // # project a 3d point into image coordinates, we strongly recommend
30 // # using image_geometry.
31 // #
32 // # If the camera is uncalibrated, the matrices D, K, R, P should be left
33 // # zeroed out. In particular, clients may assume that K[0] == 0.0
34 // # indicates an uncalibrated camera.
35 //
36 // #######################################################################
37 // # Image acquisition info #
38 // #######################################################################
39 //
40 // # Time of image acquisition, camera coordinate frame ID
41 // Header header # Header timestamp should be acquisition time of image
42 // # Header frame_id should be optical frame of camera
43 // # origin of frame should be optical center of camera
44 // # +x should point to the right in the image
45 // # +y should point down in the image
46 // # +z should point into the plane of the image
47 //
48 //
49 // #######################################################################
50 // # Calibration Parameters #
51 // #######################################################################
52 // # These are fixed during camera calibration. Their values will be the #
53 // # same in all messages until the camera is recalibrated. Note that #
54 // # self-calibrating systems may "recalibrate" frequently. #
55 // # #
56 // # The internal parameters can be used to warp a raw (distorted) image #
57 // # to: #
58 // # 1. An undistorted image (requires D and K) #
59 // # 2. A rectified image (requires D, K, R) #
60 // # The projection matrix P projects 3D points into the rectified image.#
61 // #######################################################################
62 //
63 // # The image dimensions with which the camera was calibrated. Normally
64 // # this will be the full camera resolution in pixels.
65 // uint32 height
66 // uint32 width
67 //
68 // # The distortion model used. Supported models are listed in
69 // # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a
70 // # simple model of radial and tangential distortion - is sufficient.
71 // string distortion_model
72 //
73 // # The distortion parameters, size depending on the distortion model.
74 // # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).
75 // float64[] D
76 //
77 // # Intrinsic camera matrix for the raw (distorted) images.
78 // # [fx 0 cx]
79 // # K = [ 0 fy cy]
80 // # [ 0 0 1]
81 // # Projects 3D points in the camera coordinate frame to 2D pixel
82 // # coordinates using the focal lengths (fx, fy) and principal point
83 // # (cx, cy).
84 // float64[9] K # 3x3 row-major matrix
85 //
86 // # Rectification matrix (stereo cameras only)
87 // # A rotation matrix aligning the camera coordinate system to the ideal
88 // # stereo image plane so that epipolar lines in both stereo images are
89 // # parallel.
90 // float64[9] R # 3x3 row-major matrix
91 //
92 // # Projection/camera matrix
93 // # [fx' 0 cx' Tx]
94 // # P = [ 0 fy' cy' Ty]
95 // # [ 0 0 1 0]
96 // # By convention, this matrix specifies the intrinsic (camera) matrix
97 // # of the processed (rectified) image. That is, the left 3x3 portion
98 // # is the normal camera intrinsic matrix for the rectified image.
99 // # It projects 3D points in the camera coordinate frame to 2D pixel
100 // # coordinates using the focal lengths (fx', fy') and principal point
101 // # (cx', cy') - these may differ from the values in K.
102 // # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
103 // # also have R = the identity and P[1:3,1:3] = K.
104 // # For a stereo pair, the fourth column [Tx Ty 0]' is related to the
105 // # position of the optical center of the second camera in the first
106 // # camera's frame. We assume Tz = 0 so both cameras are in the same
107 // # stereo image plane. The first camera always has Tx = Ty = 0. For
108 // # the right (second) camera of a horizontal stereo pair, Ty = 0 and
109 // # Tx = -fx' * B, where B is the baseline between the cameras.
110 // # Given a 3D point [X Y Z]', the projection (x, y) of the point onto
111 // # the rectified image is given by:
112 // # [u v w]' = P * [X Y Z 1]'
113 // # x = u / w
114 // # y = v / w
115 // # This holds for both images of a stereo pair.
116 // float64[12] P # 3x4 row-major matrix
117 //
118 //
119 // #######################################################################
120 // # Operational Parameters #
121 // #######################################################################
122 // # These define the image region actually captured by the camera #
123 // # driver. Although they affect the geometry of the output image, they #
124 // # may be changed freely without recalibrating the camera. #
125 // #######################################################################
126 //
127 // # Binning refers here to any camera setting which combines rectangular
128 // # neighborhoods of pixels into larger "super-pixels." It reduces the
129 // # resolution of the output image to
130 // # (width / binning_x) x (height / binning_y).
131 // # The default values binning_x = binning_y = 0 is considered the same
132 // # as binning_x = binning_y = 1 (no subsampling).
133 // uint32 binning_x
134 // uint32 binning_y
135 //
136 // # Region of interest (subwindow of full camera resolution), given in
137 // # full resolution (unbinned) image coordinates. A particular ROI
138 // # always denotes the same window of pixels on the camera sensor,
139 // # regardless of binning settings.
140 // # The default setting of roi (all values 0) is considered the same as
141 // # full resolution (roi.width = width, roi.height = height).
142 // RegionOfInterest roi
143 // Instances of this class can be read and written with YARP ports,
144 // using a ROS-compatible format.
145 
146 #ifndef YARP_ROSMSG_sensor_msgs_CameraInfo_h
147 #define YARP_ROSMSG_sensor_msgs_CameraInfo_h
148 
149 #include <yarp/os/Wire.h>
150 #include <yarp/os/Type.h>
151 #include <yarp/os/idl/WireTypes.h>
152 #include <string>
153 #include <vector>
156 
157 namespace yarp {
158 namespace rosmsg {
159 namespace sensor_msgs {
160 
162 {
163 public:
165  std::uint32_t height;
166  std::uint32_t width;
167  std::string distortion_model;
168  std::vector<yarp::conf::float64_t> D;
169  std::vector<yarp::conf::float64_t> K;
170  std::vector<yarp::conf::float64_t> R;
171  std::vector<yarp::conf::float64_t> P;
172  std::uint32_t binning_x;
173  std::uint32_t binning_y;
175 
177  header(),
178  height(0),
179  width(0),
180  distortion_model(""),
181  D(),
182  K(),
183  R(),
184  P(),
185  binning_x(0),
186  binning_y(0),
187  roi()
188  {
189  K.resize(9, 0.0);
190  R.resize(9, 0.0);
191  P.resize(12, 0.0);
192  }
193 
194  void clear()
195  {
196  // *** header ***
197  header.clear();
198 
199  // *** height ***
200  height = 0;
201 
202  // *** width ***
203  width = 0;
204 
205  // *** distortion_model ***
206  distortion_model = "";
207 
208  // *** D ***
209  D.clear();
210 
211  // *** K ***
212  K.clear();
213  K.resize(9, 0.0);
214 
215  // *** R ***
216  R.clear();
217  R.resize(9, 0.0);
218 
219  // *** P ***
220  P.clear();
221  P.resize(12, 0.0);
222 
223  // *** binning_x ***
224  binning_x = 0;
225 
226  // *** binning_y ***
227  binning_y = 0;
228 
229  // *** roi ***
230  roi.clear();
231  }
232 
233  bool readBare(yarp::os::ConnectionReader& connection) override
234  {
235  // *** header ***
236  if (!header.read(connection)) {
237  return false;
238  }
239 
240  // *** height ***
241  height = connection.expectInt32();
242 
243  // *** width ***
244  width = connection.expectInt32();
245 
246  // *** distortion_model ***
247  int len = connection.expectInt32();
248  distortion_model.resize(len);
249  if (!connection.expectBlock((char*)distortion_model.c_str(), len)) {
250  return false;
251  }
252 
253  // *** D ***
254  len = connection.expectInt32();
255  D.resize(len);
256  if (len > 0 && !connection.expectBlock((char*)&D[0], sizeof(yarp::conf::float64_t)*len)) {
257  return false;
258  }
259 
260  // *** K ***
261  len = 9;
262  K.resize(len);
263  if (len > 0 && !connection.expectBlock((char*)&K[0], sizeof(yarp::conf::float64_t)*len)) {
264  return false;
265  }
266 
267  // *** R ***
268  len = 9;
269  R.resize(len);
270  if (len > 0 && !connection.expectBlock((char*)&R[0], sizeof(yarp::conf::float64_t)*len)) {
271  return false;
272  }
273 
274  // *** P ***
275  len = 12;
276  P.resize(len);
277  if (len > 0 && !connection.expectBlock((char*)&P[0], sizeof(yarp::conf::float64_t)*len)) {
278  return false;
279  }
280 
281  // *** binning_x ***
282  binning_x = connection.expectInt32();
283 
284  // *** binning_y ***
285  binning_y = connection.expectInt32();
286 
287  // *** roi ***
288  if (!roi.read(connection)) {
289  return false;
290  }
291 
292  return !connection.isError();
293  }
294 
295  bool readBottle(yarp::os::ConnectionReader& connection) override
296  {
297  connection.convertTextMode();
298  yarp::os::idl::WireReader reader(connection);
299  if (!reader.readListHeader(11)) {
300  return false;
301  }
302 
303  // *** header ***
304  if (!header.read(connection)) {
305  return false;
306  }
307 
308  // *** height ***
309  height = reader.expectInt32();
310 
311  // *** width ***
312  width = reader.expectInt32();
313 
314  // *** distortion_model ***
315  if (!reader.readString(distortion_model)) {
316  return false;
317  }
318 
319  // *** D ***
320  if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_FLOAT64)) {
321  return false;
322  }
323  int len = connection.expectInt32();
324  D.resize(len);
325  for (int i=0; i<len; i++) {
326  D[i] = (yarp::conf::float64_t)connection.expectFloat64();
327  }
328 
329  // *** K ***
330  if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_FLOAT64)) {
331  return false;
332  }
333  len = connection.expectInt32();
334  K.resize(len);
335  for (int i=0; i<len; i++) {
336  K[i] = (yarp::conf::float64_t)connection.expectFloat64();
337  }
338 
339  // *** R ***
340  if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_FLOAT64)) {
341  return false;
342  }
343  len = connection.expectInt32();
344  R.resize(len);
345  for (int i=0; i<len; i++) {
346  R[i] = (yarp::conf::float64_t)connection.expectFloat64();
347  }
348 
349  // *** P ***
350  if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_FLOAT64)) {
351  return false;
352  }
353  len = connection.expectInt32();
354  P.resize(len);
355  for (int i=0; i<len; i++) {
356  P[i] = (yarp::conf::float64_t)connection.expectFloat64();
357  }
358 
359  // *** binning_x ***
360  binning_x = reader.expectInt32();
361 
362  // *** binning_y ***
363  binning_y = reader.expectInt32();
364 
365  // *** roi ***
366  if (!roi.read(connection)) {
367  return false;
368  }
369 
370  return !connection.isError();
371  }
372 
374  bool read(yarp::os::ConnectionReader& connection) override
375  {
376  return (connection.isBareMode() ? readBare(connection)
377  : readBottle(connection));
378  }
379 
380  bool writeBare(yarp::os::ConnectionWriter& connection) const override
381  {
382  // *** header ***
383  if (!header.write(connection)) {
384  return false;
385  }
386 
387  // *** height ***
388  connection.appendInt32(height);
389 
390  // *** width ***
391  connection.appendInt32(width);
392 
393  // *** distortion_model ***
394  connection.appendInt32(distortion_model.length());
395  connection.appendExternalBlock((char*)distortion_model.c_str(), distortion_model.length());
396 
397  // *** D ***
398  connection.appendInt32(D.size());
399  if (D.size()>0) {
400  connection.appendExternalBlock((char*)&D[0], sizeof(yarp::conf::float64_t)*D.size());
401  }
402 
403  // *** K ***
404  if (K.size()>0) {
405  connection.appendExternalBlock((char*)&K[0], sizeof(yarp::conf::float64_t)*K.size());
406  }
407 
408  // *** R ***
409  if (R.size()>0) {
410  connection.appendExternalBlock((char*)&R[0], sizeof(yarp::conf::float64_t)*R.size());
411  }
412 
413  // *** P ***
414  if (P.size()>0) {
415  connection.appendExternalBlock((char*)&P[0], sizeof(yarp::conf::float64_t)*P.size());
416  }
417 
418  // *** binning_x ***
419  connection.appendInt32(binning_x);
420 
421  // *** binning_y ***
422  connection.appendInt32(binning_y);
423 
424  // *** roi ***
425  if (!roi.write(connection)) {
426  return false;
427  }
428 
429  return !connection.isError();
430  }
431 
432  bool writeBottle(yarp::os::ConnectionWriter& connection) const override
433  {
434  connection.appendInt32(BOTTLE_TAG_LIST);
435  connection.appendInt32(11);
436 
437  // *** header ***
438  if (!header.write(connection)) {
439  return false;
440  }
441 
442  // *** height ***
443  connection.appendInt32(BOTTLE_TAG_INT32);
444  connection.appendInt32(height);
445 
446  // *** width ***
447  connection.appendInt32(BOTTLE_TAG_INT32);
448  connection.appendInt32(width);
449 
450  // *** distortion_model ***
451  connection.appendInt32(BOTTLE_TAG_STRING);
452  connection.appendInt32(distortion_model.length());
453  connection.appendExternalBlock((char*)distortion_model.c_str(), distortion_model.length());
454 
455  // *** D ***
457  connection.appendInt32(D.size());
458  for (size_t i=0; i<D.size(); i++) {
459  connection.appendFloat64(D[i]);
460  }
461 
462  // *** K ***
464  connection.appendInt32(K.size());
465  for (size_t i=0; i<K.size(); i++) {
466  connection.appendFloat64(K[i]);
467  }
468 
469  // *** R ***
471  connection.appendInt32(R.size());
472  for (size_t i=0; i<R.size(); i++) {
473  connection.appendFloat64(R[i]);
474  }
475 
476  // *** P ***
478  connection.appendInt32(P.size());
479  for (size_t i=0; i<P.size(); i++) {
480  connection.appendFloat64(P[i]);
481  }
482 
483  // *** binning_x ***
484  connection.appendInt32(BOTTLE_TAG_INT32);
485  connection.appendInt32(binning_x);
486 
487  // *** binning_y ***
488  connection.appendInt32(BOTTLE_TAG_INT32);
489  connection.appendInt32(binning_y);
490 
491  // *** roi ***
492  if (!roi.write(connection)) {
493  return false;
494  }
495 
496  connection.convertTextMode();
497  return !connection.isError();
498  }
499 
501  bool write(yarp::os::ConnectionWriter& connection) const override
502  {
503  return (connection.isBareMode() ? writeBare(connection)
504  : writeBottle(connection));
505  }
506 
507  // This class will serialize ROS style or YARP style depending on protocol.
508  // If you need to force a serialization style, use one of these classes:
511 
512  // The name for this message, ROS will need this
513  static constexpr const char* typeName = "sensor_msgs/CameraInfo";
514 
515  // The checksum for this message, ROS will need this
516  static constexpr const char* typeChecksum = "c9a58c1b0b154e0e6da7578cb991d214";
517 
518  // The source text for this message, ROS will need this
519  static constexpr const char* typeText = "\
520 # This message defines meta information for a camera. It should be in a\n\
521 # camera namespace on topic \"camera_info\" and accompanied by up to five\n\
522 # image topics named:\n\
523 #\n\
524 # image_raw - raw data from the camera driver, possibly Bayer encoded\n\
525 # image - monochrome, distorted\n\
526 # image_color - color, distorted\n\
527 # image_rect - monochrome, rectified\n\
528 # image_rect_color - color, rectified\n\
529 #\n\
530 # The image_pipeline contains packages (image_proc, stereo_image_proc)\n\
531 # for producing the four processed image topics from image_raw and\n\
532 # camera_info. The meaning of the camera parameters are described in\n\
533 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.\n\
534 #\n\
535 # The image_geometry package provides a user-friendly interface to\n\
536 # common operations using this meta information. If you want to, e.g.,\n\
537 # project a 3d point into image coordinates, we strongly recommend\n\
538 # using image_geometry.\n\
539 #\n\
540 # If the camera is uncalibrated, the matrices D, K, R, P should be left\n\
541 # zeroed out. In particular, clients may assume that K[0] == 0.0\n\
542 # indicates an uncalibrated camera.\n\
543 \n\
544 #######################################################################\n\
545 # Image acquisition info #\n\
546 #######################################################################\n\
547 \n\
548 # Time of image acquisition, camera coordinate frame ID\n\
549 Header header # Header timestamp should be acquisition time of image\n\
550  # Header frame_id should be optical frame of camera\n\
551  # origin of frame should be optical center of camera\n\
552  # +x should point to the right in the image\n\
553  # +y should point down in the image\n\
554  # +z should point into the plane of the image\n\
555 \n\
556 \n\
557 #######################################################################\n\
558 # Calibration Parameters #\n\
559 #######################################################################\n\
560 # These are fixed during camera calibration. Their values will be the #\n\
561 # same in all messages until the camera is recalibrated. Note that #\n\
562 # self-calibrating systems may \"recalibrate\" frequently. #\n\
563 # #\n\
564 # The internal parameters can be used to warp a raw (distorted) image #\n\
565 # to: #\n\
566 # 1. An undistorted image (requires D and K) #\n\
567 # 2. A rectified image (requires D, K, R) #\n\
568 # The projection matrix P projects 3D points into the rectified image.#\n\
569 #######################################################################\n\
570 \n\
571 # The image dimensions with which the camera was calibrated. Normally\n\
572 # this will be the full camera resolution in pixels.\n\
573 uint32 height\n\
574 uint32 width\n\
575 \n\
576 # The distortion model used. Supported models are listed in\n\
577 # sensor_msgs/distortion_models.h. For most cameras, \"plumb_bob\" - a\n\
578 # simple model of radial and tangential distortion - is sufficient.\n\
579 string distortion_model\n\
580 \n\
581 # The distortion parameters, size depending on the distortion model.\n\
582 # For \"plumb_bob\", the 5 parameters are: (k1, k2, t1, t2, k3).\n\
583 float64[] D\n\
584 \n\
585 # Intrinsic camera matrix for the raw (distorted) images.\n\
586 # [fx 0 cx]\n\
587 # K = [ 0 fy cy]\n\
588 # [ 0 0 1]\n\
589 # Projects 3D points in the camera coordinate frame to 2D pixel\n\
590 # coordinates using the focal lengths (fx, fy) and principal point\n\
591 # (cx, cy).\n\
592 float64[9] K # 3x3 row-major matrix\n\
593 \n\
594 # Rectification matrix (stereo cameras only)\n\
595 # A rotation matrix aligning the camera coordinate system to the ideal\n\
596 # stereo image plane so that epipolar lines in both stereo images are\n\
597 # parallel.\n\
598 float64[9] R # 3x3 row-major matrix\n\
599 \n\
600 # Projection/camera matrix\n\
601 # [fx' 0 cx' Tx]\n\
602 # P = [ 0 fy' cy' Ty]\n\
603 # [ 0 0 1 0]\n\
604 # By convention, this matrix specifies the intrinsic (camera) matrix\n\
605 # of the processed (rectified) image. That is, the left 3x3 portion\n\
606 # is the normal camera intrinsic matrix for the rectified image.\n\
607 # It projects 3D points in the camera coordinate frame to 2D pixel\n\
608 # coordinates using the focal lengths (fx', fy') and principal point\n\
609 # (cx', cy') - these may differ from the values in K.\n\
610 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will\n\
611 # also have R = the identity and P[1:3,1:3] = K.\n\
612 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the\n\
613 # position of the optical center of the second camera in the first\n\
614 # camera's frame. We assume Tz = 0 so both cameras are in the same\n\
615 # stereo image plane. The first camera always has Tx = Ty = 0. For\n\
616 # the right (second) camera of a horizontal stereo pair, Ty = 0 and\n\
617 # Tx = -fx' * B, where B is the baseline between the cameras.\n\
618 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto\n\
619 # the rectified image is given by:\n\
620 # [u v w]' = P * [X Y Z 1]'\n\
621 # x = u / w\n\
622 # y = v / w\n\
623 # This holds for both images of a stereo pair.\n\
624 float64[12] P # 3x4 row-major matrix\n\
625 \n\
626 \n\
627 #######################################################################\n\
628 # Operational Parameters #\n\
629 #######################################################################\n\
630 # These define the image region actually captured by the camera #\n\
631 # driver. Although they affect the geometry of the output image, they #\n\
632 # may be changed freely without recalibrating the camera. #\n\
633 #######################################################################\n\
634 \n\
635 # Binning refers here to any camera setting which combines rectangular\n\
636 # neighborhoods of pixels into larger \"super-pixels.\" It reduces the\n\
637 # resolution of the output image to\n\
638 # (width / binning_x) x (height / binning_y).\n\
639 # The default values binning_x = binning_y = 0 is considered the same\n\
640 # as binning_x = binning_y = 1 (no subsampling).\n\
641 uint32 binning_x\n\
642 uint32 binning_y\n\
643 \n\
644 # Region of interest (subwindow of full camera resolution), given in\n\
645 # full resolution (unbinned) image coordinates. A particular ROI\n\
646 # always denotes the same window of pixels on the camera sensor,\n\
647 # regardless of binning settings.\n\
648 # The default setting of roi (all values 0) is considered the same as\n\
649 # full resolution (roi.width = width, roi.height = height).\n\
650 RegionOfInterest roi\n\
651 \n\
652 ================================================================================\n\
653 MSG: std_msgs/Header\n\
654 # Standard metadata for higher-level stamped data types.\n\
655 # This is generally used to communicate timestamped data \n\
656 # in a particular coordinate frame.\n\
657 # \n\
658 # sequence ID: consecutively increasing ID \n\
659 uint32 seq\n\
660 #Two-integer timestamp that is expressed as:\n\
661 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
662 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
663 # time-handling sugar is provided by the client library\n\
664 time stamp\n\
665 #Frame this data is associated with\n\
666 # 0: no frame\n\
667 # 1: global frame\n\
668 string frame_id\n\
669 \n\
670 ================================================================================\n\
671 MSG: sensor_msgs/RegionOfInterest\n\
672 # This message is used to specify a region of interest within an image.\n\
673 #\n\
674 # When used to specify the ROI setting of the camera when the image was\n\
675 # taken, the height and width fields should either match the height and\n\
676 # width fields for the associated image; or height = width = 0\n\
677 # indicates that the full resolution image was captured.\n\
678 \n\
679 uint32 x_offset # Leftmost pixel of the ROI\n\
680  # (0 if the ROI includes the left edge of the image)\n\
681 uint32 y_offset # Topmost pixel of the ROI\n\
682  # (0 if the ROI includes the top edge of the image)\n\
683 uint32 height # Height of ROI\n\
684 uint32 width # Width of ROI\n\
685 \n\
686 # True if a distinct rectified ROI should be calculated from the \"raw\"\n\
687 # ROI in this message. Typically this should be False if the full image\n\
688 # is captured (ROI not used), and True if a subwindow is captured (ROI\n\
689 # used).\n\
690 bool do_rectify\n\
691 ";
692 
693  yarp::os::Type getType() const override
694  {
696  typ.addProperty("md5sum", yarp::os::Value(typeChecksum));
697  typ.addProperty("message_definition", yarp::os::Value(typeText));
698  return typ;
699  }
700 };
701 
702 } // namespace sensor_msgs
703 } // namespace rosmsg
704 } // namespace yarp
705 
706 #endif // YARP_ROSMSG_sensor_msgs_CameraInfo_h
yarp::rosmsg::std_msgs::Header::read
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: Header.h:115
yarp::os::idl::WireReader::readString
bool readString(std::string &str, bool *is_vocab=nullptr)
Definition: WireReader.cpp:339
yarp::rosmsg::sensor_msgs::CameraInfo::writeBare
bool writeBare(yarp::os::ConnectionWriter &connection) const override
Definition: CameraInfo.h:380
yarp::rosmsg::sensor_msgs::CameraInfo::typeChecksum
static constexpr const char * typeChecksum
Definition: CameraInfo.h:516
WireTypes.h
BOTTLE_TAG_LIST
#define BOTTLE_TAG_LIST
Definition: Bottle.h:30
yarp::rosmsg::sensor_msgs::CameraInfo
Definition: CameraInfo.h:162
yarp::os::ConnectionWriter::appendFloat64
virtual void appendFloat64(yarp::conf::float64_t data)=0
Send a representation of a 64-bit floating point number to the network connection.
yarp::os::idl::BottleStyle
Definition: BottleStyle.h:22
yarp::rosmsg::sensor_msgs::RegionOfInterest::write
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: RegionOfInterest.h:188
yarp::os::Type
Definition: Type.h:24
yarp::os::idl::WirePortable::read
virtual bool read(yarp::os::idl::WireReader &reader)
Definition: WirePortable.cpp:14
Header.h
yarp::rosmsg::sensor_msgs::CameraInfo::rosStyle
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::CameraInfo > rosStyle
Definition: CameraInfo.h:509
yarp::os::ConnectionReader::isBareMode
virtual bool isBareMode() const =0
Check if the connection is bare mode.
yarp::rosmsg::std_msgs::Header::clear
void clear()
Definition: Header.h:58
BOTTLE_TAG_STRING
#define BOTTLE_TAG_STRING
Definition: Bottle.h:28
Wire.h
yarp::rosmsg::sensor_msgs::CameraInfo::header
yarp::rosmsg::std_msgs::Header header
Definition: CameraInfo.h:164
BOTTLE_TAG_INT32
#define BOTTLE_TAG_INT32
Definition: Bottle.h:23
yarp::os::ConnectionReader::expectFloat64
virtual yarp::conf::float64_t expectFloat64()=0
Read a 64-bit floating point number from the network connection.
yarp::os::ConnectionWriter::isError
virtual bool isError() const =0
yarp::rosmsg::sensor_msgs::CameraInfo::roi
yarp::rosmsg::sensor_msgs::RegionOfInterest roi
Definition: CameraInfo.h:174
yarp::os::Type::byName
static Type byName(const char *name)
Definition: Type.cpp:174
yarp::os::ConnectionReader::expectInt32
virtual std::int32_t expectInt32()=0
Read a 32-bit integer from the network connection.
yarp::os::Type::addProperty
Type & addProperty(const char *key, const Value &val)
Definition: Type.cpp:137
Type.h
yarp::os::ConnectionWriter
An interface for writing to a network connection.
Definition: ConnectionWriter.h:40
yarp::rosmsg::sensor_msgs::RegionOfInterest::read
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: RegionOfInterest.h:132
yarp::os::ConnectionReader::isError
virtual bool isError() const =0
yarp::rosmsg::sensor_msgs::CameraInfo::height
std::uint32_t height
Definition: CameraInfo.h:165
yarp::rosmsg::sensor_msgs::CameraInfo::width
std::uint32_t width
Definition: CameraInfo.h:166
yarp::os::ConnectionReader::convertTextMode
virtual bool convertTextMode()=0
Reads in a standard description in text mode, and converts it to a standard description in binary.
yarp::rosmsg::sensor_msgs::CameraInfo::getType
yarp::os::Type getType() const override
Definition: CameraInfo.h:693
yarp::os::idl::WirePortable
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
Definition: WirePortable.h:26
yarp::os::ConnectionWriter::isBareMode
virtual bool isBareMode() const =0
Check if the connection is bare mode.
yarp::rosmsg::sensor_msgs::CameraInfo::bottleStyle
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::CameraInfo > bottleStyle
Definition: CameraInfo.h:510
yarp::rosmsg::sensor_msgs::CameraInfo::binning_x
std::uint32_t binning_x
Definition: CameraInfo.h:172
yarp::rosmsg::sensor_msgs::CameraInfo::P
std::vector< yarp::conf::float64_t > P
Definition: CameraInfo.h:171
yarp::rosmsg::std_msgs::Header::write
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: Header.h:162
yarp::rosmsg::sensor_msgs::RegionOfInterest
Definition: RegionOfInterest.h:48
yarp::rosmsg::sensor_msgs::CameraInfo::D
std::vector< yarp::conf::float64_t > D
Definition: CameraInfo.h:168
yarp::rosmsg::sensor_msgs::CameraInfo::readBottle
bool readBottle(yarp::os::ConnectionReader &connection) override
Definition: CameraInfo.h:295
yarp::os::ConnectionWriter::convertTextMode
virtual bool convertTextMode()=0
Converts a standard description in binary into a textual description, if the connection is in text-mo...
yarp::rosmsg::sensor_msgs::CameraInfo::CameraInfo
CameraInfo()
Definition: CameraInfo.h:176
yarp::os::ConnectionWriter::appendInt32
virtual void appendInt32(std::int32_t data)=0
Send a representation of a 32-bit integer to the network connection.
yarp::os::idl::WireReader
IDL-friendly connection reader.
Definition: WireReader.h:33
yarp::os::ConnectionReader
An interface for reading from a network connection.
Definition: ConnectionReader.h:40
yarp::rosmsg::sensor_msgs::CameraInfo::typeText
static constexpr const char * typeText
Definition: CameraInfo.h:519
yarp::os::idl::BareStyle
Definition: BareStyle.h:22
BOTTLE_TAG_FLOAT64
#define BOTTLE_TAG_FLOAT64
Definition: Bottle.h:27
yarp::os::idl::WireReader::expectInt32
std::int32_t expectInt32()
Definition: WireReader.h:99
yarp::rosmsg::sensor_msgs::CameraInfo::R
std::vector< yarp::conf::float64_t > R
Definition: CameraInfo.h:170
RegionOfInterest.h
yarp::rosmsg::sensor_msgs::RegionOfInterest::clear
void clear()
Definition: RegionOfInterest.h:65
yarp
The main, catch-all namespace for YARP.
Definition: environment.h:18
yarp::rosmsg::sensor_msgs::CameraInfo::clear
void clear()
Definition: CameraInfo.h:194
yarp::rosmsg::sensor_msgs::CameraInfo::binning_y
std::uint32_t binning_y
Definition: CameraInfo.h:173
yarp::conf::float64_t
double float64_t
Definition: numeric.h:51
yarp::os::ConnectionWriter::appendExternalBlock
virtual void appendExternalBlock(const char *data, size_t len)=0
Send a block of data to the network connection, without making a copy.
yarp::os::ConnectionReader::expectBlock
virtual bool expectBlock(char *data, size_t len)=0
Read a block of data from the network connection.
yarp::rosmsg::sensor_msgs::CameraInfo::distortion_model
std::string distortion_model
Definition: CameraInfo.h:167
yarp::os::Value
A single value (typically within a Bottle).
Definition: Value.h:47
sensor_msgs
Definition: BatteryState.h:22
yarp::rosmsg::sensor_msgs::CameraInfo::writeBottle
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
Definition: CameraInfo.h:432
yarp::rosmsg::sensor_msgs::CameraInfo::write
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: CameraInfo.h:501
yarp::rosmsg::sensor_msgs::CameraInfo::typeName
static constexpr const char * typeName
Definition: CameraInfo.h:513
yarp::rosmsg::sensor_msgs::CameraInfo::read
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: CameraInfo.h:374
yarp::rosmsg::std_msgs::Header
Definition: Header.h:45
yarp::rosmsg::sensor_msgs::CameraInfo::K
std::vector< yarp::conf::float64_t > K
Definition: CameraInfo.h:169
yarp::os::idl::WireReader::readListHeader
bool readListHeader()
Definition: WireReader.cpp:470
yarp::rosmsg::sensor_msgs::CameraInfo::readBare
bool readBare(yarp::os::ConnectionReader &connection) override
Definition: CameraInfo.h:233
yarp::os::idl::WirePortable::write
virtual bool write(const yarp::os::idl::WireWriter &writer) const
Definition: WirePortable.cpp:20