YARP
Yet Another Robot Platform
OccupancyGrid.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  * All rights reserved.
4  *
5  * This software may be modified and distributed under the terms of the
6  * BSD-3-Clause license. See the accompanying LICENSE file for details.
7  */
8 
9 // This is an automatically generated file.
10 
11 // Generated from the following "nav_msgs/OccupancyGrid" msg definition:
12 // # This represents a 2-D grid map, in which each cell represents the probability of
13 // # occupancy.
14 //
15 // Header header
16 //
17 // #MetaData for the map
18 // MapMetaData info
19 //
20 // # The map data, in row-major order, starting with (0,0). Occupancy
21 // # probabilities are in the range [0,100]. Unknown is -1.
22 // int8[] data
23 // Instances of this class can be read and written with YARP ports,
24 // using a ROS-compatible format.
25 
26 #ifndef YARP_ROSMSG_nav_msgs_OccupancyGrid_h
27 #define YARP_ROSMSG_nav_msgs_OccupancyGrid_h
28 
29 #include <yarp/os/Wire.h>
30 #include <yarp/os/Type.h>
31 #include <yarp/os/idl/WireTypes.h>
32 #include <string>
33 #include <vector>
36 
37 namespace yarp {
38 namespace rosmsg {
39 namespace nav_msgs {
40 
42 {
43 public:
46  std::vector<std::int8_t> data;
47 
49  header(),
50  info(),
51  data()
52  {
53  }
54 
55  void clear()
56  {
57  // *** header ***
58  header.clear();
59 
60  // *** info ***
61  info.clear();
62 
63  // *** data ***
64  data.clear();
65  }
66 
67  bool readBare(yarp::os::ConnectionReader& connection) override
68  {
69  // *** header ***
70  if (!header.read(connection)) {
71  return false;
72  }
73 
74  // *** info ***
75  if (!info.read(connection)) {
76  return false;
77  }
78 
79  // *** data ***
80  int len = connection.expectInt32();
81  data.resize(len);
82  if (len > 0 && !connection.expectBlock((char*)&data[0], sizeof(std::int8_t)*len)) {
83  return false;
84  }
85 
86  return !connection.isError();
87  }
88 
89  bool readBottle(yarp::os::ConnectionReader& connection) override
90  {
91  connection.convertTextMode();
92  yarp::os::idl::WireReader reader(connection);
93  if (!reader.readListHeader(3)) {
94  return false;
95  }
96 
97  // *** header ***
98  if (!header.read(connection)) {
99  return false;
100  }
101 
102  // *** info ***
103  if (!info.read(connection)) {
104  return false;
105  }
106 
107  // *** data ***
108  if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_INT8)) {
109  return false;
110  }
111  int len = connection.expectInt32();
112  data.resize(len);
113  for (int i=0; i<len; i++) {
114  data[i] = (std::int8_t)connection.expectInt8();
115  }
116 
117  return !connection.isError();
118  }
119 
121  bool read(yarp::os::ConnectionReader& connection) override
122  {
123  return (connection.isBareMode() ? readBare(connection)
124  : readBottle(connection));
125  }
126 
127  bool writeBare(yarp::os::ConnectionWriter& connection) const override
128  {
129  // *** header ***
130  if (!header.write(connection)) {
131  return false;
132  }
133 
134  // *** info ***
135  if (!info.write(connection)) {
136  return false;
137  }
138 
139  // *** data ***
140  connection.appendInt32(data.size());
141  if (data.size()>0) {
142  connection.appendExternalBlock((char*)&data[0], sizeof(std::int8_t)*data.size());
143  }
144 
145  return !connection.isError();
146  }
147 
148  bool writeBottle(yarp::os::ConnectionWriter& connection) const override
149  {
150  connection.appendInt32(BOTTLE_TAG_LIST);
151  connection.appendInt32(3);
152 
153  // *** header ***
154  if (!header.write(connection)) {
155  return false;
156  }
157 
158  // *** info ***
159  if (!info.write(connection)) {
160  return false;
161  }
162 
163  // *** data ***
165  connection.appendInt32(data.size());
166  for (size_t i=0; i<data.size(); i++) {
167  connection.appendInt8(data[i]);
168  }
169 
170  connection.convertTextMode();
171  return !connection.isError();
172  }
173 
175  bool write(yarp::os::ConnectionWriter& connection) const override
176  {
177  return (connection.isBareMode() ? writeBare(connection)
178  : writeBottle(connection));
179  }
180 
181  // This class will serialize ROS style or YARP style depending on protocol.
182  // If you need to force a serialization style, use one of these classes:
185 
186  // The name for this message, ROS will need this
187  static constexpr const char* typeName = "nav_msgs/OccupancyGrid";
188 
189  // The checksum for this message, ROS will need this
190  static constexpr const char* typeChecksum = "3381f2d731d4076ec5c71b0759edbe4e";
191 
192  // The source text for this message, ROS will need this
193  static constexpr const char* typeText = "\
194 # This represents a 2-D grid map, in which each cell represents the probability of\n\
195 # occupancy.\n\
196 \n\
197 Header header \n\
198 \n\
199 #MetaData for the map\n\
200 MapMetaData info\n\
201 \n\
202 # The map data, in row-major order, starting with (0,0). Occupancy\n\
203 # probabilities are in the range [0,100]. Unknown is -1.\n\
204 int8[] data\n\
205 \n\
206 ================================================================================\n\
207 MSG: std_msgs/Header\n\
208 # Standard metadata for higher-level stamped data types.\n\
209 # This is generally used to communicate timestamped data \n\
210 # in a particular coordinate frame.\n\
211 # \n\
212 # sequence ID: consecutively increasing ID \n\
213 uint32 seq\n\
214 #Two-integer timestamp that is expressed as:\n\
215 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
216 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
217 # time-handling sugar is provided by the client library\n\
218 time stamp\n\
219 #Frame this data is associated with\n\
220 # 0: no frame\n\
221 # 1: global frame\n\
222 string frame_id\n\
223 \n\
224 ================================================================================\n\
225 MSG: nav_msgs/MapMetaData\n\
226 # This hold basic information about the characterists of the OccupancyGrid\n\
227 \n\
228 # The time at which the map was loaded\n\
229 time map_load_time\n\
230 # The map resolution [m/cell]\n\
231 float32 resolution\n\
232 # Map width [cells]\n\
233 uint32 width\n\
234 # Map height [cells]\n\
235 uint32 height\n\
236 # The origin of the map [m, m, rad]. This is the real-world pose of the\n\
237 # cell (0,0) in the map.\n\
238 geometry_msgs/Pose origin\n\
239 ================================================================================\n\
240 MSG: geometry_msgs/Pose\n\
241 # A representation of pose in free space, composed of position and orientation. \n\
242 Point position\n\
243 Quaternion orientation\n\
244 \n\
245 ================================================================================\n\
246 MSG: geometry_msgs/Point\n\
247 # This contains the position of a point in free space\n\
248 float64 x\n\
249 float64 y\n\
250 float64 z\n\
251 \n\
252 ================================================================================\n\
253 MSG: geometry_msgs/Quaternion\n\
254 # This represents an orientation in free space in quaternion form.\n\
255 \n\
256 float64 x\n\
257 float64 y\n\
258 float64 z\n\
259 float64 w\n\
260 ";
261 
262  yarp::os::Type getType() const override
263  {
265  typ.addProperty("md5sum", yarp::os::Value(typeChecksum));
266  typ.addProperty("message_definition", yarp::os::Value(typeText));
267  return typ;
268  }
269 };
270 
271 } // namespace nav_msgs
272 } // namespace rosmsg
273 } // namespace yarp
274 
275 #endif // YARP_ROSMSG_nav_msgs_OccupancyGrid_h
yarp::rosmsg::nav_msgs::OccupancyGrid::OccupancyGrid
OccupancyGrid()
Definition: OccupancyGrid.h:48
yarp::rosmsg::nav_msgs::OccupancyGrid::clear
void clear()
Definition: OccupancyGrid.h:55
yarp::rosmsg::std_msgs::Header::read
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: Header.h:115
yarp::rosmsg::nav_msgs::OccupancyGrid::writeBare
bool writeBare(yarp::os::ConnectionWriter &connection) const override
Definition: OccupancyGrid.h:127
WireTypes.h
BOTTLE_TAG_LIST
#define BOTTLE_TAG_LIST
Definition: Bottle.h:30
yarp::os::idl::BottleStyle
Definition: BottleStyle.h:22
yarp::os::Type
Definition: Type.h:24
yarp::os::idl::WirePortable::read
virtual bool read(yarp::os::idl::WireReader &reader)
Definition: WirePortable.cpp:14
Header.h
yarp::os::ConnectionWriter::appendInt8
virtual void appendInt8(std::int8_t data)=0
Send a representation of a 8-bit integer to the network connection.
yarp::os::ConnectionReader::isBareMode
virtual bool isBareMode() const =0
Check if the connection is bare mode.
yarp::rosmsg::std_msgs::Header::clear
void clear()
Definition: Header.h:58
yarp::rosmsg::nav_msgs::OccupancyGrid::header
yarp::rosmsg::std_msgs::Header header
Definition: OccupancyGrid.h:44
Wire.h
yarp::rosmsg::nav_msgs::OccupancyGrid::getType
yarp::os::Type getType() const override
Definition: OccupancyGrid.h:262
BOTTLE_TAG_INT8
#define BOTTLE_TAG_INT8
Definition: Bottle.h:21
yarp::rosmsg::nav_msgs::MapMetaData::read
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: MapMetaData.h:133
MapMetaData.h
yarp::os::ConnectionReader::expectInt8
virtual std::int8_t expectInt8()=0
Read a 8-bit integer from the network connection.
yarp::rosmsg::nav_msgs::OccupancyGrid::write
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: OccupancyGrid.h:175
yarp::rosmsg::nav_msgs::OccupancyGrid::bottleStyle
yarp::os::idl::BottleStyle< yarp::rosmsg::nav_msgs::OccupancyGrid > bottleStyle
Definition: OccupancyGrid.h:184
yarp::os::ConnectionWriter::isError
virtual bool isError() const =0
yarp::rosmsg::nav_msgs::OccupancyGrid::typeName
static constexpr const char * typeName
Definition: OccupancyGrid.h:187
yarp::os::Type::byName
static Type byName(const char *name)
Definition: Type.cpp:174
yarp::rosmsg::nav_msgs::MapMetaData
Definition: MapMetaData.h:43
yarp::os::ConnectionReader::expectInt32
virtual std::int32_t expectInt32()=0
Read a 32-bit integer from the network connection.
yarp::os::Type::addProperty
Type & addProperty(const char *key, const Value &val)
Definition: Type.cpp:137
Type.h
yarp::os::ConnectionWriter
An interface for writing to a network connection.
Definition: ConnectionWriter.h:40
yarp::os::ConnectionReader::isError
virtual bool isError() const =0
yarp::os::ConnectionReader::convertTextMode
virtual bool convertTextMode()=0
Reads in a standard description in text mode, and converts it to a standard description in binary.
yarp::rosmsg::nav_msgs::OccupancyGrid::rosStyle
yarp::os::idl::BareStyle< yarp::rosmsg::nav_msgs::OccupancyGrid > rosStyle
Definition: OccupancyGrid.h:183
yarp::os::idl::WirePortable
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
Definition: WirePortable.h:26
yarp::os::ConnectionWriter::isBareMode
virtual bool isBareMode() const =0
Check if the connection is bare mode.
yarp::rosmsg::std_msgs::Header::write
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: Header.h:162
yarp::os::ConnectionWriter::convertTextMode
virtual bool convertTextMode()=0
Converts a standard description in binary into a textual description, if the connection is in text-mo...
yarp::os::ConnectionWriter::appendInt32
virtual void appendInt32(std::int32_t data)=0
Send a representation of a 32-bit integer to the network connection.
nav_msgs
Definition: GetMap.h:22
yarp::os::idl::WireReader
IDL-friendly connection reader.
Definition: WireReader.h:33
yarp::rosmsg::nav_msgs::OccupancyGrid::typeText
static constexpr const char * typeText
Definition: OccupancyGrid.h:193
yarp::os::ConnectionReader
An interface for reading from a network connection.
Definition: ConnectionReader.h:40
yarp::rosmsg::nav_msgs::OccupancyGrid::writeBottle
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
Definition: OccupancyGrid.h:148
yarp::os::idl::BareStyle
Definition: BareStyle.h:22
yarp::rosmsg::nav_msgs::OccupancyGrid
Definition: OccupancyGrid.h:42
yarp::rosmsg::nav_msgs::OccupancyGrid::data
std::vector< std::int8_t > data
Definition: OccupancyGrid.h:46
yarp
The main, catch-all namespace for YARP.
Definition: environment.h:18
yarp::rosmsg::nav_msgs::OccupancyGrid::read
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: OccupancyGrid.h:121
yarp::os::ConnectionWriter::appendExternalBlock
virtual void appendExternalBlock(const char *data, size_t len)=0
Send a block of data to the network connection, without making a copy.
yarp::os::ConnectionReader::expectBlock
virtual bool expectBlock(char *data, size_t len)=0
Read a block of data from the network connection.
yarp::rosmsg::nav_msgs::OccupancyGrid::typeChecksum
static constexpr const char * typeChecksum
Definition: OccupancyGrid.h:190
yarp::os::Value
A single value (typically within a Bottle).
Definition: Value.h:47
yarp::rosmsg::nav_msgs::OccupancyGrid::info
yarp::rosmsg::nav_msgs::MapMetaData info
Definition: OccupancyGrid.h:45
yarp::rosmsg::nav_msgs::OccupancyGrid::readBare
bool readBare(yarp::os::ConnectionReader &connection) override
Definition: OccupancyGrid.h:67
yarp::rosmsg::nav_msgs::MapMetaData::write
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: MapMetaData.h:195
yarp::rosmsg::std_msgs::Header
Definition: Header.h:45
yarp::rosmsg::nav_msgs::OccupancyGrid::readBottle
bool readBottle(yarp::os::ConnectionReader &connection) override
Definition: OccupancyGrid.h:89
yarp::rosmsg::nav_msgs::MapMetaData::clear
void clear()
Definition: MapMetaData.h:60
yarp::os::idl::WireReader::readListHeader
bool readListHeader()
Definition: WireReader.cpp:470
yarp::os::idl::WirePortable::write
virtual bool write(const yarp::os::idl::WireWriter &writer) const
Definition: WirePortable.cpp:20