|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
18 #ifndef YARP_ROSMSG_geometry_msgs_PolygonStamped_h
19 #define YARP_ROSMSG_geometry_msgs_PolygonStamped_h
144 static constexpr
const char*
typeName =
"geometry_msgs/PolygonStamped";
147 static constexpr
const char*
typeChecksum =
"c6be8f7dc3bee7fe9e8d296070f53340";
151 # This represents a Polygon with reference coordinate frame and timestamp\n\
155 ================================================================================\n\
156 MSG: std_msgs/Header\n\
157 # Standard metadata for higher-level stamped data types.\n\
158 # This is generally used to communicate timestamped data \n\
159 # in a particular coordinate frame.\n\
161 # sequence ID: consecutively increasing ID \n\
163 #Two-integer timestamp that is expressed as:\n\
164 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
165 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
166 # time-handling sugar is provided by the client library\n\
168 #Frame this data is associated with\n\
173 ================================================================================\n\
174 MSG: geometry_msgs/Polygon\n\
175 #A specification of a polygon where the first and last points are assumed to be connected\n\
178 ================================================================================\n\
179 MSG: geometry_msgs/Point32\n\
180 # This contains the position of a point in free space(with 32 bits of precision).\n\
181 # It is recommeded to use Point wherever possible instead of Point32. \n\
183 # This recommendation is to promote interoperability. \n\
185 # This message is designed to take up less space when sending\n\
186 # lots of points at once, as in the case of a PointCloud. \n\
206 #endif // YARP_ROSMSG_geometry_msgs_PolygonStamped_h
static constexpr const char * typeChecksum
virtual bool read(yarp::os::idl::WireReader &reader)
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
virtual bool isBareMode() const =0
Check if the connection is bare mode.
bool readBottle(yarp::os::ConnectionReader &connection) override
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
yarp::rosmsg::std_msgs::Header header
virtual bool isError() const =0
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
static Type byName(const char *name)
Type & addProperty(const char *key, const Value &val)
An interface for writing to a network connection.
bool readBare(yarp::os::ConnectionReader &connection) override
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.
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.
static constexpr const char * typeName
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.
bool writeBare(yarp::os::ConnectionWriter &connection) const override
yarp::rosmsg::geometry_msgs::Polygon polygon
yarp::os::idl::BareStyle< yarp::rosmsg::geometry_msgs::PolygonStamped > rosStyle
The main, catch-all namespace for YARP.
static constexpr const char * typeText
yarp::os::Type getType() const override
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
yarp::os::idl::BottleStyle< yarp::rosmsg::geometry_msgs::PolygonStamped > bottleStyle
A single value (typically within a Bottle).
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
virtual bool write(const yarp::os::idl::WireWriter &writer) const