|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
42 #ifndef YARP_ROSMSG_sensor_msgs_PointCloud2_h
43 #define YARP_ROSMSG_sensor_msgs_PointCloud2_h
63 std::vector<yarp::rosmsg::sensor_msgs::PointField>
fields;
67 std::vector<std::uint8_t>
data;
129 for (
int i=0; i<len; i++) {
149 if (len > 0 && !connection.
expectBlock((
char*)&
data[0],
sizeof(std::uint8_t)*len)) {
186 for (
int i=0; i<len; i++) {
207 for (
int i=0; i<len; i++) {
239 for (
size_t i=0; i<
fields.size(); i++) {
287 for (
size_t i=0; i<
fields.size(); i++) {
308 for (
size_t i=0; i<
data.size(); i++) {
333 static constexpr
const char*
typeName =
"sensor_msgs/PointCloud2";
336 static constexpr
const char*
typeChecksum =
"1158d486dd51d683ce2f1be655c3c181";
340 # This message holds a collection of N-dimensional points, which may\n\
341 # contain additional information such as normals, intensity, etc. The\n\
342 # point data is stored as a binary blob, its layout described by the\n\
343 # contents of the \"fields\" array.\n\
345 # The point cloud data may be organized 2d (image-like) or 1d\n\
346 # (unordered). Point clouds organized as 2d images may be produced by\n\
347 # camera depth sensors such as stereo or time-of-flight.\n\
349 # Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\
353 # 2D structure of the point cloud. If the cloud is unordered, height is\n\
354 # 1 and width is the length of the point cloud.\n\
358 # Describes the channels and their layout in the binary data blob.\n\
359 PointField[] fields\n\
361 bool is_bigendian # Is this data bigendian?\n\
362 uint32 point_step # Length of a point in bytes\n\
363 uint32 row_step # Length of a row in bytes\n\
364 uint8[] data # Actual point data, size is (row_step*height)\n\
366 bool is_dense # True if there are no invalid points\n\
368 ================================================================================\n\
369 MSG: std_msgs/Header\n\
370 # Standard metadata for higher-level stamped data types.\n\
371 # This is generally used to communicate timestamped data \n\
372 # in a particular coordinate frame.\n\
374 # sequence ID: consecutively increasing ID \n\
376 #Two-integer timestamp that is expressed as:\n\
377 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
378 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
379 # time-handling sugar is provided by the client library\n\
381 #Frame this data is associated with\n\
386 ================================================================================\n\
387 MSG: sensor_msgs/PointField\n\
388 # This message holds the description of one point entry in the\n\
389 # PointCloud2 message format.\n\
399 string name # Name of field\n\
400 uint32 offset # Offset from start of point struct\n\
401 uint8 datatype # Datatype enumeration, see above\n\
402 uint32 count # How many elements in the field\n\
418 #endif // YARP_ROSMSG_sensor_msgs_PointCloud2_h
bool writeBare(yarp::os::ConnectionWriter &connection) const override
yarp::os::Type getType() const override
virtual void appendBlock(const char *data, size_t len)=0
Send a block of data to the network connection.
static constexpr const char * typeName
static constexpr const char * typeText
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
static constexpr const char * typeChecksum
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.
std::vector< yarp::rosmsg::sensor_msgs::PointField > fields
bool readBare(yarp::os::ConnectionReader &connection) override
virtual std::int8_t expectInt8()=0
Read a 8-bit integer from the network connection.
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.
bool readBottle(yarp::os::ConnectionReader &connection) override
Type & addProperty(const char *key, const Value &val)
An interface for writing to a network connection.
virtual bool isError() const =0
virtual bool convertTextMode()=0
Reads in a standard description in text mode, and converts it to a standard description in binary.
yarp::rosmsg::std_msgs::Header header
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.
virtual bool convertTextMode()=0
Converts a standard description in binary into a textual description, if the connection is in text-mo...
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
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()
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::PointCloud2 > bottleStyle
The main, catch-all namespace for YARP.
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.
A single value (typically within a Bottle).
std::vector< std::uint8_t > data
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::PointCloud2 > rosStyle
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
virtual bool write(const yarp::os::idl::WireWriter &writer) const