YARP
Yet Another Robot Platform
OccupancyGrid.h
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: BSD-3-Clause
4 */
5
6// This is an automatically generated file.
7
8// Generated from the following "nav_msgs/OccupancyGrid" msg definition:
9// # This represents a 2-D grid map, in which each cell represents the probability of
10// # occupancy.
11//
12// Header header
13//
14// #MetaData for the map
15// MapMetaData info
16//
17// # The map data, in row-major order, starting with (0,0). Occupancy
18// # probabilities are in the range [0,100]. Unknown is -1.
19// int8[] data
20// Instances of this class can be read and written with YARP ports,
21// using a ROS-compatible format.
22
23#ifndef YARP_ROSMSG_nav_msgs_OccupancyGrid_h
24#define YARP_ROSMSG_nav_msgs_OccupancyGrid_h
25
26#include <yarp/os/Wire.h>
27#include <yarp/os/Type.h>
29#include <string>
30#include <vector>
33
34namespace yarp {
35namespace rosmsg {
36namespace nav_msgs {
37
39{
40public:
43 std::vector<std::int8_t> data;
44
46 header(),
47 info(),
48 data()
49 {
50 }
51
52 void clear()
53 {
54 // *** header ***
55 header.clear();
56
57 // *** info ***
58 info.clear();
59
60 // *** data ***
61 data.clear();
62 }
63
64 bool readBare(yarp::os::ConnectionReader& connection) override
65 {
66 // *** header ***
67 if (!header.read(connection)) {
68 return false;
69 }
70
71 // *** info ***
72 if (!info.read(connection)) {
73 return false;
74 }
75
76 // *** data ***
77 int len = connection.expectInt32();
78 data.resize(len);
79 if (len > 0 && !connection.expectBlock((char*)&data[0], sizeof(std::int8_t)*len)) {
80 return false;
81 }
82
83 return !connection.isError();
84 }
85
86 bool readBottle(yarp::os::ConnectionReader& connection) override
87 {
88 connection.convertTextMode();
89 yarp::os::idl::WireReader reader(connection);
90 if (!reader.readListHeader(3)) {
91 return false;
92 }
93
94 // *** header ***
95 if (!header.read(connection)) {
96 return false;
97 }
98
99 // *** info ***
100 if (!info.read(connection)) {
101 return false;
102 }
103
104 // *** data ***
105 if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_INT8)) {
106 return false;
107 }
108 int len = connection.expectInt32();
109 data.resize(len);
110 for (int i=0; i<len; i++) {
111 data[i] = (std::int8_t)connection.expectInt8();
112 }
113
114 return !connection.isError();
115 }
116
118 bool read(yarp::os::ConnectionReader& connection) override
119 {
120 return (connection.isBareMode() ? readBare(connection)
121 : readBottle(connection));
122 }
123
124 bool writeBare(yarp::os::ConnectionWriter& connection) const override
125 {
126 // *** header ***
127 if (!header.write(connection)) {
128 return false;
129 }
130
131 // *** info ***
132 if (!info.write(connection)) {
133 return false;
134 }
135
136 // *** data ***
137 connection.appendInt32(data.size());
138 if (data.size()>0) {
139 connection.appendExternalBlock((char*)&data[0], sizeof(std::int8_t)*data.size());
140 }
141
142 return !connection.isError();
143 }
144
145 bool writeBottle(yarp::os::ConnectionWriter& connection) const override
146 {
147 connection.appendInt32(BOTTLE_TAG_LIST);
148 connection.appendInt32(3);
149
150 // *** header ***
151 if (!header.write(connection)) {
152 return false;
153 }
154
155 // *** info ***
156 if (!info.write(connection)) {
157 return false;
158 }
159
160 // *** data ***
162 connection.appendInt32(data.size());
163 for (size_t i=0; i<data.size(); i++) {
164 connection.appendInt8(data[i]);
165 }
166
167 connection.convertTextMode();
168 return !connection.isError();
169 }
170
172 bool write(yarp::os::ConnectionWriter& connection) const override
173 {
174 return (connection.isBareMode() ? writeBare(connection)
175 : writeBottle(connection));
176 }
177
178 // This class will serialize ROS style or YARP style depending on protocol.
179 // If you need to force a serialization style, use one of these classes:
182
183 // The name for this message, ROS will need this
184 static constexpr const char* typeName = "nav_msgs/OccupancyGrid";
185
186 // The checksum for this message, ROS will need this
187 static constexpr const char* typeChecksum = "3381f2d731d4076ec5c71b0759edbe4e";
188
189 // The source text for this message, ROS will need this
190 static constexpr const char* typeText = "\
191# This represents a 2-D grid map, in which each cell represents the probability of\n\
192# occupancy.\n\
193\n\
194Header header \n\
195\n\
196#MetaData for the map\n\
197MapMetaData info\n\
198\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\
201int8[] data\n\
202\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\
208# \n\
209# sequence ID: consecutively increasing ID \n\
210uint32 seq\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\
215time stamp\n\
216#Frame this data is associated with\n\
217# 0: no frame\n\
218# 1: global frame\n\
219string frame_id\n\
220\n\
221================================================================================\n\
222MSG: nav_msgs/MapMetaData\n\
223# This hold basic information about the characterists of the OccupancyGrid\n\
224\n\
225# The time at which the map was loaded\n\
226time map_load_time\n\
227# The map resolution [m/cell]\n\
228float32 resolution\n\
229# Map width [cells]\n\
230uint32 width\n\
231# Map height [cells]\n\
232uint32 height\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\
239Point position\n\
240Quaternion orientation\n\
241\n\
242================================================================================\n\
243MSG: geometry_msgs/Point\n\
244# This contains the position of a point in free space\n\
245float64 x\n\
246float64 y\n\
247float64 z\n\
248\n\
249================================================================================\n\
250MSG: geometry_msgs/Quaternion\n\
251# This represents an orientation in free space in quaternion form.\n\
252\n\
253float64 x\n\
254float64 y\n\
255float64 z\n\
256float64 w\n\
257";
258
259 yarp::os::Type getType() const override
260 {
263 typ.addProperty("message_definition", yarp::os::Value(typeText));
264 return typ;
265 }
266};
267
268} // namespace nav_msgs
269} // namespace rosmsg
270} // namespace yarp
271
272#endif // YARP_ROSMSG_nav_msgs_OccupancyGrid_h
#define BOTTLE_TAG_INT8
Definition: Bottle.h:19
#define BOTTLE_TAG_LIST
Definition: Bottle.h:28
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)
Definition: Type.cpp:171
Type & addProperty(const char *key, const Value &val)
Definition: Type.cpp:134
A single value (typically within a Bottle).
Definition: Value.h:43
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
Definition: WirePortable.h:21
virtual bool read(yarp::os::idl::WireReader &reader)
virtual bool write(const yarp::os::idl::WireWriter &writer) const
IDL-friendly connection reader.
Definition: WireReader.h:27
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: MapMetaData.h:192
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: MapMetaData.h:130
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
Definition: OccupancyGrid.h:43
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
yarp::rosmsg::nav_msgs::MapMetaData info
Definition: OccupancyGrid.h:42
yarp::os::idl::BareStyle< yarp::rosmsg::nav_msgs::OccupancyGrid > rosStyle
bool readBare(yarp::os::ConnectionReader &connection) override
Definition: OccupancyGrid.h:64
yarp::rosmsg::std_msgs::Header header
Definition: OccupancyGrid.h:41
bool readBottle(yarp::os::ConnectionReader &connection) override
Definition: OccupancyGrid.h:86
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
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: Header.h:159
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: Header.h:112
The main, catch-all namespace for YARP.
Definition: dirs.h:16