|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
20 #ifndef YARP_ROSMSG_nav_msgs_GridCells_h
21 #define YARP_ROSMSG_nav_msgs_GridCells_h
41 std::vector<yarp::rosmsg::geometry_msgs::Point>
cells;
82 for (
int i=0; i<len; i++) {
116 for (
int i=0; i<len; i++) {
147 for (
size_t i=0; i<
cells.size(); i++) {
177 for (
size_t i=0; i<
cells.size(); i++) {
200 static constexpr
const char*
typeName =
"nav_msgs/GridCells";
203 static constexpr
const char*
typeChecksum =
"b9e4f5df6d28e272ebde00a3994830f5";
207 #an array of cells in a 2D grid\n\
209 float32 cell_width\n\
210 float32 cell_height\n\
211 geometry_msgs/Point[] cells\n\
213 ================================================================================\n\
214 MSG: std_msgs/Header\n\
215 # Standard metadata for higher-level stamped data types.\n\
216 # This is generally used to communicate timestamped data \n\
217 # in a particular coordinate frame.\n\
219 # sequence ID: consecutively increasing ID \n\
221 #Two-integer timestamp that is expressed as:\n\
222 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
223 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
224 # time-handling sugar is provided by the client library\n\
226 #Frame this data is associated with\n\
231 ================================================================================\n\
232 MSG: geometry_msgs/Point\n\
233 # This contains the position of a point in free space\n\
252 #endif // YARP_ROSMSG_nav_msgs_GridCells_h
static constexpr const char * typeName
virtual void appendFloat32(yarp::conf::float32_t data)=0
Send a representation of a 32-bit floating point number to the network connection.
bool readBare(yarp::os::ConnectionReader &connection) override
yarp::conf::float32_t expectFloat32()
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
yarp::conf::float32_t cell_width
virtual bool read(yarp::os::idl::WireReader &reader)
virtual bool isBareMode() const =0
Check if the connection is bare mode.
yarp::conf::float32_t cell_height
yarp::rosmsg::std_msgs::Header header
virtual bool isError() const =0
yarp::os::idl::BottleStyle< yarp::rosmsg::nav_msgs::GridCells > bottleStyle
yarp::os::Type getType() const override
#define BOTTLE_TAG_FLOAT32
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)
bool readBottle(yarp::os::ConnectionReader &connection) override
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
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.
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::BareStyle< yarp::rosmsg::nav_msgs::GridCells > rosStyle
std::vector< yarp::rosmsg::geometry_msgs::Point > cells
static constexpr const char * typeText
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
static constexpr const char * typeChecksum
The main, catch-all namespace for YARP.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
virtual yarp::conf::float32_t expectFloat32()=0
Read a 32-bit floating point number from the network connection.
A single value (typically within a Bottle).
virtual bool write(const yarp::os::idl::WireWriter &writer) const