YARP
Yet Another Robot Platform
Odometry.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/Odometry" msg definition:
9 // # This represents an estimate of a position and velocity in free space.
10 // # The pose in this message should be specified in the coordinate frame given by header.frame_id.
11 // # The twist in this message should be specified in the coordinate frame given by the child_frame_id
12 // Header header
13 // string child_frame_id
14 // geometry_msgs/PoseWithCovariance pose
15 // geometry_msgs/TwistWithCovariance twist
16 // Instances of this class can be read and written with YARP ports,
17 // using a ROS-compatible format.
18 
19 #ifndef YARP_ROSMSG_nav_msgs_Odometry_h
20 #define YARP_ROSMSG_nav_msgs_Odometry_h
21 
22 #include <yarp/os/Wire.h>
23 #include <yarp/os/Type.h>
24 #include <yarp/os/idl/WireTypes.h>
25 #include <string>
26 #include <vector>
30 
31 namespace yarp {
32 namespace rosmsg {
33 namespace nav_msgs {
34 
36 {
37 public:
39  std::string child_frame_id;
42 
44  header(),
45  child_frame_id(""),
46  pose(),
47  twist()
48  {
49  }
50 
51  void clear()
52  {
53  // *** header ***
54  header.clear();
55 
56  // *** child_frame_id ***
57  child_frame_id = "";
58 
59  // *** pose ***
60  pose.clear();
61 
62  // *** twist ***
63  twist.clear();
64  }
65 
66  bool readBare(yarp::os::ConnectionReader& connection) override
67  {
68  // *** header ***
69  if (!header.read(connection)) {
70  return false;
71  }
72 
73  // *** child_frame_id ***
74  int len = connection.expectInt32();
75  child_frame_id.resize(len);
76  if (!connection.expectBlock((char*)child_frame_id.c_str(), len)) {
77  return false;
78  }
79 
80  // *** pose ***
81  if (!pose.read(connection)) {
82  return false;
83  }
84 
85  // *** twist ***
86  if (!twist.read(connection)) {
87  return false;
88  }
89 
90  return !connection.isError();
91  }
92 
93  bool readBottle(yarp::os::ConnectionReader& connection) override
94  {
95  connection.convertTextMode();
96  yarp::os::idl::WireReader reader(connection);
97  if (!reader.readListHeader(4)) {
98  return false;
99  }
100 
101  // *** header ***
102  if (!header.read(connection)) {
103  return false;
104  }
105 
106  // *** child_frame_id ***
107  if (!reader.readString(child_frame_id)) {
108  return false;
109  }
110 
111  // *** pose ***
112  if (!pose.read(connection)) {
113  return false;
114  }
115 
116  // *** twist ***
117  if (!twist.read(connection)) {
118  return false;
119  }
120 
121  return !connection.isError();
122  }
123 
125  bool read(yarp::os::ConnectionReader& connection) override
126  {
127  return (connection.isBareMode() ? readBare(connection)
128  : readBottle(connection));
129  }
130 
131  bool writeBare(yarp::os::ConnectionWriter& connection) const override
132  {
133  // *** header ***
134  if (!header.write(connection)) {
135  return false;
136  }
137 
138  // *** child_frame_id ***
139  connection.appendInt32(child_frame_id.length());
140  connection.appendExternalBlock((char*)child_frame_id.c_str(), child_frame_id.length());
141 
142  // *** pose ***
143  if (!pose.write(connection)) {
144  return false;
145  }
146 
147  // *** twist ***
148  if (!twist.write(connection)) {
149  return false;
150  }
151 
152  return !connection.isError();
153  }
154 
155  bool writeBottle(yarp::os::ConnectionWriter& connection) const override
156  {
157  connection.appendInt32(BOTTLE_TAG_LIST);
158  connection.appendInt32(4);
159 
160  // *** header ***
161  if (!header.write(connection)) {
162  return false;
163  }
164 
165  // *** child_frame_id ***
166  connection.appendInt32(BOTTLE_TAG_STRING);
167  connection.appendInt32(child_frame_id.length());
168  connection.appendExternalBlock((char*)child_frame_id.c_str(), child_frame_id.length());
169 
170  // *** pose ***
171  if (!pose.write(connection)) {
172  return false;
173  }
174 
175  // *** twist ***
176  if (!twist.write(connection)) {
177  return false;
178  }
179 
180  connection.convertTextMode();
181  return !connection.isError();
182  }
183 
185  bool write(yarp::os::ConnectionWriter& connection) const override
186  {
187  return (connection.isBareMode() ? writeBare(connection)
188  : writeBottle(connection));
189  }
190 
191  // This class will serialize ROS style or YARP style depending on protocol.
192  // If you need to force a serialization style, use one of these classes:
195 
196  // The name for this message, ROS will need this
197  static constexpr const char* typeName = "nav_msgs/Odometry";
198 
199  // The checksum for this message, ROS will need this
200  static constexpr const char* typeChecksum = "cd5e73d190d741a2f92e81eda573aca7";
201 
202  // The source text for this message, ROS will need this
203  static constexpr const char* typeText = "\
204 # This represents an estimate of a position and velocity in free space. \n\
205 # The pose in this message should be specified in the coordinate frame given by header.frame_id.\n\
206 # The twist in this message should be specified in the coordinate frame given by the child_frame_id\n\
207 Header header\n\
208 string child_frame_id\n\
209 geometry_msgs/PoseWithCovariance pose\n\
210 geometry_msgs/TwistWithCovariance twist\n\
211 \n\
212 ================================================================================\n\
213 MSG: std_msgs/Header\n\
214 # Standard metadata for higher-level stamped data types.\n\
215 # This is generally used to communicate timestamped data \n\
216 # in a particular coordinate frame.\n\
217 # \n\
218 # sequence ID: consecutively increasing ID \n\
219 uint32 seq\n\
220 #Two-integer timestamp that is expressed as:\n\
221 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
222 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
223 # time-handling sugar is provided by the client library\n\
224 time stamp\n\
225 #Frame this data is associated with\n\
226 # 0: no frame\n\
227 # 1: global frame\n\
228 string frame_id\n\
229 \n\
230 ================================================================================\n\
231 MSG: geometry_msgs/PoseWithCovariance\n\
232 # This represents a pose in free space with uncertainty.\n\
233 \n\
234 Pose pose\n\
235 \n\
236 # Row-major representation of the 6x6 covariance matrix\n\
237 # The orientation parameters use a fixed-axis representation.\n\
238 # In order, the parameters are:\n\
239 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n\
240 float64[36] covariance\n\
241 \n\
242 ================================================================================\n\
243 MSG: geometry_msgs/Pose\n\
244 # A representation of pose in free space, composed of position and orientation. \n\
245 Point position\n\
246 Quaternion orientation\n\
247 \n\
248 ================================================================================\n\
249 MSG: geometry_msgs/Point\n\
250 # This contains the position of a point in free space\n\
251 float64 x\n\
252 float64 y\n\
253 float64 z\n\
254 \n\
255 ================================================================================\n\
256 MSG: geometry_msgs/Quaternion\n\
257 # This represents an orientation in free space in quaternion form.\n\
258 \n\
259 float64 x\n\
260 float64 y\n\
261 float64 z\n\
262 float64 w\n\
263 \n\
264 ================================================================================\n\
265 MSG: geometry_msgs/TwistWithCovariance\n\
266 # This expresses velocity in free space with uncertainty.\n\
267 \n\
268 Twist twist\n\
269 \n\
270 # Row-major representation of the 6x6 covariance matrix\n\
271 # The orientation parameters use a fixed-axis representation.\n\
272 # In order, the parameters are:\n\
273 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n\
274 float64[36] covariance\n\
275 \n\
276 ================================================================================\n\
277 MSG: geometry_msgs/Twist\n\
278 # This expresses velocity in free space broken into its linear and angular parts.\n\
279 Vector3 linear\n\
280 Vector3 angular\n\
281 \n\
282 ================================================================================\n\
283 MSG: geometry_msgs/Vector3\n\
284 # This represents a vector in free space. \n\
285 # It is only meant to represent a direction. Therefore, it does not\n\
286 # make sense to apply a translation to it (e.g., when applying a \n\
287 # generic rigid transformation to a Vector3, tf2 will only apply the\n\
288 # rotation). If you want your data to be translatable too, use the\n\
289 # geometry_msgs/Point message instead.\n\
290 \n\
291 float64 x\n\
292 float64 y\n\
293 float64 z\n\
294 ";
295 
296  yarp::os::Type getType() const override
297  {
299  typ.addProperty("md5sum", yarp::os::Value(typeChecksum));
300  typ.addProperty("message_definition", yarp::os::Value(typeText));
301  return typ;
302  }
303 };
304 
305 } // namespace nav_msgs
306 } // namespace rosmsg
307 } // namespace yarp
308 
309 #endif // YARP_ROSMSG_nav_msgs_Odometry_h
#define BOTTLE_TAG_STRING
Definition: Bottle.h:26
#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
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 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: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 readString(std::string &str, bool *is_vocab=nullptr)
Definition: WireReader.cpp:382
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 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 write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: Odometry.h:185
yarp::os::idl::BottleStyle< yarp::rosmsg::nav_msgs::Odometry > bottleStyle
Definition: Odometry.h:194
yarp::rosmsg::geometry_msgs::PoseWithCovariance pose
Definition: Odometry.h:40
bool readBare(yarp::os::ConnectionReader &connection) override
Definition: Odometry.h:66
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
Definition: Odometry.h:155
yarp::os::idl::BareStyle< yarp::rosmsg::nav_msgs::Odometry > rosStyle
Definition: Odometry.h:193
static constexpr const char * typeText
Definition: Odometry.h:203
static constexpr const char * typeName
Definition: Odometry.h:197
yarp::rosmsg::std_msgs::Header header
Definition: Odometry.h:38
bool writeBare(yarp::os::ConnectionWriter &connection) const override
Definition: Odometry.h:131
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: Odometry.h:125
static constexpr const char * typeChecksum
Definition: Odometry.h:200
yarp::os::Type getType() const override
Definition: Odometry.h:296
bool readBottle(yarp::os::ConnectionReader &connection) override
Definition: Odometry.h:93
yarp::rosmsg::geometry_msgs::TwistWithCovariance twist
Definition: Odometry.h:41
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