Main MRPT website > C++ reference
MRPT logo
Public Member Functions | Public Attributes

mrpt::slam::CObservationIMU Class Reference


Detailed Description

This class stores measurements from an Inertial Measurement Unit (IMU), and/or its attitude estimation (integration of raw measurements).

The order of the 15 raw values in each entry of mrpt::slam::CObservationIMU::rawMeasurements is (you can use the TIMUDataIndex "enum" symbolic names):

0 IMU_X_ACC x-axis acceleration (m/sec2)
1 IMU_Y_ACC y-axis acceleration (m/sec2)
2 IMU_Z_ACC z-axis acceleration (m/sec2)
3 IMU_YAW_VEL yaw angular velocity (rad/sec)
4 IMU_PITCH_VEL pitch angular velocity (rad/sec)
5 IMU_ROLL_VEL roll angular velocity (rad/sec)
6 IMU_X_VEL x-axis velocity (m/sec)
7 IMU_Y_VEL y-axis velocity (m/sec)
8 IMU_Z_VEL z-axis velocity (m/sec)
9 IMU_YAW yaw absolute value (rad)
10 IMU_PITCH pitch absolute value (rad)
11 IMU_ROLL roll absolute value (rad)
12 IMU_X x absolute value (meters)
13 IMU_Y y absolute value (meters)
14 IMU_Z z absolute value (meters)

The first 6 values are directly measured by accelerometers & gyroscopes. The rest, if present, are estimates from the IMU unit.

See also:
CObservation

Definition at line 90 of file CObservationIMU.h.

#include <mrpt/slam/CObservationIMU.h>

Inheritance diagram for mrpt::slam::CObservationIMU:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 CObservationIMU ()
 Constructor.
virtual ~CObservationIMU ()
 Destructor.
void getSensorPose (CPose3D &out_sensorPose) const
 A general method to retrieve the sensor pose on the robot.
void setSensorPose (const CPose3D &newSensorPose)
 A general method to change the sensor pose on the robot.

Public Attributes

CPose3D sensorPose
 The pose of the sensor on the robot.
vector_bool dataIsPresent
 Each of the 15 entries of this vector is true if the corresponding data index contains valid data (the IMU unit supplies that kind of data).
std::vector< double > rawMeasurements
 The accelerometer and/or gyroscope measurements taken by the IMU at the given timestamp.

RTTI stuff

typedef CObservationIMUPtr SmartPtr
static mrpt::utils::CLASSINIT _init_CObservationIMU
static mrpt::utils::TRuntimeClassId classCObservationIMU
static const
mrpt::utils::TRuntimeClassId
classinfo
static const
mrpt::utils::TRuntimeClassId
_GetBaseClass ()
virtual const
mrpt::utils::TRuntimeClassId
GetRuntimeClass () const
 Returns information about the class of an object in runtime.
virtual mrpt::utils::CObjectduplicate () const
 Returns a copy of the object, indepently of its class.
static mrpt::utils::CObjectCreateObject ()
static CObservationIMUPtr Create ()

Member Typedef Documentation

A typedef for the associated smart pointer

Definition at line 93 of file CObservationIMU.h.


Constructor & Destructor Documentation

mrpt::slam::CObservationIMU::CObservationIMU (  ) [inline]

Constructor.

Definition at line 98 of file CObservationIMU.h.

virtual mrpt::slam::CObservationIMU::~CObservationIMU (  ) [inline, virtual]

Destructor.

Definition at line 106 of file CObservationIMU.h.


Member Function Documentation

static const mrpt::utils::TRuntimeClassId* mrpt::slam::CObservationIMU::_GetBaseClass (  ) [static, protected]

Reimplemented from mrpt::slam::CObservation.

static CObservationIMUPtr mrpt::slam::CObservationIMU::Create (  ) [static]
static mrpt::utils::CObject* mrpt::slam::CObservationIMU::CreateObject (  ) [static]
virtual mrpt::utils::CObject* mrpt::slam::CObservationIMU::duplicate (  ) const [virtual]

Returns a copy of the object, indepently of its class.

Implements mrpt::utils::CObject.

virtual const mrpt::utils::TRuntimeClassId* mrpt::slam::CObservationIMU::GetRuntimeClass (  ) const [virtual]

Returns information about the class of an object in runtime.

Reimplemented from mrpt::slam::CObservation.

void mrpt::slam::CObservationIMU::getSensorPose ( CPose3D out_sensorPose ) const [inline, virtual]

A general method to retrieve the sensor pose on the robot.

Note that most sensors will return a full (6D) CPose3D, but see the derived classes for more details or special cases.

See also:
setSensorPose

Implements mrpt::slam::CObservation.

Definition at line 128 of file CObservationIMU.h.

void mrpt::slam::CObservationIMU::setSensorPose ( const CPose3D newSensorPose ) [inline, virtual]

A general method to change the sensor pose on the robot.

Note that most sensors will use the full (6D) CPose3D, but see the derived classes for more details or special cases.

See also:
getSensorPose

Implements mrpt::slam::CObservation.

Definition at line 135 of file CObservationIMU.h.


Member Data Documentation

Definition at line 93 of file CObservationIMU.h.

Definition at line 93 of file CObservationIMU.h.

Definition at line 93 of file CObservationIMU.h.

Each of the 15 entries of this vector is true if the corresponding data index contains valid data (the IMU unit supplies that kind of data).

See the top of this page for the meaning of the indices.

Definition at line 116 of file CObservationIMU.h.

The accelerometer and/or gyroscope measurements taken by the IMU at the given timestamp.

See also:
dataIsPresent, CObservation::timestamp

Definition at line 121 of file CObservationIMU.h.

The pose of the sensor on the robot.

Definition at line 111 of file CObservationIMU.h.




Page generated by Doxygen 1.7.2 for MRPT 0.9.4 SVN: at Mon Jan 10 22:30:30 UTC 2011