|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
42 #ifndef YARP_ROSMSG_sensor_msgs_Image_h
43 #define YARP_ROSMSG_sensor_msgs_Image_h
65 std::vector<std::uint8_t>
data;
131 if (len > 0 && !connection.
expectBlock((
char*)&
data[0],
sizeof(std::uint8_t)*len)) {
174 for (
int i=0; i<len; i++) {
254 for (
size_t i=0; i<
data.size(); i++) {
275 static constexpr
const char*
typeName =
"sensor_msgs/Image";
278 static constexpr
const char*
typeChecksum =
"060021388200f6f0f447d0fcd9c64743";
282 # This message contains an uncompressed image\n\
283 # (0, 0) is at top-left corner of image\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\
296 uint32 height # image height, that is, number of rows\n\
297 uint32 width # image width, that is, number of columns\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\
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\
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\
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\
316 # sequence ID: consecutively increasing ID \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\
323 #Frame this data is associated with\n\
342 #endif // YARP_ROSMSG_sensor_msgs_Image_h
bool readBottle(yarp::os::ConnectionReader &connection) override
static constexpr const char * typeText
std::vector< std::uint8_t > data
bool readString(std::string &str, bool *is_vocab=nullptr)
virtual bool read(yarp::os::idl::WireReader &reader)
virtual void appendInt8(std::int8_t data)=0
Send a representation of a 8-bit integer to the network connection.
virtual bool isBareMode() const =0
Check if the connection is bare mode.
#define BOTTLE_TAG_STRING
virtual std::int8_t expectInt8()=0
Read a 8-bit integer from the network connection.
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
std::uint8_t is_bigendian
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::Image > rosStyle
virtual bool isError() const =0
static Type byName(const char *name)
virtual std::int32_t expectInt32()=0
Read a 32-bit integer from the network connection.
Type & addProperty(const char *key, const Value &val)
static constexpr const char * typeName
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
An interface for writing to a network connection.
bool readBare(yarp::os::ConnectionReader &connection) override
virtual bool isError() const =0
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
yarp::rosmsg::std_msgs::Header header
virtual bool convertTextMode()=0
Reads in a standard description in text mode, and converts it to a standard description in binary.
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
virtual bool isBareMode() const =0
Check if the connection is bare mode.
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::Image > bottleStyle
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.
IDL-friendly connection reader.
An interface for reading from a network connection.
std::int32_t expectInt32()
The main, catch-all namespace for YARP.
bool writeBare(yarp::os::ConnectionWriter &connection) const override
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 expectBlock(char *data, size_t len)=0
Read a block of data from the network connection.
yarp::os::Type getType() const override
A single value (typically within a Bottle).
static constexpr const char * typeChecksum
virtual bool write(const yarp::os::idl::WireWriter &writer) const