23#ifndef YARP_ROSMSG_nav_msgs_OccupancyGrid_h
24#define YARP_ROSMSG_nav_msgs_OccupancyGrid_h
43 std::vector<std::int8_t>
data;
79 if (len > 0 && !connection.
expectBlock((
char*)&
data[0],
sizeof(std::int8_t)*len)) {
110 for (
int i=0; i<len; i++) {
163 for (
size_t i=0; i<
data.size(); i++) {
184 static constexpr const char*
typeName =
"nav_msgs/OccupancyGrid";
187 static constexpr const char*
typeChecksum =
"3381f2d731d4076ec5c71b0759edbe4e";
191# This represents a 2-D grid map, in which each cell represents the probability of\n\
196#MetaData for the map\n\
199# The map data, in row-major order, starting with (0,0). Occupancy\n\
200# probabilities are in the range [0,100]. Unknown is -1.\n\
203================================================================================\n\
204MSG: std_msgs/Header\n\
205# Standard metadata for higher-level stamped data types.\n\
206# This is generally used to communicate timestamped data \n\
207# in a particular coordinate frame.\n\
209# sequence ID: consecutively increasing ID \n\
211#Two-integer timestamp that is expressed as:\n\
212# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
213# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
214# time-handling sugar is provided by the client library\n\
216#Frame this data is associated with\n\
221================================================================================\n\
222MSG: nav_msgs/MapMetaData\n\
223# This hold basic information about the characterists of the OccupancyGrid\n\
225# The time at which the map was loaded\n\
227# The map resolution [m/cell]\n\
229# Map width [cells]\n\
231# Map height [cells]\n\
233# The origin of the map [m, m, rad]. This is the real-world pose of the\n\
234# cell (0,0) in the map.\n\
235geometry_msgs/Pose origin\n\
236================================================================================\n\
237MSG: geometry_msgs/Pose\n\
238# A representation of pose in free space, composed of position and orientation. \n\
240Quaternion orientation\n\
242================================================================================\n\
243MSG: geometry_msgs/Point\n\
244# This contains the position of a point in free space\n\
249================================================================================\n\
250MSG: geometry_msgs/Quaternion\n\
251# This represents an orientation in free space in quaternion form.\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.
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.
yarp::os::idl::BottleStyle< yarp::rosmsg::nav_msgs::OccupancyGrid > bottleStyle
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
static constexpr const char * typeName
bool writeBare(yarp::os::ConnectionWriter &connection) const override
std::vector< std::int8_t > data
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
yarp::rosmsg::nav_msgs::MapMetaData info
yarp::os::idl::BareStyle< yarp::rosmsg::nav_msgs::OccupancyGrid > rosStyle
bool readBare(yarp::os::ConnectionReader &connection) override
yarp::rosmsg::std_msgs::Header header
bool readBottle(yarp::os::ConnectionReader &connection) override
yarp::os::Type getType() const override
static constexpr const char * typeChecksum
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
static constexpr const char * typeText
The main, catch-all namespace for YARP.