YARP
Yet Another Robot Platform
DisparityImage.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 "stereo_msgs/DisparityImage" msg definition:
12 // # Separate header for compatibility with current TimeSynchronizer.
13 // # Likely to be removed in a later release, use image.header instead.
14 // Header header
15 //
16 // # Floating point disparity image. The disparities are pre-adjusted for any
17 // # x-offset between the principal points of the two cameras (in the case
18 // # that they are verged). That is: d = x_l - x_r - (cx_l - cx_r)
19 // sensor_msgs/Image image
20 //
21 // # Stereo geometry. For disparity d, the depth from the camera is Z = fT/d.
22 // float32 f # Focal length, pixels
23 // float32 T # Baseline, world units
24 //
25 // # Subwindow of (potentially) valid disparity values.
26 // sensor_msgs/RegionOfInterest valid_window
27 //
28 // # The range of disparities searched.
29 // # In the disparity image, any disparity less than min_disparity is invalid.
30 // # The disparity search range defines the horopter, or 3D volume that the
31 // # stereo algorithm can "see". Points with Z outside of:
32 // # Z_min = fT / max_disparity
33 // # Z_max = fT / min_disparity
34 // # could not be found.
35 // float32 min_disparity
36 // float32 max_disparity
37 //
38 // # Smallest allowed disparity increment. The smallest achievable depth range
39 // # resolution is delta_Z = (Z^2/fT)*delta_d.
40 // float32 delta_d
41 // Instances of this class can be read and written with YARP ports,
42 // using a ROS-compatible format.
43 
44 #ifndef YARP_ROSMSG_stereo_msgs_DisparityImage_h
45 #define YARP_ROSMSG_stereo_msgs_DisparityImage_h
46 
47 #include <yarp/os/Wire.h>
48 #include <yarp/os/Type.h>
49 #include <yarp/os/idl/WireTypes.h>
50 #include <string>
51 #include <vector>
55 
56 namespace yarp {
57 namespace rosmsg {
58 namespace stereo_msgs {
59 
61 {
62 public:
71 
73  header(),
74  image(),
75  f(0.0f),
76  T(0.0f),
77  valid_window(),
78  min_disparity(0.0f),
79  max_disparity(0.0f),
80  delta_d(0.0f)
81  {
82  }
83 
84  void clear()
85  {
86  // *** header ***
87  header.clear();
88 
89  // *** image ***
90  image.clear();
91 
92  // *** f ***
93  f = 0.0f;
94 
95  // *** T ***
96  T = 0.0f;
97 
98  // *** valid_window ***
100 
101  // *** min_disparity ***
102  min_disparity = 0.0f;
103 
104  // *** max_disparity ***
105  max_disparity = 0.0f;
106 
107  // *** delta_d ***
108  delta_d = 0.0f;
109  }
110 
111  bool readBare(yarp::os::ConnectionReader& connection) override
112  {
113  // *** header ***
114  if (!header.read(connection)) {
115  return false;
116  }
117 
118  // *** image ***
119  if (!image.read(connection)) {
120  return false;
121  }
122 
123  // *** f ***
124  f = connection.expectFloat32();
125 
126  // *** T ***
127  T = connection.expectFloat32();
128 
129  // *** valid_window ***
130  if (!valid_window.read(connection)) {
131  return false;
132  }
133 
134  // *** min_disparity ***
135  min_disparity = connection.expectFloat32();
136 
137  // *** max_disparity ***
138  max_disparity = connection.expectFloat32();
139 
140  // *** delta_d ***
141  delta_d = connection.expectFloat32();
142 
143  return !connection.isError();
144  }
145 
146  bool readBottle(yarp::os::ConnectionReader& connection) override
147  {
148  connection.convertTextMode();
149  yarp::os::idl::WireReader reader(connection);
150  if (!reader.readListHeader(8)) {
151  return false;
152  }
153 
154  // *** header ***
155  if (!header.read(connection)) {
156  return false;
157  }
158 
159  // *** image ***
160  if (!image.read(connection)) {
161  return false;
162  }
163 
164  // *** f ***
165  f = reader.expectFloat32();
166 
167  // *** T ***
168  T = reader.expectFloat32();
169 
170  // *** valid_window ***
171  if (!valid_window.read(connection)) {
172  return false;
173  }
174 
175  // *** min_disparity ***
176  min_disparity = reader.expectFloat32();
177 
178  // *** max_disparity ***
179  max_disparity = reader.expectFloat32();
180 
181  // *** delta_d ***
182  delta_d = reader.expectFloat32();
183 
184  return !connection.isError();
185  }
186 
188  bool read(yarp::os::ConnectionReader& connection) override
189  {
190  return (connection.isBareMode() ? readBare(connection)
191  : readBottle(connection));
192  }
193 
194  bool writeBare(yarp::os::ConnectionWriter& connection) const override
195  {
196  // *** header ***
197  if (!header.write(connection)) {
198  return false;
199  }
200 
201  // *** image ***
202  if (!image.write(connection)) {
203  return false;
204  }
205 
206  // *** f ***
207  connection.appendFloat32(f);
208 
209  // *** T ***
210  connection.appendFloat32(T);
211 
212  // *** valid_window ***
213  if (!valid_window.write(connection)) {
214  return false;
215  }
216 
217  // *** min_disparity ***
218  connection.appendFloat32(min_disparity);
219 
220  // *** max_disparity ***
221  connection.appendFloat32(max_disparity);
222 
223  // *** delta_d ***
224  connection.appendFloat32(delta_d);
225 
226  return !connection.isError();
227  }
228 
229  bool writeBottle(yarp::os::ConnectionWriter& connection) const override
230  {
231  connection.appendInt32(BOTTLE_TAG_LIST);
232  connection.appendInt32(8);
233 
234  // *** header ***
235  if (!header.write(connection)) {
236  return false;
237  }
238 
239  // *** image ***
240  if (!image.write(connection)) {
241  return false;
242  }
243 
244  // *** f ***
245  connection.appendInt32(BOTTLE_TAG_FLOAT32);
246  connection.appendFloat32(f);
247 
248  // *** T ***
249  connection.appendInt32(BOTTLE_TAG_FLOAT32);
250  connection.appendFloat32(T);
251 
252  // *** valid_window ***
253  if (!valid_window.write(connection)) {
254  return false;
255  }
256 
257  // *** min_disparity ***
258  connection.appendInt32(BOTTLE_TAG_FLOAT32);
259  connection.appendFloat32(min_disparity);
260 
261  // *** max_disparity ***
262  connection.appendInt32(BOTTLE_TAG_FLOAT32);
263  connection.appendFloat32(max_disparity);
264 
265  // *** delta_d ***
266  connection.appendInt32(BOTTLE_TAG_FLOAT32);
267  connection.appendFloat32(delta_d);
268 
269  connection.convertTextMode();
270  return !connection.isError();
271  }
272 
274  bool write(yarp::os::ConnectionWriter& connection) const override
275  {
276  return (connection.isBareMode() ? writeBare(connection)
277  : writeBottle(connection));
278  }
279 
280  // This class will serialize ROS style or YARP style depending on protocol.
281  // If you need to force a serialization style, use one of these classes:
284 
285  // The name for this message, ROS will need this
286  static constexpr const char* typeName = "stereo_msgs/DisparityImage";
287 
288  // The checksum for this message, ROS will need this
289  static constexpr const char* typeChecksum = "04a177815f75271039fa21f16acad8c9";
290 
291  // The source text for this message, ROS will need this
292  static constexpr const char* typeText = "\
293 # Separate header for compatibility with current TimeSynchronizer.\n\
294 # Likely to be removed in a later release, use image.header instead.\n\
295 Header header\n\
296 \n\
297 # Floating point disparity image. The disparities are pre-adjusted for any\n\
298 # x-offset between the principal points of the two cameras (in the case\n\
299 # that they are verged). That is: d = x_l - x_r - (cx_l - cx_r)\n\
300 sensor_msgs/Image image\n\
301 \n\
302 # Stereo geometry. For disparity d, the depth from the camera is Z = fT/d.\n\
303 float32 f # Focal length, pixels\n\
304 float32 T # Baseline, world units\n\
305 \n\
306 # Subwindow of (potentially) valid disparity values.\n\
307 sensor_msgs/RegionOfInterest valid_window\n\
308 \n\
309 # The range of disparities searched.\n\
310 # In the disparity image, any disparity less than min_disparity is invalid.\n\
311 # The disparity search range defines the horopter, or 3D volume that the\n\
312 # stereo algorithm can \"see\". Points with Z outside of:\n\
313 # Z_min = fT / max_disparity\n\
314 # Z_max = fT / min_disparity\n\
315 # could not be found.\n\
316 float32 min_disparity\n\
317 float32 max_disparity\n\
318 \n\
319 # Smallest allowed disparity increment. The smallest achievable depth range\n\
320 # resolution is delta_Z = (Z^2/fT)*delta_d.\n\
321 float32 delta_d\n\
322 \n\
323 ================================================================================\n\
324 MSG: std_msgs/Header\n\
325 # Standard metadata for higher-level stamped data types.\n\
326 # This is generally used to communicate timestamped data \n\
327 # in a particular coordinate frame.\n\
328 # \n\
329 # sequence ID: consecutively increasing ID \n\
330 uint32 seq\n\
331 #Two-integer timestamp that is expressed as:\n\
332 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
333 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
334 # time-handling sugar is provided by the client library\n\
335 time stamp\n\
336 #Frame this data is associated with\n\
337 # 0: no frame\n\
338 # 1: global frame\n\
339 string frame_id\n\
340 \n\
341 ================================================================================\n\
342 MSG: sensor_msgs/Image\n\
343 # This message contains an uncompressed image\n\
344 # (0, 0) is at top-left corner of image\n\
345 #\n\
346 \n\
347 Header header # Header timestamp should be acquisition time of image\n\
348  # Header frame_id should be optical frame of camera\n\
349  # origin of frame should be optical center of cameara\n\
350  # +x should point to the right in the image\n\
351  # +y should point down in the image\n\
352  # +z should point into to plane of the image\n\
353  # If the frame_id here and the frame_id of the CameraInfo\n\
354  # message associated with the image conflict\n\
355  # the behavior is undefined\n\
356 \n\
357 uint32 height # image height, that is, number of rows\n\
358 uint32 width # image width, that is, number of columns\n\
359 \n\
360 # The legal values for encoding are in file src/image_encodings.cpp\n\
361 # If you want to standardize a new string format, join\n\
362 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\
363 \n\
364 string encoding # Encoding of pixels -- channel meaning, ordering, size\n\
365  # taken from the list of strings in include/sensor_msgs/image_encodings.h\n\
366 \n\
367 uint8 is_bigendian # is this data bigendian?\n\
368 uint32 step # Full row length in bytes\n\
369 uint8[] data # actual matrix data, size is (step * rows)\n\
370 \n\
371 ================================================================================\n\
372 MSG: sensor_msgs/RegionOfInterest\n\
373 # This message is used to specify a region of interest within an image.\n\
374 #\n\
375 # When used to specify the ROI setting of the camera when the image was\n\
376 # taken, the height and width fields should either match the height and\n\
377 # width fields for the associated image; or height = width = 0\n\
378 # indicates that the full resolution image was captured.\n\
379 \n\
380 uint32 x_offset # Leftmost pixel of the ROI\n\
381  # (0 if the ROI includes the left edge of the image)\n\
382 uint32 y_offset # Topmost pixel of the ROI\n\
383  # (0 if the ROI includes the top edge of the image)\n\
384 uint32 height # Height of ROI\n\
385 uint32 width # Width of ROI\n\
386 \n\
387 # True if a distinct rectified ROI should be calculated from the \"raw\"\n\
388 # ROI in this message. Typically this should be False if the full image\n\
389 # is captured (ROI not used), and True if a subwindow is captured (ROI\n\
390 # used).\n\
391 bool do_rectify\n\
392 ";
393 
394  yarp::os::Type getType() const override
395  {
397  typ.addProperty("md5sum", yarp::os::Value(typeChecksum));
398  typ.addProperty("message_definition", yarp::os::Value(typeText));
399  return typ;
400  }
401 };
402 
403 } // namespace stereo_msgs
404 } // namespace rosmsg
405 } // namespace yarp
406 
407 #endif // YARP_ROSMSG_stereo_msgs_DisparityImage_h
yarp::os::ConnectionWriter::appendFloat32
virtual void appendFloat32(yarp::conf::float32_t data)=0
Send a representation of a 32-bit floating point number to the network connection.
yarp::rosmsg::stereo_msgs::DisparityImage::f
yarp::conf::float32_t f
Definition: DisparityImage.h:65
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::rosmsg::stereo_msgs::DisparityImage
Definition: DisparityImage.h:61
yarp::rosmsg::stereo_msgs::DisparityImage::delta_d
yarp::conf::float32_t delta_d
Definition: DisparityImage.h:70
yarp::rosmsg::stereo_msgs::DisparityImage::writeBottle
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
Definition: DisparityImage.h:229
WireTypes.h
BOTTLE_TAG_LIST
#define BOTTLE_TAG_LIST
Definition: Bottle.h:30
yarp::os::idl::WireReader::expectFloat32
yarp::conf::float32_t expectFloat32()
Definition: WireReader.h:113
yarp::rosmsg::stereo_msgs::DisparityImage::read
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: DisparityImage.h:188
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::stereo_msgs::DisparityImage::header
yarp::rosmsg::std_msgs::Header header
Definition: DisparityImage.h:63
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
Wire.h
yarp::rosmsg::stereo_msgs::DisparityImage::typeName
static constexpr const char * typeName
Definition: DisparityImage.h:286
yarp::rosmsg::stereo_msgs::DisparityImage::bottleStyle
yarp::os::idl::BottleStyle< yarp::rosmsg::stereo_msgs::DisparityImage > bottleStyle
Definition: DisparityImage.h:283
yarp::rosmsg::sensor_msgs::Image::clear
void clear()
Definition: Image.h:78
yarp::rosmsg::stereo_msgs::DisparityImage::DisparityImage
DisparityImage()
Definition: DisparityImage.h:72
yarp::rosmsg::stereo_msgs::DisparityImage::getType
yarp::os::Type getType() const override
Definition: DisparityImage.h:394
yarp::rosmsg::sensor_msgs::Image
Definition: Image.h:57
yarp::rosmsg::stereo_msgs::DisparityImage::readBare
bool readBare(yarp::os::ConnectionReader &connection) override
Definition: DisparityImage.h:111
yarp::rosmsg::stereo_msgs::DisparityImage::min_disparity
yarp::conf::float32_t min_disparity
Definition: DisparityImage.h:68
yarp::os::ConnectionWriter::isError
virtual bool isError() const =0
BOTTLE_TAG_FLOAT32
#define BOTTLE_TAG_FLOAT32
Definition: Bottle.h:26
yarp::rosmsg::stereo_msgs::DisparityImage::image
yarp::rosmsg::sensor_msgs::Image image
Definition: DisparityImage.h:64
yarp::os::Type::byName
static Type byName(const char *name)
Definition: Type.cpp:174
yarp::os::Type::addProperty
Type & addProperty(const char *key, const Value &val)
Definition: Type.cpp:137
yarp::rosmsg::stereo_msgs::DisparityImage::write
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: DisparityImage.h:274
Type.h
yarp::rosmsg::sensor_msgs::Image::read
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: Image.h:182
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::Image::write
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: Image.h:263
yarp::rosmsg::stereo_msgs::DisparityImage::typeText
static constexpr const char * typeText
Definition: DisparityImage.h:292
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::stereo_msgs::DisparityImage::rosStyle
yarp::os::idl::BareStyle< yarp::rosmsg::stereo_msgs::DisparityImage > rosStyle
Definition: DisparityImage.h:282
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::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::stereo_msgs::DisparityImage::readBottle
bool readBottle(yarp::os::ConnectionReader &connection) override
Definition: DisparityImage.h:146
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::conf::float32_t
float float32_t
Definition: numeric.h:50
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::stereo_msgs::DisparityImage::clear
void clear()
Definition: DisparityImage.h:84
yarp::os::idl::BareStyle
Definition: BareStyle.h:22
yarp::rosmsg::stereo_msgs::DisparityImage::valid_window
yarp::rosmsg::sensor_msgs::RegionOfInterest valid_window
Definition: DisparityImage.h:67
yarp::rosmsg::stereo_msgs::DisparityImage::typeChecksum
static constexpr const char * typeChecksum
Definition: DisparityImage.h:289
RegionOfInterest.h
yarp::rosmsg::stereo_msgs::DisparityImage::writeBare
bool writeBare(yarp::os::ConnectionWriter &connection) const override
Definition: DisparityImage.h:194
yarp::rosmsg::sensor_msgs::RegionOfInterest::clear
void clear()
Definition: RegionOfInterest.h:65
yarp
The main, catch-all namespace for YARP.
Definition: environment.h:18
stereo_msgs
Definition: DisparityImage.h:22
yarp::rosmsg::stereo_msgs::DisparityImage::max_disparity
yarp::conf::float32_t max_disparity
Definition: DisparityImage.h:69
yarp::os::ConnectionReader::expectFloat32
virtual yarp::conf::float32_t expectFloat32()=0
Read a 32-bit floating point number from the network connection.
yarp::os::Value
A single value (typically within a Bottle).
Definition: Value.h:47
Image.h
yarp::rosmsg::stereo_msgs::DisparityImage::T
yarp::conf::float32_t T
Definition: DisparityImage.h:66
yarp::rosmsg::std_msgs::Header
Definition: Header.h:45
yarp::os::idl::WireReader::readListHeader
bool readListHeader()
Definition: WireReader.cpp:470
yarp::os::idl::WirePortable::write
virtual bool write(const yarp::os::idl::WireWriter &writer) const
Definition: WirePortable.cpp:20