YARP
Yet Another Robot Platform
SetMap.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/SetMap" msg definition:
9 // # Set a new map together with an initial pose
10 // nav_msgs/OccupancyGrid map
11 // geometry_msgs/PoseWithCovarianceStamped initial_pose
12 // ---
13 // bool success
14 //
15 // Instances of this class can be read and written with YARP ports,
16 // using a ROS-compatible format.
17 
18 #ifndef YARP_ROSMSG_nav_msgs_SetMap_h
19 #define YARP_ROSMSG_nav_msgs_SetMap_h
20 
21 #include <yarp/os/Wire.h>
22 #include <yarp/os/Type.h>
23 #include <yarp/os/idl/WireTypes.h>
24 #include <string>
25 #include <vector>
28 
29 namespace yarp {
30 namespace rosmsg {
31 namespace nav_msgs {
32 
34 {
35 public:
38 
39  SetMap() :
40  map(),
41  initial_pose()
42  {
43  }
44 
45  void clear()
46  {
47  // *** map ***
48  map.clear();
49 
50  // *** initial_pose ***
52  }
53 
54  bool readBare(yarp::os::ConnectionReader& connection) override
55  {
56  // *** map ***
57  if (!map.read(connection)) {
58  return false;
59  }
60 
61  // *** initial_pose ***
62  if (!initial_pose.read(connection)) {
63  return false;
64  }
65 
66  return !connection.isError();
67  }
68 
69  bool readBottle(yarp::os::ConnectionReader& connection) override
70  {
71  connection.convertTextMode();
72  yarp::os::idl::WireReader reader(connection);
73  if (!reader.readListHeader(2)) {
74  return false;
75  }
76 
77  // *** map ***
78  if (!map.read(connection)) {
79  return false;
80  }
81 
82  // *** initial_pose ***
83  if (!initial_pose.read(connection)) {
84  return false;
85  }
86 
87  return !connection.isError();
88  }
89 
91  bool read(yarp::os::ConnectionReader& connection) override
92  {
93  return (connection.isBareMode() ? readBare(connection)
94  : readBottle(connection));
95  }
96 
97  bool writeBare(yarp::os::ConnectionWriter& connection) const override
98  {
99  // *** map ***
100  if (!map.write(connection)) {
101  return false;
102  }
103 
104  // *** initial_pose ***
105  if (!initial_pose.write(connection)) {
106  return false;
107  }
108 
109  return !connection.isError();
110  }
111 
112  bool writeBottle(yarp::os::ConnectionWriter& connection) const override
113  {
114  connection.appendInt32(BOTTLE_TAG_LIST);
115  connection.appendInt32(2);
116 
117  // *** map ***
118  if (!map.write(connection)) {
119  return false;
120  }
121 
122  // *** initial_pose ***
123  if (!initial_pose.write(connection)) {
124  return false;
125  }
126 
127  connection.convertTextMode();
128  return !connection.isError();
129  }
130 
132  bool write(yarp::os::ConnectionWriter& connection) const override
133  {
134  return (connection.isBareMode() ? writeBare(connection)
135  : writeBottle(connection));
136  }
137 
138  // This class will serialize ROS style or YARP style depending on protocol.
139  // If you need to force a serialization style, use one of these classes:
142 
143  // The name for this message, ROS will need this
144  static constexpr const char* typeName = "nav_msgs/SetMap";
145 
146  // The checksum for this message, ROS will need this
147  static constexpr const char* typeChecksum = "91149a20d7be299b87c340df8cc94fd4";
148 
149  // The source text for this message, ROS will need this
150  static constexpr const char* typeText = "\
151 # Set a new map together with an initial pose\n\
152 nav_msgs/OccupancyGrid map\n\
153 geometry_msgs/PoseWithCovarianceStamped initial_pose\n\
154 ---\n\
155 bool success\n\
156 \n\
157 \n\
158 ================================================================================\n\
159 MSG: nav_msgs/OccupancyGrid\n\
160 # This represents a 2-D grid map, in which each cell represents the probability of\n\
161 # occupancy.\n\
162 \n\
163 Header header \n\
164 \n\
165 #MetaData for the map\n\
166 MapMetaData info\n\
167 \n\
168 # The map data, in row-major order, starting with (0,0). Occupancy\n\
169 # probabilities are in the range [0,100]. Unknown is -1.\n\
170 int8[] data\n\
171 \n\
172 ================================================================================\n\
173 MSG: std_msgs/Header\n\
174 # Standard metadata for higher-level stamped data types.\n\
175 # This is generally used to communicate timestamped data \n\
176 # in a particular coordinate frame.\n\
177 # \n\
178 # sequence ID: consecutively increasing ID \n\
179 uint32 seq\n\
180 #Two-integer timestamp that is expressed as:\n\
181 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
182 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
183 # time-handling sugar is provided by the client library\n\
184 time stamp\n\
185 #Frame this data is associated with\n\
186 # 0: no frame\n\
187 # 1: global frame\n\
188 string frame_id\n\
189 \n\
190 ================================================================================\n\
191 MSG: nav_msgs/MapMetaData\n\
192 # This hold basic information about the characterists of the OccupancyGrid\n\
193 \n\
194 # The time at which the map was loaded\n\
195 time map_load_time\n\
196 # The map resolution [m/cell]\n\
197 float32 resolution\n\
198 # Map width [cells]\n\
199 uint32 width\n\
200 # Map height [cells]\n\
201 uint32 height\n\
202 # The origin of the map [m, m, rad]. This is the real-world pose of the\n\
203 # cell (0,0) in the map.\n\
204 geometry_msgs/Pose origin\n\
205 ================================================================================\n\
206 MSG: geometry_msgs/Pose\n\
207 # A representation of pose in free space, composed of position and orientation. \n\
208 Point position\n\
209 Quaternion orientation\n\
210 \n\
211 ================================================================================\n\
212 MSG: geometry_msgs/Point\n\
213 # This contains the position of a point in free space\n\
214 float64 x\n\
215 float64 y\n\
216 float64 z\n\
217 \n\
218 ================================================================================\n\
219 MSG: geometry_msgs/Quaternion\n\
220 # This represents an orientation in free space in quaternion form.\n\
221 \n\
222 float64 x\n\
223 float64 y\n\
224 float64 z\n\
225 float64 w\n\
226 \n\
227 ================================================================================\n\
228 MSG: geometry_msgs/PoseWithCovarianceStamped\n\
229 # This expresses an estimated pose with a reference coordinate frame and timestamp\n\
230 \n\
231 Header header\n\
232 PoseWithCovariance pose\n\
233 \n\
234 ================================================================================\n\
235 MSG: geometry_msgs/PoseWithCovariance\n\
236 # This represents a pose in free space with uncertainty.\n\
237 \n\
238 Pose pose\n\
239 \n\
240 # Row-major representation of the 6x6 covariance matrix\n\
241 # The orientation parameters use a fixed-axis representation.\n\
242 # In order, the parameters are:\n\
243 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n\
244 float64[36] covariance\n\
245 ";
246 
247  yarp::os::Type getType() const override
248  {
250  typ.addProperty("md5sum", yarp::os::Value(typeChecksum));
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_SetMap_h
#define BOTTLE_TAG_LIST
Definition: Bottle.h:28
An interface for reading from a network connection.
virtual bool isBareMode() const =0
Check if the connection is bare mode.
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
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 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:45
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
Definition: WirePortable.h:23
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:30
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
static constexpr const char * typeName
Definition: SetMap.h:144
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: SetMap.h:91
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: SetMap.h:132
bool readBare(yarp::os::ConnectionReader &connection) override
Definition: SetMap.h:54
static constexpr const char * typeText
Definition: SetMap.h:150
yarp::os::Type getType() const override
Definition: SetMap.h:247
yarp::os::idl::BottleStyle< yarp::rosmsg::nav_msgs::SetMap > bottleStyle
Definition: SetMap.h:141
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
Definition: SetMap.h:112
bool writeBare(yarp::os::ConnectionWriter &connection) const override
Definition: SetMap.h:97
yarp::rosmsg::nav_msgs::OccupancyGrid map
Definition: SetMap.h:36
bool readBottle(yarp::os::ConnectionReader &connection) override
Definition: SetMap.h:69
yarp::rosmsg::geometry_msgs::PoseWithCovarianceStamped initial_pose
Definition: SetMap.h:37
yarp::os::idl::BareStyle< yarp::rosmsg::nav_msgs::SetMap > rosStyle
Definition: SetMap.h:140
static constexpr const char * typeChecksum
Definition: SetMap.h:147
The main, catch-all namespace for YARP.
Definition: dirs.h:16