9#ifndef CObservationIMU_H
10#define CObservationIMU_H
#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.
CObservationIMU()
Constructor.
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).
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.
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.