YARP
Yet Another Robot Platform
Imu.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 "sensor_msgs/Imu" msg definition:
9// # This is a message to hold data from an IMU (Inertial Measurement Unit)
10// #
11// # Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec
12// #
13// # If the covariance of the measurement is known, it should be filled in (if all you know is the
14// # variance of each measurement, e.g. from the datasheet, just put those along the diagonal)
15// # A covariance matrix of all zeros will be interpreted as "covariance unknown", and to use the
16// # data a covariance will have to be assumed or gotten from some other source
17// #
18// # If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an orientation
19// # estimate), please set element 0 of the associated covariance matrix to -1
20// # If you are interpreting this message, please check for a value of -1 in the first element of each
21// # covariance matrix, and disregard the associated estimate.
22//
23// Header header
24//
25// geometry_msgs/Quaternion orientation
26// float64[9] orientation_covariance # Row major about x, y, z axes
27//
28// geometry_msgs/Vector3 angular_velocity
29// float64[9] angular_velocity_covariance # Row major about x, y, z axes
30//
31// geometry_msgs/Vector3 linear_acceleration
32// float64[9] linear_acceleration_covariance # Row major x, y z
33// Instances of this class can be read and written with YARP ports,
34// using a ROS-compatible format.
35
36#ifndef YARP_ROSMSG_sensor_msgs_Imu_h
37#define YARP_ROSMSG_sensor_msgs_Imu_h
38
39#include <yarp/os/Wire.h>
40#include <yarp/os/Type.h>
42#include <string>
43#include <vector>
47
48namespace yarp {
49namespace rosmsg {
50namespace sensor_msgs {
51
53{
54public:
57 std::vector<yarp::conf::float64_t> orientation_covariance;
59 std::vector<yarp::conf::float64_t> angular_velocity_covariance;
61 std::vector<yarp::conf::float64_t> linear_acceleration_covariance;
62
63 Imu() :
64 header(),
71 {
72 orientation_covariance.resize(9, 0.0);
73 angular_velocity_covariance.resize(9, 0.0);
74 linear_acceleration_covariance.resize(9, 0.0);
75 }
76
77 void clear()
78 {
79 // *** header ***
80 header.clear();
81
82 // *** orientation ***
84
85 // *** orientation_covariance ***
87 orientation_covariance.resize(9, 0.0);
88
89 // *** angular_velocity ***
91
92 // *** angular_velocity_covariance ***
94 angular_velocity_covariance.resize(9, 0.0);
95
96 // *** linear_acceleration ***
98
99 // *** linear_acceleration_covariance ***
101 linear_acceleration_covariance.resize(9, 0.0);
102 }
103
104 bool readBare(yarp::os::ConnectionReader& connection) override
105 {
106 // *** header ***
107 if (!header.read(connection)) {
108 return false;
109 }
110
111 // *** orientation ***
112 if (!orientation.read(connection)) {
113 return false;
114 }
115
116 // *** orientation_covariance ***
117 int len = 9;
118 orientation_covariance.resize(len);
119 if (len > 0 && !connection.expectBlock((char*)&orientation_covariance[0], sizeof(yarp::conf::float64_t)*len)) {
120 return false;
121 }
122
123 // *** angular_velocity ***
124 if (!angular_velocity.read(connection)) {
125 return false;
126 }
127
128 // *** angular_velocity_covariance ***
129 len = 9;
130 angular_velocity_covariance.resize(len);
131 if (len > 0 && !connection.expectBlock((char*)&angular_velocity_covariance[0], sizeof(yarp::conf::float64_t)*len)) {
132 return false;
133 }
134
135 // *** linear_acceleration ***
136 if (!linear_acceleration.read(connection)) {
137 return false;
138 }
139
140 // *** linear_acceleration_covariance ***
141 len = 9;
143 if (len > 0 && !connection.expectBlock((char*)&linear_acceleration_covariance[0], sizeof(yarp::conf::float64_t)*len)) {
144 return false;
145 }
146
147 return !connection.isError();
148 }
149
150 bool readBottle(yarp::os::ConnectionReader& connection) override
151 {
152 connection.convertTextMode();
153 yarp::os::idl::WireReader reader(connection);
154 if (!reader.readListHeader(7)) {
155 return false;
156 }
157
158 // *** header ***
159 if (!header.read(connection)) {
160 return false;
161 }
162
163 // *** orientation ***
164 if (!orientation.read(connection)) {
165 return false;
166 }
167
168 // *** orientation_covariance ***
169 if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_FLOAT64)) {
170 return false;
171 }
172 int len = connection.expectInt32();
173 orientation_covariance.resize(len);
174 for (int i=0; i<len; i++) {
176 }
177
178 // *** angular_velocity ***
179 if (!angular_velocity.read(connection)) {
180 return false;
181 }
182
183 // *** angular_velocity_covariance ***
184 if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_FLOAT64)) {
185 return false;
186 }
187 len = connection.expectInt32();
188 angular_velocity_covariance.resize(len);
189 for (int i=0; i<len; i++) {
191 }
192
193 // *** linear_acceleration ***
194 if (!linear_acceleration.read(connection)) {
195 return false;
196 }
197
198 // *** linear_acceleration_covariance ***
199 if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_FLOAT64)) {
200 return false;
201 }
202 len = connection.expectInt32();
204 for (int i=0; i<len; i++) {
206 }
207
208 return !connection.isError();
209 }
210
212 bool read(yarp::os::ConnectionReader& connection) override
213 {
214 return (connection.isBareMode() ? readBare(connection)
215 : readBottle(connection));
216 }
217
218 bool writeBare(yarp::os::ConnectionWriter& connection) const override
219 {
220 // *** header ***
221 if (!header.write(connection)) {
222 return false;
223 }
224
225 // *** orientation ***
226 if (!orientation.write(connection)) {
227 return false;
228 }
229
230 // *** orientation_covariance ***
231 if (orientation_covariance.size()>0) {
233 }
234
235 // *** angular_velocity ***
236 if (!angular_velocity.write(connection)) {
237 return false;
238 }
239
240 // *** angular_velocity_covariance ***
241 if (angular_velocity_covariance.size()>0) {
243 }
244
245 // *** linear_acceleration ***
246 if (!linear_acceleration.write(connection)) {
247 return false;
248 }
249
250 // *** linear_acceleration_covariance ***
251 if (linear_acceleration_covariance.size()>0) {
253 }
254
255 return !connection.isError();
256 }
257
258 bool writeBottle(yarp::os::ConnectionWriter& connection) const override
259 {
260 connection.appendInt32(BOTTLE_TAG_LIST);
261 connection.appendInt32(7);
262
263 // *** header ***
264 if (!header.write(connection)) {
265 return false;
266 }
267
268 // *** orientation ***
269 if (!orientation.write(connection)) {
270 return false;
271 }
272
273 // *** orientation_covariance ***
275 connection.appendInt32(orientation_covariance.size());
276 for (size_t i=0; i<orientation_covariance.size(); i++) {
278 }
279
280 // *** angular_velocity ***
281 if (!angular_velocity.write(connection)) {
282 return false;
283 }
284
285 // *** angular_velocity_covariance ***
287 connection.appendInt32(angular_velocity_covariance.size());
288 for (size_t i=0; i<angular_velocity_covariance.size(); i++) {
290 }
291
292 // *** linear_acceleration ***
293 if (!linear_acceleration.write(connection)) {
294 return false;
295 }
296
297 // *** linear_acceleration_covariance ***
300 for (size_t i=0; i<linear_acceleration_covariance.size(); i++) {
302 }
303
304 connection.convertTextMode();
305 return !connection.isError();
306 }
307
309 bool write(yarp::os::ConnectionWriter& connection) const override
310 {
311 return (connection.isBareMode() ? writeBare(connection)
312 : writeBottle(connection));
313 }
314
315 // This class will serialize ROS style or YARP style depending on protocol.
316 // If you need to force a serialization style, use one of these classes:
319
320 // The name for this message, ROS will need this
321 static constexpr const char* typeName = "sensor_msgs/Imu";
322
323 // The checksum for this message, ROS will need this
324 static constexpr const char* typeChecksum = "6a62c6daae103f4ff57a132d6f95cec2";
325
326 // The source text for this message, ROS will need this
327 static constexpr const char* typeText = "\
328# This is a message to hold data from an IMU (Inertial Measurement Unit)\n\
329#\n\
330# Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec\n\
331#\n\
332# If the covariance of the measurement is known, it should be filled in (if all you know is the \n\
333# variance of each measurement, e.g. from the datasheet, just put those along the diagonal)\n\
334# A covariance matrix of all zeros will be interpreted as \"covariance unknown\", and to use the\n\
335# data a covariance will have to be assumed or gotten from some other source\n\
336#\n\
337# If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an orientation \n\
338# estimate), please set element 0 of the associated covariance matrix to -1\n\
339# If you are interpreting this message, please check for a value of -1 in the first element of each \n\
340# covariance matrix, and disregard the associated estimate.\n\
341\n\
342Header header\n\
343\n\
344geometry_msgs/Quaternion orientation\n\
345float64[9] orientation_covariance # Row major about x, y, z axes\n\
346\n\
347geometry_msgs/Vector3 angular_velocity\n\
348float64[9] angular_velocity_covariance # Row major about x, y, z axes\n\
349\n\
350geometry_msgs/Vector3 linear_acceleration\n\
351float64[9] linear_acceleration_covariance # Row major x, y z \n\
352\n\
353================================================================================\n\
354MSG: std_msgs/Header\n\
355# Standard metadata for higher-level stamped data types.\n\
356# This is generally used to communicate timestamped data \n\
357# in a particular coordinate frame.\n\
358# \n\
359# sequence ID: consecutively increasing ID \n\
360uint32 seq\n\
361#Two-integer timestamp that is expressed as:\n\
362# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
363# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
364# time-handling sugar is provided by the client library\n\
365time stamp\n\
366#Frame this data is associated with\n\
367# 0: no frame\n\
368# 1: global frame\n\
369string frame_id\n\
370\n\
371================================================================================\n\
372MSG: geometry_msgs/Quaternion\n\
373# This represents an orientation in free space in quaternion form.\n\
374\n\
375float64 x\n\
376float64 y\n\
377float64 z\n\
378float64 w\n\
379\n\
380================================================================================\n\
381MSG: geometry_msgs/Vector3\n\
382# This represents a vector in free space. \n\
383# It is only meant to represent a direction. Therefore, it does not\n\
384# make sense to apply a translation to it (e.g., when applying a \n\
385# generic rigid transformation to a Vector3, tf2 will only apply the\n\
386# rotation). If you want your data to be translatable too, use the\n\
387# geometry_msgs/Point message instead.\n\
388\n\
389float64 x\n\
390float64 y\n\
391float64 z\n\
392";
393
394 yarp::os::Type getType() const override
395 {
398 typ.addProperty("message_definition", yarp::os::Value(typeText));
399 return typ;
400 }
401};
402
403} // namespace sensor_msgs
404} // namespace rosmsg
405} // namespace yarp
406
407#endif // YARP_ROSMSG_sensor_msgs_Imu_h
#define BOTTLE_TAG_FLOAT64
Definition: Bottle.h:25
#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 yarp::conf::float64_t expectFloat64()=0
Read a 64-bit floating point number 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 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.
virtual void appendFloat64(yarp::conf::float64_t data)=0
Send a representation of a 64-bit floating point number 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: Quaternion.h:152
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: Quaternion.h:103
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: Vector3.h:95
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: Vector3.h:137
yarp::os::Type getType() const override
Definition: Imu.h:394
static constexpr const char * typeChecksum
Definition: Imu.h:324
yarp::rosmsg::std_msgs::Header header
Definition: Imu.h:55
std::vector< yarp::conf::float64_t > orientation_covariance
Definition: Imu.h:57
yarp::rosmsg::geometry_msgs::Vector3 angular_velocity
Definition: Imu.h:58
std::vector< yarp::conf::float64_t > linear_acceleration_covariance
Definition: Imu.h:61
yarp::rosmsg::geometry_msgs::Vector3 linear_acceleration
Definition: Imu.h:60
bool writeBare(yarp::os::ConnectionWriter &connection) const override
Definition: Imu.h:218
yarp::rosmsg::geometry_msgs::Quaternion orientation
Definition: Imu.h:56
std::vector< yarp::conf::float64_t > angular_velocity_covariance
Definition: Imu.h:59
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::Imu > bottleStyle
Definition: Imu.h:318
static constexpr const char * typeText
Definition: Imu.h:327
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
Definition: Imu.h:258
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::Imu > rosStyle
Definition: Imu.h:317
static constexpr const char * typeName
Definition: Imu.h:321
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: Imu.h:309
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: Imu.h:212
bool readBare(yarp::os::ConnectionReader &connection) override
Definition: Imu.h:104
bool readBottle(yarp::os::ConnectionReader &connection) override
Definition: Imu.h:150
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
double float64_t
Definition: numeric.h:77
The main, catch-all namespace for YARP.
Definition: dirs.h:16