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