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