YARP
Yet Another Robot Platform
yarp::rosmsg::sensor_msgs::PointField Class Reference

#include <yarp/rosmsg/sensor_msgs/PointField.h>

+ Inheritance diagram for yarp::rosmsg::sensor_msgs::PointField:

Public Types

typedef yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::PointFieldrosStyle
 
typedef yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::PointFieldbottleStyle
 

Public Member Functions

 PointField ()
 
void clear ()
 
bool readBare (yarp::os::ConnectionReader &connection) override
 
bool readBottle (yarp::os::ConnectionReader &connection) override
 
bool read (yarp::os::ConnectionReader &connection) override
 Read this object from a network connection. More...
 
bool writeBare (yarp::os::ConnectionWriter &connection) const override
 
bool writeBottle (yarp::os::ConnectionWriter &connection) const override
 
bool write (yarp::os::ConnectionWriter &connection) const override
 Write this object to a network connection. More...
 
yarp::os::Type getType () const override
 
- Public Member Functions inherited from yarp::os::idl::WirePortable
virtual bool read (yarp::os::idl::WireReader &reader)
 
virtual bool write (const yarp::os::idl::WireWriter &writer) const
 
- Public Member Functions inherited from yarp::os::PortReader
virtual ~PortReader ()
 Destructor. More...
 
virtual Type getReadType () const
 
- Public Member Functions inherited from yarp::os::PortWriter
virtual ~PortWriter ()
 Destructor. More...
 
virtual void onCompletion () const
 This is called when the port has finished all writing operations. More...
 
virtual void onCommencement () const
 This is called when the port is about to begin writing operations. More...
 
virtual yarp::os::Type getWriteType () const
 

Public Attributes

std::string name
 
std::uint32_t offset
 
std::uint8_t datatype
 
std::uint32_t count
 

Static Public Attributes

static const std::uint8_t INT8 = 1
 
static const std::uint8_t UINT8 = 2
 
static const std::uint8_t INT16 = 3
 
static const std::uint8_t UINT16 = 4
 
static const std::uint8_t INT32 = 5
 
static const std::uint8_t UINT32 = 6
 
static const std::uint8_t FLOAT32 = 7
 
static const std::uint8_t FLOAT64 = 8
 
static constexpr const char * typeName = "sensor_msgs/PointField"
 
static constexpr const char * typeChecksum = "268eacb2962780ceac86cbd17e328150"
 
static constexpr const char * typeText
 

Additional Inherited Members

- Static Public Member Functions inherited from yarp::os::Portable
static bool copyPortable (const PortWriter &writer, PortReader &reader)
 Copy one portable to another, via writing and reading. More...
 

Detailed Description

Definition at line 43 of file PointField.h.

Member Typedef Documentation

◆ bottleStyle

◆ rosStyle

Constructor & Destructor Documentation

◆ PointField()

yarp::rosmsg::sensor_msgs::PointField::PointField ( )
inline

Definition at line 59 of file PointField.h.

Member Function Documentation

◆ clear()

void yarp::rosmsg::sensor_msgs::PointField::clear ( )
inline

Definition at line 67 of file PointField.h.

◆ getType()

yarp::os::Type yarp::rosmsg::sensor_msgs::PointField::getType ( ) const
inlineoverridevirtual

Reimplemented from yarp::os::Portable.

Definition at line 232 of file PointField.h.

◆ read()

bool yarp::rosmsg::sensor_msgs::PointField::read ( yarp::os::ConnectionReader reader)
inlineoverridevirtual

Read this object from a network connection.

Override this for your particular class.

Parameters
readeran interface to the network connection for reading
Returns
true iff the object is successfully read

Implements yarp::os::Portable.

Definition at line 145 of file PointField.h.

◆ readBare()

bool yarp::rosmsg::sensor_msgs::PointField::readBare ( yarp::os::ConnectionReader connection)
inlineoverridevirtual

Reimplemented from yarp::os::idl::WirePortable.

Definition at line 98 of file PointField.h.

◆ readBottle()

bool yarp::rosmsg::sensor_msgs::PointField::readBottle ( yarp::os::ConnectionReader connection)
inlineoverridevirtual

Reimplemented from yarp::os::idl::WirePortable.

Definition at line 119 of file PointField.h.

