Public Member Functions | Private Member Functions | Private Attributes
PoseMeasurements Class Reference

#include <pose_measurements.h>

Inheritance diagram for PoseMeasurements:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 PoseMeasurements ()

Private Member Functions

void init (double scale)

Private Attributes

Eigen::Matrix< double, 3, 1 > p_ci_
 initial distance camera-IMU
Eigen::Quaternion< double > q_ci_
 initial rotation camera-IMU
Eigen::Quaternion< double > q_wv_
 initial rotation wolrd-vision

Detailed Description

Definition at line 39 of file pose_measurements.h.


Constructor & Destructor Documentation

Definition at line 42 of file pose_measurements.h.


Member Function Documentation

void PoseMeasurements::init ( double  scale) [inline, private, virtual]

gravity

bias gyroscopes

bias accelerometer

robot velocity (IMU centered)

initial angular velocity

initial acceleration

Implements ssf_core::Measurements.

Definition at line 70 of file pose_measurements.h.


Member Data Documentation

Eigen::Matrix<double, 3, 1> PoseMeasurements::p_ci_ [private]

initial distance camera-IMU

Definition at line 66 of file pose_measurements.h.

Eigen::Quaternion<double> PoseMeasurements::q_ci_ [private]

initial rotation camera-IMU

Definition at line 67 of file pose_measurements.h.

Eigen::Quaternion<double> PoseMeasurements::q_wv_ [private]

initial rotation wolrd-vision

Definition at line 68 of file pose_measurements.h.


The documentation for this class was generated from the following file:


ssf_updates
Author(s): Stephan Weiss, Markus Achtelik
autogenerated on Mon Oct 6 2014 10:27:06