#include <imu_input.h>
Public Types | |
typedef Vector::ConstFixedSegmentReturnType< 3 >::Type | AccelerationType |
enum | InputIndex { ACCEL_X = 0, ACCEL_Y, ACCEL_Z, GYRO_X, GYRO_Y, GYRO_Z } |
typedef Vector::ConstFixedSegmentReturnType< 3 >::Type | RateType |
Public Types inherited from hector_pose_estimation::Input_< 6 > | |
enum | |
typedef boost::shared_ptr< Input_< _Dimension > > | Ptr |
typedef Input_< Dimension > | Type |
typedef SymmetricMatrix_< Dimension >::type | Variance |
typedef ColumnVector_< Dimension >::type | Vector |
Public Member Functions | |
AccelerationType | getAcceleration () const |
virtual const std::string & | getName () const |
RateType | getRate () const |
ImuInput () | |
ImuInput (const sensor_msgs::Imu &imu) | |
ImuInput & | operator= (const sensor_msgs::Imu &imu) |
virtual | ~ImuInput () |
Public Member Functions inherited from hector_pose_estimation::Input_< 6 > | |
virtual int | getDimension () const |
virtual Variance const & | getVariance () |
virtual Variance const & | getVariance () const |
virtual Vector const & | getVector () const |
virtual bool | hasVariance () const |
Input_ () | |
Input_ (const Eigen::MatrixBase< Derived > &u) | |
Input_ (const Eigen::MatrixBase< Derived > &u, const Variance &Q) | |
Input_ (double u) | |
Input_ (double u, const Variance &Q) | |
Input_ (const Input &other) | |
virtual Input_< Dimension > & | operator= (const Input &other) |
virtual Input_< Dimension > & | operator= (const Input_< Dimension > &other) |
Vector & | operator= (const Eigen::MatrixBase< Derived > &other) |
virtual Vector & | operator= (double u) |
virtual Variance & | setVariance (const Variance &other) |
virtual Vector & | u () |
virtual Variance & | variance () |
virtual | ~Input_ () |
Public Member Functions inherited from hector_pose_estimation::Input | |
Input () | |
virtual void | setName (const std::string &name) |
virtual | ~Input () |
Additional Inherited Members | |
Protected Attributes inherited from hector_pose_estimation::Input_< 6 > | |
Vector | u_ |
boost::shared_ptr< Variance > | variance_ |
Definition at line 39 of file imu_input.h.
typedef Vector::ConstFixedSegmentReturnType<3>::Type hector_pose_estimation::ImuInput::AccelerationType |
Definition at line 50 of file imu_input.h.
typedef Vector::ConstFixedSegmentReturnType<3>::Type hector_pose_estimation::ImuInput::RateType |
Definition at line 51 of file imu_input.h.
Enumerator | |
---|---|
ACCEL_X | |
ACCEL_Y | |
ACCEL_Z | |
GYRO_X | |
GYRO_Y | |
GYRO_Z |
Definition at line 42 of file imu_input.h.
|
inline |
Definition at line 53 of file imu_input.h.
|
inline |
Definition at line 54 of file imu_input.h.
|
inlinevirtual |
Definition at line 55 of file imu_input.h.
|
inline |
Definition at line 71 of file imu_input.h.
|
inlinevirtual |
Reimplemented from hector_pose_estimation::Input.
Definition at line 57 of file imu_input.h.
|
inline |
Definition at line 72 of file imu_input.h.
|
inline |
Definition at line 59 of file imu_input.h.