39#ifndef YARP_ROSMSG_sensor_msgs_PointCloud2_h
40#define YARP_ROSMSG_sensor_msgs_PointCloud2_h
60 std::vector<yarp::rosmsg::sensor_msgs::PointField>
fields;
64 std::vector<std::uint8_t>
data;
126 for (
int i=0; i<len; i++) {
146 if (len > 0 && !connection.
expectBlock((
char*)&
data[0],
sizeof(std::uint8_t)*len)) {
183 for (
int i=0; i<len; i++) {
204 for (
int i=0; i<len; i++) {
236 for (
size_t i=0; i<
fields.size(); i++) {
284 for (
size_t i=0; i<
fields.size(); i++) {
305 for (
size_t i=0; i<
data.size(); i++) {
330 static constexpr const char*
typeName =
"sensor_msgs/PointCloud2";
333 static constexpr const char*
typeChecksum =
"1158d486dd51d683ce2f1be655c3c181";
337# This message holds a collection of N-dimensional points, which may\n\
338# contain additional information such as normals, intensity, etc. The\n\
339# point data is stored as a binary blob, its layout described by the\n\
340# contents of the \"fields\" array.\n\
342# The point cloud data may be organized 2d (image-like) or 1d\n\
343# (unordered). Point clouds organized as 2d images may be produced by\n\
344# camera depth sensors such as stereo or time-of-flight.\n\
346# Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\
350# 2D structure of the point cloud. If the cloud is unordered, height is\n\
351# 1 and width is the length of the point cloud.\n\
355# Describes the channels and their layout in the binary data blob.\n\
356PointField[] fields\n\
358bool is_bigendian # Is this data bigendian?\n\
359uint32 point_step # Length of a point in bytes\n\
360uint32 row_step # Length of a row in bytes\n\
361uint8[] data # Actual point data, size is (row_step*height)\n\
363bool is_dense # True if there are no invalid points\n\
365================================================================================\n\
366MSG: std_msgs/Header\n\
367# Standard metadata for higher-level stamped data types.\n\
368# This is generally used to communicate timestamped data \n\
369# in a particular coordinate frame.\n\
371# sequence ID: consecutively increasing ID \n\
373#Two-integer timestamp that is expressed as:\n\
374# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
375# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
376# time-handling sugar is provided by the client library\n\
378#Frame this data is associated with\n\
383================================================================================\n\
384MSG: sensor_msgs/PointField\n\
385# This message holds the description of one point entry in the\n\
386# PointCloud2 message format.\n\
396string name # Name of field\n\
397uint32 offset # Offset from start of point struct\n\
398uint8 datatype # Datatype enumeration, see above\n\
399uint32 count # How many elements in the field\n\
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.
virtual void appendBlock(const char *data, size_t len)=0
Send a block of data to the network connection.
static Type byName(const char *name)
Type & addProperty(const char *key, const Value &val)
A single value (typically within a Bottle).
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
virtual bool read(yarp::os::idl::WireReader &reader)
virtual bool write(const yarp::os::idl::WireWriter &writer) const
IDL-friendly connection reader.
std::int32_t expectInt32()
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
yarp::rosmsg::std_msgs::Header header
yarp::os::Type getType() const override
std::vector< std::uint8_t > data
bool writeBare(yarp::os::ConnectionWriter &connection) const override
static constexpr const char * typeChecksum
bool readBottle(yarp::os::ConnectionReader &connection) override
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::PointCloud2 > bottleStyle
static constexpr const char * typeName
static constexpr const char * typeText
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 readBare(yarp::os::ConnectionReader &connection) override
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::PointCloud2 > rosStyle
std::vector< yarp::rosmsg::sensor_msgs::PointField > fields
The main, catch-all namespace for YARP.