9 #ifndef CObservationIMU_H 10 #define CObservationIMU_H 110 void getDescriptionAsText(std::ostream &o)
const MRPT_OVERRIDE;
x-axis acceleration (global/navigation frame) (m/sec2)
z-axis acceleration (global/navigation frame) (m/sec2)
yaw angular velocity (global/navigation frame) (rad/sec)
std::vector< double > rawMeasurements
The accelerometer and/or gyroscope measurements taken by the IMU at the given timestamp.
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
orientation pitch absolute value (global/navigation frame) (rad)
void setSensorPose(const mrpt::poses::CPose3D &newSensorPose) MRPT_OVERRIDE
A general method to change the sensor pose on the robot.
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)
void getSensorPose(mrpt::poses::CPose3D &out_sensorPose) const MRPT_OVERRIDE
A general method to retrieve the sensor pose on the robot.
x-axis velocity (global/navigation frame) (m/sec)
virtual ~CObservationIMU()
Destructor.
std::vector< bool > vector_bool
A type for passing a vector of bools.
roll angular velocity (global/navigation frame) (rad/sec)
pitch angular velocity (local/vehicle frame) (rad/sec)
#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...
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).
Declares a class that represents any robot's observation.
y-axis acceleration (global/navigation frame) (m/sec2)
CObservationIMU()
Constructor.
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)
roll angular velocity (local/vehicle frame) (rad/sec)
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
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)