◆ write()

bool yarp::rosmsg::sensor_msgs::PointField::write ( yarp::os::ConnectionWriter writer) const
inlineoverridevirtual

Write this object to a network connection.

Override this for your particular class. Be aware that depending on the nature of the connections a port has, and what protocol they use, and how efficient the YARP implementation is, this method may be called once, twice, or many times, as the result of a single call to Port::write

Parameters
writeran interface to the network connection for writing
Returns
true iff the object is successfully written

Implements yarp::os::Portable.

Definition at line 196 of file PointField.h.

◆ writeBare()

bool yarp::rosmsg::sensor_msgs::PointField::writeBare ( yarp::os::ConnectionWriter connection) const
inlineoverridevirtual

Reimplemented from yarp::os::idl::WirePortable.

Definition at line 151 of file PointField.h.

◆ writeBottle()

bool yarp::rosmsg::sensor_msgs::PointField::writeBottle ( yarp::os::ConnectionWriter connection) const
inlineoverridevirtual

Reimplemented from yarp::os::idl::WirePortable.

Definition at line 169 of file PointField.h.

Member Data Documentation

◆ count

std::uint32_t yarp::rosmsg::sensor_msgs::PointField::count

Definition at line 57 of file PointField.h.

◆ datatype

std::uint8_t yarp::rosmsg::sensor_msgs::PointField::datatype

Definition at line 56 of file PointField.h.

◆ FLOAT32

const std::uint8_t yarp::rosmsg::sensor_msgs::PointField::FLOAT32 = 7
static

Definition at line 52 of file PointField.h.

◆ FLOAT64

const std::uint8_t yarp::rosmsg::sensor_msgs::PointField::FLOAT64 = 8
static

Definition at line 53 of file PointField.h.

◆ INT16

const std::uint8_t yarp::rosmsg::sensor_msgs::PointField::INT16 = 3
static

Definition at line 48 of file PointField.h.

◆ INT32

const std::uint8_t yarp::rosmsg::sensor_msgs::PointField::INT32 = 5
static

Definition at line 50 of file PointField.h.

◆ INT8

const std::uint8_t yarp::rosmsg::sensor_msgs::PointField::INT8 = 1
static

Definition at line 46 of file PointField.h.

◆ name

std::string yarp::rosmsg::sensor_msgs::PointField::name

Definition at line 54 of file PointField.h.

◆ offset

std::uint32_t yarp::rosmsg::sensor_msgs::PointField::offset

Definition at line 55 of file PointField.h.

◆ typeChecksum

constexpr const char* yarp::rosmsg::sensor_msgs::PointField::typeChecksum = "268eacb2962780ceac86cbd17e328150"
staticconstexpr

Definition at line 211 of file PointField.h.

◆ typeName

constexpr const char* yarp::rosmsg::sensor_msgs::PointField::typeName = "sensor_msgs/PointField"
staticconstexpr

Definition at line 208 of file PointField.h.

◆ typeText

constexpr const char* yarp::rosmsg::sensor_msgs::PointField::typeText
staticconstexpr
Initial value:
= "\
# This message holds the description of one point entry in the\n\
# PointCloud2 message format.\n\
uint8 INT8 = 1\n\
uint8 UINT8 = 2\n\
uint8 INT16 = 3\n\
uint8 UINT16 = 4\n\
uint8 INT32 = 5\n\
uint8 UINT32 = 6\n\
uint8 FLOAT32 = 7\n\
uint8 FLOAT64 = 8\n\
\n\
string name # Name of field\n\
uint32 offset # Offset from start of point struct\n\
uint8 datatype # Datatype enumeration, see above\n\
uint32 count # How many elements in the field\n\
"

Definition at line 214 of file PointField.h.

◆ UINT16

const std::uint8_t yarp::rosmsg::sensor_msgs::PointField::UINT16 = 4
static

Definition at line 49 of file PointField.h.

◆ UINT32

const std::uint8_t yarp::rosmsg::sensor_msgs::PointField::UINT32 = 6
static

Definition at line 51 of file PointField.h.

◆ UINT8

const std::uint8_t yarp::rosmsg::sensor_msgs::PointField::UINT8 = 2
static

Definition at line 47 of file PointField.h.


The documentation for this class was generated from the following file: