MRPT logo

mrpt::slam::CObservationIMU Class Reference

This class stores both sequences of raw measurements from an IMU, and/or its attitude estimation (integration of raw measurements). More...

#include <mrpt/slam/CObservationIMU.h>

Inheritance diagram for mrpt::slam::CObservationIMU:

mrpt::slam::CObservation mrpt::utils::CSerializable

List of all members.

Public Member Functions

 CObservationIMU ()
 Constructor.
virtual ~CObservationIMU ()
 Destructor.
float likelihoodWith (const CObservation *anotherObs, const CPosePDF *anotherObsPose=NULL) const
 Implements the virtual method in charge of finding the likelihood between this and another observation, probably only of the same derived class.
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 sequence of accelerometers/gyroscopes measurements in time.


Detailed Description

This class stores both sequences of raw measurements from an 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 "enum" symbolic names):
0 IMU_X_ACC x-axis acceleration (m/sec²)
1 IMU_Y_ACC y-axis acceleration (m/sec²)
2 IMU_Z_ACC z-axis acceleration (m/sec²)
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.


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

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 143 of file CObservationIMU.h.

float mrpt::slam::CObservationIMU::likelihoodWith ( const CObservation anotherObs,
const CPosePDF anotherObsPose = NULL 
) const [virtual]

Implements the virtual method in charge of finding the likelihood between this and another observation, probably only of the same derived class.

The operator may be asymmetric.

Parameters:
anotherObs The other observation to compute likelihood with.
anotherObsPose If known, the belief about the robot pose when the other observation was taken can be supplied here, or NULL if it is unknown.
Returns:
Returns a likelihood measurement, in the range [0,1].
Exceptions:
std::exception On any error, as another observation being of an invalid class.

Implements mrpt::slam::CObservation.

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 150 of file CObservationIMU.h.


Member Data Documentation

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 sequence of accelerometers/gyroscopes measurements in time.

Each entry of rawMeasurements is a sequence of 15 values for each instant of time, and the time between entries is fixed, starting in the CObservation::timestamp, and with a sampling period of periodBetweenMeasurements. See the top of this page for further details on the contents of the vector.

See also:
hasRawMeasurements,periodBetweenMeasurements

Definition at line 124 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.5.8 for MRPT 0.6.5 SVN:exported at Mon Jan 12 13:00:16 UTC 2009