Main MRPT website > C++ reference for MRPT 1.4.0
obs/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-2016, 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 
24 
25  /** Symbolic names for the indices of IMU data (refer to mrpt::obs::CObservationIMU)
26  * \ingroup mrpt_obs_grp
27  */
29  {
30  IMU_X_ACC = 0 , //!< x-axis acceleration (local/vehicle frame) (m/sec<sup>2</sup>)
31  IMU_Y_ACC, //!< y-axis acceleration (local/vehicle frame) (m/sec<sup>2</sup>)
32  IMU_Z_ACC, //!< z-axis acceleration (local/vehicle frame) (m/sec<sup>2</sup>)
33  IMU_YAW_VEL, //!< yaw angular velocity (local/vehicle frame) (rad/sec)
34  IMU_PITCH_VEL, //!< pitch angular velocity (local/vehicle frame) (rad/sec)
35  IMU_ROLL_VEL, //!< roll angular velocity (local/vehicle frame) (rad/sec)
36  IMU_X_VEL, //!< x-axis velocity (global/navigation frame) (m/sec)
37  IMU_Y_VEL, //!< y-axis velocity (global/navigation frame) (m/sec)
38  IMU_Z_VEL, //!< z-axis velocity (global/navigation frame) (m/sec)
39  IMU_YAW, //!< orientation yaw absolute value (global/navigation frame) (rad)
40  IMU_PITCH, //!< orientation pitch absolute value (global/navigation frame) (rad)
41  IMU_ROLL, //!< orientation roll absolute value (global/navigation frame) (rad)
42  IMU_X, //!< x absolute value (global/navigation frame) (meters)
43  IMU_Y, //!< y absolute value (global/navigation frame) (meters)
44  IMU_Z, //!< z absolute value (global/navigation frame) (meters)
45  IMU_MAG_X, //!< x magnetic field value (local/vehicle frame) (gauss)
46  IMU_MAG_Y, //!< y magnetic field value (local/vehicle frame) (gauss)
47  IMU_MAG_Z, //!< z magnetic field value (local/vehicle frame) (gauss)
48  IMU_PRESSURE, //!< air pressure (Pascals)
49  IMU_ALTITUDE, //!< altitude from an altimeter (meters)
50  IMU_TEMPERATURE, //!< temperature (degrees Celsius)
51  IMU_ORI_QUAT_X, //!< Orientation Quaternion X (global/navigation frame)
52  IMU_ORI_QUAT_Y, //!< Orientation Quaternion Y (global/navigation frame)
53  IMU_ORI_QUAT_Z, //!< Orientation Quaternion Z (global/navigation frame)
54  IMU_ORI_QUAT_W, //!< Orientation Quaternion W (global/navigation frame)
55  IMU_YAW_VEL_GLOBAL, //!< yaw angular velocity (global/navigation frame) (rad/sec)
56  IMU_PITCH_VEL_GLOBAL,//!< pitch angular velocity (global/navigation frame) (rad/sec)
57  IMU_ROLL_VEL_GLOBAL, //!< roll angular velocity (global/navigation frame) (rad/sec)
58  IMU_X_ACC_GLOBAL, //!< x-axis acceleration (global/navigation frame) (m/sec<sup>2</sup>)
59  IMU_Y_ACC_GLOBAL, //!< y-axis acceleration (global/navigation frame) (m/sec<sup>2</sup>)
60  IMU_Z_ACC_GLOBAL, //!< z-axis acceleration (global/navigation frame) (m/sec<sup>2</sup>)
61 
62  // Always leave this last value to reflect the number of enum values
64  };
65 
66  /** This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation, raw gyroscope and accelerometer values), altimeters or magnetometers.
67  *
68  * The order of the values in each entry of mrpt::obs::CObservationIMU::rawMeasurements is defined as symbolic names in the enum mrpt::obs::TIMUDataIndex.
69  * Check it out also for reference on the unit and the coordinate frame used for each value.
70  *
71  * \sa CObservation
72  * \ingroup mrpt_obs_grp
73  */
75  {
76  // This must be added to any CSerializable derived class:
78 
79  public:
80  /** Constructor.
81  */
83  sensorPose(),
84  dataIsPresent(mrpt::obs::COUNT_IMU_DATA_FIELDS,false),
85  rawMeasurements(mrpt::obs::COUNT_IMU_DATA_FIELDS,0)
86  { }
87 
88  /** Destructor
89  */
90  virtual ~CObservationIMU()
91  { }
92 
93  /** The pose of the sensor on the robot. */
95 
96  /** Each entry in this vector is true if the corresponding data index contains valid data (the IMU unit supplies that kind of data).
97  * See the top of this page for the meaning of the indices.
98  */
100 
101  /** The accelerometer and/or gyroscope measurements taken by the IMU at the given timestamp.
102  * \sa dataIsPresent, CObservation::timestamp
103  */
104  std::vector<double> rawMeasurements;
105 
106 
107  // See base class docs
108  void getSensorPose( mrpt::poses::CPose3D &out_sensorPose ) const MRPT_OVERRIDE { out_sensorPose = sensorPose; }
109  void setSensorPose( const mrpt::poses::CPose3D &newSensorPose ) MRPT_OVERRIDE { sensorPose = newSensorPose; }
110  void getDescriptionAsText(std::ostream &o) const MRPT_OVERRIDE;
111 
112 
113  }; // End of class def.
115 
116 
117  } // End of namespace
118 } // End of namespace
119 
120 #endif
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
#define DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
This declaration must be inserted in all CSerializable classes definition, before the class declarati...
Declares a class that represents any robot's observation.
This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation,...
std::vector< double > rawMeasurements
The accelerometer and/or gyroscope measurements taken by the IMU at the given timestamp.
mrpt::poses::CPose3D sensorPose
The pose of the sensor on the robot.
vector_bool dataIsPresent
Each entry in this vector is true if the corresponding data index contains valid data (the IMU unit s...
void getDescriptionAsText(std::ostream &o) const MRPT_OVERRIDE
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...
virtual ~CObservationIMU()
Destructor.
void setSensorPose(const mrpt::poses::CPose3D &newSensorPose) MRPT_OVERRIDE
A general method to change the sensor pose on the robot.
void getSensorPose(mrpt::poses::CPose3D &out_sensorPose) const MRPT_OVERRIDE
A general method to retrieve the sensor pose on the robot.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:73
TIMUDataIndex
Symbolic names for the indices of IMU data (refer to mrpt::obs::CObservationIMU)
@ IMU_MAG_Y
y magnetic field value (local/vehicle frame) (gauss)
@ IMU_Y_ACC_GLOBAL
y-axis acceleration (global/navigation frame) (m/sec2)
@ IMU_MAG_Z
z magnetic field value (local/vehicle frame) (gauss)
@ IMU_YAW_VEL_GLOBAL
yaw angular velocity (global/navigation frame) (rad/sec)
@ IMU_ALTITUDE
altitude from an altimeter (meters)
@ IMU_X_ACC_GLOBAL
x-axis acceleration (global/navigation frame) (m/sec2)
@ IMU_X_ACC
x-axis acceleration (local/vehicle frame) (m/sec2)
@ IMU_PITCH_VEL
pitch angular velocity (local/vehicle frame) (rad/sec)
@ IMU_X
x absolute value (global/navigation frame) (meters)
@ IMU_ROLL_VEL_GLOBAL
roll angular velocity (global/navigation frame) (rad/sec)
@ IMU_ORI_QUAT_W
Orientation Quaternion W (global/navigation frame)
@ IMU_PITCH
orientation pitch absolute value (global/navigation frame) (rad)
@ IMU_PRESSURE
air pressure (Pascals)
@ IMU_ORI_QUAT_Y
Orientation Quaternion Y (global/navigation frame)
@ IMU_YAW
orientation yaw absolute value (global/navigation frame) (rad)
@ IMU_ORI_QUAT_X
Orientation Quaternion X (global/navigation frame)
@ IMU_TEMPERATURE
temperature (degrees Celsius)
@ IMU_Y
y absolute value (global/navigation frame) (meters)
@ IMU_X_VEL
x-axis velocity (global/navigation frame) (m/sec)
@ IMU_Z_ACC
z-axis acceleration (local/vehicle frame) (m/sec2)
@ IMU_Z
z absolute value (global/navigation frame) (meters)
@ IMU_ORI_QUAT_Z
Orientation Quaternion Z (global/navigation frame)
@ IMU_Z_VEL
z-axis velocity (global/navigation frame) (m/sec)
@ IMU_PITCH_VEL_GLOBAL
pitch angular velocity (global/navigation frame) (rad/sec)
@ IMU_ROLL_VEL
roll angular velocity (local/vehicle frame) (rad/sec)
@ IMU_YAW_VEL
yaw angular velocity (local/vehicle frame) (rad/sec)
@ IMU_MAG_X
x magnetic field value (local/vehicle frame) (gauss)
@ IMU_Y_ACC
y-axis acceleration (local/vehicle frame) (m/sec2)
@ IMU_Y_VEL
y-axis velocity (global/navigation frame) (m/sec)
@ IMU_ROLL
orientation roll absolute value (global/navigation frame) (rad)
@ IMU_Z_ACC_GLOBAL
z-axis acceleration (global/navigation frame) (m/sec2)
std::vector< bool > vector_bool
A type for passing a vector of bools.
Definition: types_simple.h:29
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
Definition: mrpt_macros.h:28
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.



Page generated by Doxygen 1.9.1 for MRPT 1.4.0 SVN: at Mon Apr 18 03:44:04 UTC 2022