Main MRPT website > C++ reference for MRPT 1.9.9
CObservationIMU.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #ifndef CObservationIMU_H
10 #define CObservationIMU_H
11 
13 #include <mrpt/math/CMatrixD.h>
14 #include <mrpt/obs/CObservation.h>
15 #include <mrpt/poses/CPose3D.h>
16 #include <mrpt/poses/CPose2D.h>
17 
18 namespace mrpt
19 {
20 namespace obs
21 {
22 /** Symbolic names for the indices of IMU data (refer to
23  * mrpt::obs::CObservationIMU)
24  * \ingroup mrpt_obs_grp
25  */
27 {
28  /** x-axis acceleration (local/vehicle frame) (m/sec<sup>2</sup>) */
29  IMU_X_ACC = 0,
30  /** y-axis acceleration (local/vehicle frame) (m/sec<sup>2</sup>) */
32  /** z-axis acceleration (local/vehicle frame) (m/sec<sup>2</sup>) */
34  /** yaw angular velocity (local/vehicle frame) (rad/sec) */
36  /** pitch angular velocity (local/vehicle frame) (rad/sec) */
38  /** roll angular velocity (local/vehicle frame) (rad/sec) */
40  /** x-axis velocity (global/navigation frame) (m/sec) */
42  /** y-axis velocity (global/navigation frame) (m/sec) */
44  /** z-axis velocity (global/navigation frame) (m/sec) */
46  /** orientation yaw absolute value (global/navigation frame) (rad) */
48  /** orientation pitch absolute value (global/navigation frame) (rad) */
50  /** orientation roll absolute value (global/navigation frame) (rad) */
52  /** x absolute value (global/navigation frame) (meters) */
54  /** y absolute value (global/navigation frame) (meters) */
56  /** z absolute value (global/navigation frame) (meters) */
58  /** x magnetic field value (local/vehicle frame) (gauss) */
60  /** y magnetic field value (local/vehicle frame) (gauss) */
62  /** z magnetic field value (local/vehicle frame) (gauss) */
64  /** air pressure (Pascals) */
66  /** altitude from an altimeter (meters) */
68  /** temperature (degrees Celsius) */
70  /** Orientation Quaternion X (global/navigation frame) */
72  /** Orientation Quaternion Y (global/navigation frame) */
74  /** Orientation Quaternion Z (global/navigation frame) */
76  /** Orientation Quaternion W (global/navigation frame) */
78  /** yaw angular velocity (global/navigation frame) (rad/sec) */
80  /** pitch angular velocity (global/navigation frame) (rad/sec) */
82  /** roll angular velocity (global/navigation frame) (rad/sec) */
84  /** x-axis acceleration (global/navigation frame) (m/sec<sup>2</sup>) */
86  /** y-axis acceleration (global/navigation frame) (m/sec<sup>2</sup>) */
88  /** z-axis acceleration (global/navigation frame) (m/sec<sup>2</sup>) */
90 
91  // Always leave this last value to reflect the number of enum values
93 };
94 
95 /** This class stores measurements from an Inertial Measurement Unit (IMU)
96  * (attitude estimation, raw gyroscope and accelerometer values), altimeters or
97  * magnetometers.
98  *
99  * The order of the values in each entry of
100  * mrpt::obs::CObservationIMU::rawMeasurements is defined as symbolic names in
101  * the enum mrpt::obs::TIMUDataIndex.
102  * Check it out also for reference on the unit and the coordinate frame used
103  * for each value.
104  *
105  * \sa CObservation
106  * \ingroup mrpt_obs_grp
107  */
109 {
111 
112  public:
113  /** Constructor.
114  */
116  : sensorPose(),
119  {
120  }
121 
122  /** Destructor
123  */
124  virtual ~CObservationIMU() {}
125  /** The pose of the sensor on the robot. */
127 
128  /** Each entry in this vector is true if the corresponding data index
129  * contains valid data (the IMU unit supplies that kind of data).
130  * See the top of this page for the meaning of the indices.
131  */
133 
134  /** The accelerometer and/or gyroscope measurements taken by the IMU at the
135  * given timestamp.
136  * \sa dataIsPresent, CObservation::timestamp
137  */
138  std::vector<double> rawMeasurements;
139 
140  // See base class docs
141  void getSensorPose(mrpt::poses::CPose3D& out_sensorPose) const override
142  {
143  out_sensorPose = sensorPose;
144  }
145  void setSensorPose(const mrpt::poses::CPose3D& newSensorPose) override
146  {
147  sensorPose = newSensorPose;
148  }
149  void getDescriptionAsText(std::ostream& o) const override;
150 
151 }; // End of class def.
152 
153 } // End of namespace
154 } // End of namespace
155 
156 #endif
x-axis acceleration (global/navigation frame) (m/sec2)
z-axis acceleration (global/navigation frame) (m/sec2)
yaw angular velocity (global/navigation frame) (rad/sec)
void getDescriptionAsText(std::ostream &o) const override
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...
std::vector< double > rawMeasurements
The accelerometer and/or gyroscope measurements taken by the IMU at the given timestamp.
orientation pitch absolute value (global/navigation frame) (rad)
temperature (degrees Celsius)
x magnetic field value (local/vehicle frame) (gauss)
y-axis acceleration (local/vehicle frame) (m/sec2)
Orientation Quaternion X (global/navigation frame)
This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation, raw gyroscope and accelerometer values), altimeters or magnetometers.
z-axis acceleration (local/vehicle frame) (m/sec2)
x-axis velocity (global/navigation frame) (m/sec)
virtual ~CObservationIMU()
Destructor.
std::vector< bool > vector_bool
A type for passing a vector of bools.
Definition: types_simple.h:31
roll angular velocity (global/navigation frame) (rad/sec)
pitch angular velocity (local/vehicle frame) (rad/sec)
void setSensorPose(const mrpt::poses::CPose3D &newSensorPose) override
A general method to change the sensor pose on the robot.
pitch angular velocity (global/navigation frame) (rad/sec)
Orientation Quaternion Y (global/navigation frame)
Orientation Quaternion Z (global/navigation frame)
z magnetic field value (local/vehicle frame) (gauss)
Orientation Quaternion W (global/navigation frame)
y absolute value (global/navigation frame) (meters)
y magnetic field value (local/vehicle frame) (gauss)
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
mrpt::poses::CPose3D sensorPose
The pose of the sensor on the robot.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
Declares a class that represents any robot&#39;s observation.
Definition: CObservation.h:41
y-axis acceleration (global/navigation frame) (m/sec2)
air pressure (Pascals)
z absolute value (global/navigation frame) (meters)
TIMUDataIndex
Symbolic names for the indices of IMU data (refer to mrpt::obs::CObservationIMU)
orientation yaw absolute value (global/navigation frame) (rad)
y-axis velocity (global/navigation frame) (m/sec)
orientation roll absolute value (global/navigation frame) (rad)
yaw angular velocity (local/vehicle frame) (rad/sec)
x absolute value (global/navigation frame) (meters)
void getSensorPose(mrpt::poses::CPose3D &out_sensorPose) const override
A general method to retrieve the sensor pose on the robot.
roll angular velocity (local/vehicle frame) (rad/sec)
x-axis acceleration (local/vehicle frame) (m/sec2)
z-axis velocity (global/navigation frame) (m/sec)
vector_bool dataIsPresent
Each entry in this vector is true if the corresponding data index contains valid data (the IMU unit s...
altitude from an altimeter (meters)



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019