YARP
Yet Another Robot Platform
Image.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/Image" msg definition:
9 // # This message contains an uncompressed image
10 // # (0, 0) is at top-left corner of image
11 // #
12 //
13 // Header header # Header timestamp should be acquisition time of image
14 // # Header frame_id should be optical frame of camera
15 // # origin of frame should be optical center of cameara
16 // # +x should point to the right in the image
17 // # +y should point down in the image
18 // # +z should point into to plane of the image
19 // # If the frame_id here and the frame_id of the CameraInfo
20 // # message associated with the image conflict
21 // # the behavior is undefined
22 //
23 // uint32 height # image height, that is, number of rows
24 // uint32 width # image width, that is, number of columns
25 //
26 // # The legal values for encoding are in file src/image_encodings.cpp
27 // # If you want to standardize a new string format, join
28 // # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
29 //
30 // string encoding # Encoding of pixels -- channel meaning, ordering, size
31 // # taken from the list of strings in include/sensor_msgs/image_encodings.h
32 //
33 // uint8 is_bigendian # is this data bigendian?
34 // uint32 step # Full row length in bytes
35 // uint8[] data # actual matrix data, size is (step * rows)
36 // Instances of this class can be read and written with YARP ports,
37 // using a ROS-compatible format.
38 
39 #ifndef YARP_ROSMSG_sensor_msgs_Image_h
40 #define YARP_ROSMSG_sensor_msgs_Image_h
41 
42 #include <yarp/os/Wire.h>
43 #include <yarp/os/Type.h>
44 #include <yarp/os/idl/WireTypes.h>
45 #include <string>
46 #include <vector>
48 
49 namespace yarp {
50 namespace rosmsg {
51 namespace sensor_msgs {
52 
54 {
55 public:
57  std::uint32_t height;
58  std::uint32_t width;
59  std::string encoding;
60  std::uint8_t is_bigendian;
61  std::uint32_t step;
62  std::vector<std::uint8_t> data;
63 
64  Image() :
65  header(),
66  height(0),
67  width(0),
68  encoding(""),
69  is_bigendian(0),
70  step(0),
71  data()
72  {
73  }
74 
75  void clear()
76  {
77  // *** header ***
78  header.clear();
79 
80  // *** height ***
81  height = 0;
82 
83  // *** width ***
84  width = 0;
85 
86  // *** encoding ***
87  encoding = "";
88 
89  // *** is_bigendian ***
90  is_bigendian = 0;
91 
92  // *** step ***
93  step = 0;
94 
95  // *** data ***
96  data.clear();
97  }
98 
99  bool readBare(yarp::os::ConnectionReader& connection) override
100  {
101  // *** header ***
102  if (!header.read(connection)) {
103  return false;
104  }
105 
106  // *** height ***
107  height = connection.expectInt32();
108 
109  // *** width ***
110  width = connection.expectInt32();
111 
112  // *** encoding ***
113  int len = connection.expectInt32();
114  encoding.resize(len);
115  if (!connection.expectBlock((char*)encoding.c_str(), len)) {
116  return false;
117  }
118 
119  // *** is_bigendian ***
120  is_bigendian = connection.expectInt8();
121 
122  // *** step ***
123  step = connection.expectInt32();
124 
125  // *** data ***
126  len = connection.expectInt32();
127  data.resize(len);
128  if (len > 0 && !connection.expectBlock((char*)&data[0], sizeof(std::uint8_t)*len)) {
129  return false;
130  }
131 
132  return !connection.isError();
133  }
134 
135  bool readBottle(yarp::os::ConnectionReader& connection) override
136  {
137  connection.convertTextMode();
138  yarp::os::idl::WireReader reader(connection);
139  if (!reader.readListHeader(7)) {
140  return false;
141  }
142 
143  // *** header ***
144  if (!header.read(connection)) {
145  return false;
146  }
147 
148  // *** height ***
149  height = reader.expectInt32();
150 
151  // *** width ***
152  width = reader.expectInt32();
153 
154  // *** encoding ***
155  if (!reader.readString(encoding)) {
156  return false;
157  }
158 
159  // *** is_bigendian ***
160  is_bigendian = reader.expectInt8();
161 
162  // *** step ***
163  step = reader.expectInt32();
164 
165  // *** data ***
166  if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_INT8)) {
167  return false;
168  }
169  int len = connection.expectInt32();
170  data.resize(len);
171  for (int i=0; i<len; i++) {
172  data[i] = (std::uint8_t)connection.expectInt8();
173  }
174 
175  return !connection.isError();
176  }
177 
179  bool read(yarp::os::ConnectionReader& connection) override
180  {
181  return (connection.isBareMode() ? readBare(connection)
182  : readBottle(connection));
183  }
184 
185  bool writeBare(yarp::os::ConnectionWriter& connection) const override
186  {
187  // *** header ***
188  if (!header.write(connection)) {
189  return false;
190  }
191 
192  // *** height ***
193  connection.appendInt32(height);
194 
195  // *** width ***
196  connection.appendInt32(width);
197 
198  // *** encoding ***
199  connection.appendInt32(encoding.length());
200  connection.appendExternalBlock((char*)encoding.c_str(), encoding.length());
201 
202  // *** is_bigendian ***
203  connection.appendInt8(is_bigendian);
204 
205  // *** step ***
206  connection.appendInt32(step);
207 
208  // *** data ***
209  connection.appendInt32(data.size());
210  if (data.size()>0) {
211  connection.appendExternalBlock((char*)&data[0], sizeof(std::uint8_t)*data.size());
212  }
213 
214  return !connection.isError();
215  }
216 
217  bool writeBottle(yarp::os::ConnectionWriter& connection) const override
218  {
219  connection.appendInt32(BOTTLE_TAG_LIST);
220  connection.appendInt32(7);
221 
222  // *** header ***
223  if (!header.write(connection)) {
224  return false;
225  }
226 
227  // *** height ***
228  connection.appendInt32(BOTTLE_TAG_INT32);
229  connection.appendInt32(height);
230 
231  // *** width ***
232  connection.appendInt32(BOTTLE_TAG_INT32);
233  connection.appendInt32(width);
234 
235  // *** encoding ***
236  connection.appendInt32(BOTTLE_TAG_STRING);
237  connection.appendInt32(encoding.length());
238  connection.appendExternalBlock((char*)encoding.c_str(), encoding.length());
239 
240  // *** is_bigendian ***
241  connection.appendInt32(BOTTLE_TAG_INT8);
242  connection.appendInt8(is_bigendian);
243 
244  // *** step ***
245  connection.appendInt32(BOTTLE_TAG_INT32);
246  connection.appendInt32(step);
247 
248  // *** data ***
250  connection.appendInt32(data.size());
251  for (size_t i=0; i<data.size(); i++) {
252  connection.appendInt8(data[i]);
253  }
254 
255  connection.convertTextMode();
256  return !connection.isError();
257  }
258 
260  bool write(yarp::os::ConnectionWriter& connection) const override
261  {
262  return (connection.isBareMode() ? writeBare(connection)
263  : writeBottle(connection));
264  }
265 
266  // This class will serialize ROS style or YARP style depending on protocol.
267  // If you need to force a serialization style, use one of these classes:
270 
271  // The name for this message, ROS will need this
272  static constexpr const char* typeName = "sensor_msgs/Image";
273 
274  // The checksum for this message, ROS will need this
275  static constexpr const char* typeChecksum = "060021388200f6f0f447d0fcd9c64743";
276 
277  // The source text for this message, ROS will need this
278  static constexpr const char* typeText = "\
279 # This message contains an uncompressed image\n\
280 # (0, 0) is at top-left corner of image\n\
281 #\n\
282 \n\
283 Header header # Header timestamp should be acquisition time of image\n\
284  # Header frame_id should be optical frame of camera\n\
285  # origin of frame should be optical center of cameara\n\
286  # +x should point to the right in the image\n\
287  # +y should point down in the image\n\
288  # +z should point into to plane of the image\n\
289  # If the frame_id here and the frame_id of the CameraInfo\n\
290  # message associated with the image conflict\n\
291  # the behavior is undefined\n\
292 \n\
293 uint32 height # image height, that is, number of rows\n\
294 uint32 width # image width, that is, number of columns\n\
295 \n\
296 # The legal values for encoding are in file src/image_encodings.cpp\n\
297 # If you want to standardize a new string format, join\n\
298 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\
299 \n\
300 string encoding # Encoding of pixels -- channel meaning, ordering, size\n\
301  # taken from the list of strings in include/sensor_msgs/image_encodings.h\n\
302 \n\
303 uint8 is_bigendian # is this data bigendian?\n\
304 uint32 step # Full row length in bytes\n\
305 uint8[] data # actual matrix data, size is (step * rows)\n\
306 \n\
307 ================================================================================\n\
308 MSG: std_msgs/Header\n\
309 # Standard metadata for higher-level stamped data types.\n\
310 # This is generally used to communicate timestamped data \n\
311 # in a particular coordinate frame.\n\
312 # \n\
313 # sequence ID: consecutively increasing ID \n\
314 uint32 seq\n\
315 #Two-integer timestamp that is expressed as:\n\
316 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
317 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
318 # time-handling sugar is provided by the client library\n\
319 time stamp\n\
320 #Frame this data is associated with\n\
321 # 0: no frame\n\
322 # 1: global frame\n\
323 string frame_id\n\
324 ";
325 
326  yarp::os::Type getType() const override
327  {
329  typ.addProperty("md5sum", yarp::os::Value(typeChecksum));
330  typ.addProperty("message_definition", yarp::os::Value(typeText));
331  return typ;
332  }
333 };
334 
335 } // namespace sensor_msgs
336 } // namespace rosmsg
337 } // namespace yarp
338 
339 #endif // YARP_ROSMSG_sensor_msgs_Image_h
#define BOTTLE_TAG_INT8
Definition: Bottle.h:19
#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 std::int8_t expectInt8()=0
Read a 8-bit integer 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 appendInt8(std::int8_t data)=0
Send a representation of a 8-bit integer to the network connection.
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.
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::int8_t expectInt8()
Definition: WireReader.h:80
std::int32_t expectInt32()
Definition: WireReader.h:92
std::vector< std::uint8_t > data
Definition: Image.h:62
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
Definition: Image.h:217
yarp::rosmsg::std_msgs::Header header
Definition: Image.h:56
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: Image.h:260
static constexpr const char * typeText
Definition: Image.h:278
yarp::os::Type getType() const override
Definition: Image.h:326
bool writeBare(yarp::os::ConnectionWriter &connection) const override
Definition: Image.h:185
bool readBare(yarp::os::ConnectionReader &connection) override
Definition: Image.h:99
static constexpr const char * typeName
Definition: Image.h:272
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::Image > rosStyle
Definition: Image.h:268
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::Image > bottleStyle
Definition: Image.h:269
bool readBottle(yarp::os::ConnectionReader &connection) override
Definition: Image.h:135
static constexpr const char * typeChecksum
Definition: Image.h:275
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: Image.h:179
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
The main, catch-all namespace for YARP.
Definition: dirs.h:16