YARP
Yet Another Robot Platform
MapMetaData.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/MapMetaData" msg definition:
9// # This hold basic information about the characterists of the OccupancyGrid
10//
11// # The time at which the map was loaded
12// time map_load_time
13// # The map resolution [m/cell]
14// float32 resolution
15// # Map width [cells]
16// uint32 width
17// # Map height [cells]
18// uint32 height
19// # The origin of the map [m, m, rad]. This is the real-world pose of the
20// # cell (0,0) in the map.
21// geometry_msgs/Pose origin// Instances of this class can be read and written with YARP ports,
22// using a ROS-compatible format.
23
24#ifndef YARP_ROSMSG_nav_msgs_MapMetaData_h
25#define YARP_ROSMSG_nav_msgs_MapMetaData_h
26
27#include <yarp/os/Wire.h>
28#include <yarp/os/Type.h>
30#include <string>
31#include <vector>
34
35namespace yarp {
36namespace rosmsg {
37namespace nav_msgs {
38
40{
41public:
44 std::uint32_t width;
45 std::uint32_t height;
47
50 resolution(0.0f),
51 width(0),
52 height(0),
53 origin()
54 {
55 }
56
57 void clear()
58 {
59 // *** map_load_time ***
61
62 // *** resolution ***
63 resolution = 0.0f;
64
65 // *** width ***
66 width = 0;
67
68 // *** height ***
69 height = 0;
70
71 // *** origin ***
72 origin.clear();
73 }
74
75 bool readBare(yarp::os::ConnectionReader& connection) override
76 {
77 // *** map_load_time ***
78 if (!map_load_time.read(connection)) {
79 return false;
80 }
81
82 // *** resolution ***
83 resolution = connection.expectFloat32();
84
85 // *** width ***
86 width = connection.expectInt32();
87
88 // *** height ***
89 height = connection.expectInt32();
90
91 // *** origin ***
92 if (!origin.read(connection)) {
93 return false;
94 }
95
96 return !connection.isError();
97 }
98
99 bool readBottle(yarp::os::ConnectionReader& connection) override
100 {
101 connection.convertTextMode();
102 yarp::os::idl::WireReader reader(connection);
103 if (!reader.readListHeader(5)) {
104 return false;
105 }
106
107 // *** map_load_time ***
108 if (!map_load_time.read(connection)) {
109 return false;
110 }
111
112 // *** resolution ***
113 resolution = reader.expectFloat32();
114
115 // *** width ***
116 width = reader.expectInt32();
117
118 // *** height ***
119 height = reader.expectInt32();
120
121 // *** origin ***
122 if (!origin.read(connection)) {
123 return false;
124 }
125
126 return !connection.isError();
127 }
128
130 bool read(yarp::os::ConnectionReader& connection) override
131 {
132 return (connection.isBareMode() ? readBare(connection)
133 : readBottle(connection));
134 }
135
136 bool writeBare(yarp::os::ConnectionWriter& connection) const override
137 {
138 // *** map_load_time ***
139 if (!map_load_time.write(connection)) {
140 return false;
141 }
142
143 // *** resolution ***
144 connection.appendFloat32(resolution);
145
146 // *** width ***
147 connection.appendInt32(width);
148
149 // *** height ***
150 connection.appendInt32(height);
151
152 // *** origin ***
153 if (!origin.write(connection)) {
154 return false;
155 }
156
157 return !connection.isError();
158 }
159
160 bool writeBottle(yarp::os::ConnectionWriter& connection) const override
161 {
162 connection.appendInt32(BOTTLE_TAG_LIST);
163 connection.appendInt32(5);
164
165 // *** map_load_time ***
166 if (!map_load_time.write(connection)) {
167 return false;
168 }
169
170 // *** resolution ***
172 connection.appendFloat32(resolution);
173
174 // *** width ***
175 connection.appendInt32(BOTTLE_TAG_INT32);
176 connection.appendInt32(width);
177
178 // *** height ***
179 connection.appendInt32(BOTTLE_TAG_INT32);
180 connection.appendInt32(height);
181
182 // *** origin ***
183 if (!origin.write(connection)) {
184 return false;
185 }
186
187 connection.convertTextMode();
188 return !connection.isError();
189 }
190
192 bool write(yarp::os::ConnectionWriter& connection) const override
193 {
194 return (connection.isBareMode() ? writeBare(connection)
195 : writeBottle(connection));
196 }
197
198 // This class will serialize ROS style or YARP style depending on protocol.
199 // If you need to force a serialization style, use one of these classes:
202
203 // The name for this message, ROS will need this
204 static constexpr const char* typeName = "nav_msgs/MapMetaData";
205
206 // The checksum for this message, ROS will need this
207 static constexpr const char* typeChecksum = "10cfc8a2818024d3248802c00c95f11b";
208
209 // The source text for this message, ROS will need this
210 static constexpr const char* typeText = "\
211# This hold basic information about the characterists of the OccupancyGrid\n\
212\n\
213# The time at which the map was loaded\n\
214time map_load_time\n\
215# The map resolution [m/cell]\n\
216float32 resolution\n\
217# Map width [cells]\n\
218uint32 width\n\
219# Map height [cells]\n\
220uint32 height\n\
221# The origin of the map [m, m, rad]. This is the real-world pose of the\n\
222# cell (0,0) in the map.\n\
223geometry_msgs/Pose origin\n\
224================================================================================\n\
225MSG: geometry_msgs/Pose\n\
226# A representation of pose in free space, composed of position and orientation. \n\
227Point position\n\
228Quaternion orientation\n\
229\n\
230================================================================================\n\
231MSG: geometry_msgs/Point\n\
232# This contains the position of a point in free space\n\
233float64 x\n\
234float64 y\n\
235float64 z\n\
236\n\
237================================================================================\n\
238MSG: geometry_msgs/Quaternion\n\
239# This represents an orientation in free space in quaternion form.\n\
240\n\
241float64 x\n\
242float64 y\n\
243float64 z\n\
244float64 w\n\
245";
246
247 yarp::os::Type getType() const override
248 {
251 typ.addProperty("message_definition", yarp::os::Value(typeText));
252 return typ;
253 }
254};
255
256} // namespace nav_msgs
257} // namespace rosmsg
258} // namespace yarp
259
260#endif // YARP_ROSMSG_nav_msgs_MapMetaData_h
#define BOTTLE_TAG_INT32
Definition: Bottle.h:21
#define BOTTLE_TAG_LIST
Definition: Bottle.h:28
#define BOTTLE_TAG_FLOAT32
Definition: Bottle.h:24
An interface for reading from a 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 yarp::conf::float32_t expectFloat32()=0
Read a 32-bit floating point number from the network connection.
virtual bool isError() const =0
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 appendFloat32(yarp::conf::float32_t data)=0
Send a representation of a 32-bit floating point number to the network connection.
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
std::int32_t expectInt32()
Definition: WireReader.h:89
yarp::conf::float32_t expectFloat32()
Definition: WireReader.h:103
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: TickTime.h:148
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: TickTime.h:113
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: Pose.h:129
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: Pose.h:88
static constexpr const char * typeChecksum
Definition: MapMetaData.h:207
yarp::rosmsg::geometry_msgs::Pose origin
Definition: MapMetaData.h:46
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: MapMetaData.h:192
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
Definition: MapMetaData.h:160
static constexpr const char * typeText
Definition: MapMetaData.h:210
yarp::conf::float32_t resolution
Definition: MapMetaData.h:43
bool readBottle(yarp::os::ConnectionReader &connection) override
Definition: MapMetaData.h:99
bool readBare(yarp::os::ConnectionReader &connection) override
Definition: MapMetaData.h:75
yarp::os::idl::BottleStyle< yarp::rosmsg::nav_msgs::MapMetaData > bottleStyle
Definition: MapMetaData.h:201
bool writeBare(yarp::os::ConnectionWriter &connection) const override
Definition: MapMetaData.h:136
yarp::os::idl::BareStyle< yarp::rosmsg::nav_msgs::MapMetaData > rosStyle
Definition: MapMetaData.h:200
yarp::rosmsg::TickTime map_load_time
Definition: MapMetaData.h:42
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: MapMetaData.h:130
yarp::os::Type getType() const override
Definition: MapMetaData.h:247
static constexpr const char * typeName
Definition: MapMetaData.h:204
float float32_t
Definition: numeric.h:76
The main, catch-all namespace for YARP.
Definition: dirs.h:16