|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
15 #ifndef YARP_ROSMSG_nav_msgs_GetMapReply_h
16 #define YARP_ROSMSG_nav_msgs_GetMapReply_h
115 static constexpr
const char*
typeName =
"nav_msgs/GetMapReply";
118 static constexpr
const char*
typeChecksum =
"6cdd0a18e0aff5b0a3ca2326a89b54ff";
123 ================================================================================\n\
124 MSG: nav_msgs/OccupancyGrid\n\
125 # This represents a 2-D grid map, in which each cell represents the probability of\n\
130 #MetaData for the map\n\
133 # The map data, in row-major order, starting with (0,0). Occupancy\n\
134 # probabilities are in the range [0,100]. Unknown is -1.\n\
137 ================================================================================\n\
138 MSG: std_msgs/Header\n\
139 # Standard metadata for higher-level stamped data types.\n\
140 # This is generally used to communicate timestamped data \n\
141 # in a particular coordinate frame.\n\
143 # sequence ID: consecutively increasing ID \n\
145 #Two-integer timestamp that is expressed as:\n\
146 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
147 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
148 # time-handling sugar is provided by the client library\n\
150 #Frame this data is associated with\n\
155 ================================================================================\n\
156 MSG: nav_msgs/MapMetaData\n\
157 # This hold basic information about the characterists of the OccupancyGrid\n\
159 # The time at which the map was loaded\n\
160 time map_load_time\n\
161 # The map resolution [m/cell]\n\
162 float32 resolution\n\
163 # Map width [cells]\n\
165 # Map height [cells]\n\
167 # The origin of the map [m, m, rad]. This is the real-world pose of the\n\
168 # cell (0,0) in the map.\n\
169 geometry_msgs/Pose origin\n\
170 ================================================================================\n\
171 MSG: geometry_msgs/Pose\n\
172 # A representation of pose in free space, composed of position and orientation. \n\
174 Quaternion orientation\n\
176 ================================================================================\n\
177 MSG: geometry_msgs/Point\n\
178 # This contains the position of a point in free space\n\
183 ================================================================================\n\
184 MSG: geometry_msgs/Quaternion\n\
185 # This represents an orientation in free space in quaternion form.\n\
206 #endif // YARP_ROSMSG_nav_msgs_GetMapReply_h
yarp::rosmsg::nav_msgs::OccupancyGrid map
virtual bool read(yarp::os::idl::WireReader &reader)
virtual bool isBareMode() const =0
Check if the connection is bare mode.
bool writeBare(yarp::os::ConnectionWriter &connection) const override
static constexpr const char * typeName
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
yarp::os::idl::BareStyle< yarp::rosmsg::nav_msgs::GetMapReply > rosStyle
static constexpr const char * typeText
bool readBottle(yarp::os::ConnectionReader &connection) override
virtual bool isError() const =0
static Type byName(const char *name)
Type & addProperty(const char *key, const Value &val)
An interface for writing to a network connection.
virtual bool isError() const =0
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
virtual bool convertTextMode()=0
Reads in a standard description in text mode, and converts it to a standard description in binary.
yarp::os::Type getType() const override
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
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...
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 readBare(yarp::os::ConnectionReader &connection) override
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
The main, catch-all namespace for YARP.
yarp::os::idl::BottleStyle< yarp::rosmsg::nav_msgs::GetMapReply > bottleStyle
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
A single value (typically within a Bottle).
static constexpr const char * typeChecksum
virtual bool write(const yarp::os::idl::WireWriter &writer) const