Namespaces | Classes | Typedefs | Enumerations | Functions
hector_pose_estimation Namespace Reference

Namespaces

namespace  filter
namespace  traits

Classes

class  AccelerometerModel
class  Alias
class  AliasT
class  Baro
class  BaroModel
class  BaroUpdate
class  Collection
class  ColumnVector_
class  Filter
struct  functor_wrapper
class  GenericQuaternionSystemModel
class  GlobalReference
class  GPS
class  GPSModel
struct  GPSUpdate
class  GravityModel
class  GroundVehicleModel
class  GyroModel
class  HeadingModel
class  Height
class  HeightBaroCommon
class  HeightModel
class  ImuInput
class  Input
class  Input_
class  Magnetic
class  MagneticModel
class  Matrix_
class  Measurement
class  Measurement_
class  MeasurementModel
class  MeasurementModel_
class  MeasurementUpdate
class  Model
class  Parameter
class  ParameterList
struct  ParameterRegistry
struct  ParameterRegistryROS
class  ParameterT
class  PoseEstimation
class  PoseUpdate
class  PositionXYModel
class  PositionZModel
class  Queue
class  Queue_
class  RateModel
class  RowVector_
class  State
class  SubState
class  SubState_
class  SubSystemModel_
class  SubSystemModel_< 0 >
class  SymmetricMatrix
class  SymmetricMatrix_
class  System
class  System_
class  SystemModel
class  SystemModel_
class  TimeContinuousSystemModel_
class  TimeDiscreteSystemModel_
class  TwistModel
class  Update_
class  YawModel
class  ZeroRateModel

Typedefs

typedef System_
< AccelerometerModel
Accelerometer
typedef SubState_< 0 > BaseState
typedef Eigen::Matrix
< ScalarType, Dynamic, 1 > 
ColumnVector
typedef ColumnVector_< 3 > ColumnVector3
typedef VectorBlock< const
ColumnVector, 3 > 
ConstVectorBlock3
typedef VectorBlock< const
ColumnVector, 4 > 
ConstVectorBlock4
typedef boost::shared_ptr
< GlobalReference
GlobalReferencePtr
typedef Measurement_
< GravityModel
Gravity
typedef System_< GyroModelGyro
typedef Measurement_
< HeadingModel
Heading
typedef Eigen::DenseIndex IndexType
typedef boost::shared_ptr< InputInputPtr
typedef Collection< InputInputs
typedef boost::weak_ptr< InputInputWPtr
typedef Eigen::Matrix
< ScalarType, Dynamic, Dynamic > 
Matrix
typedef Matrix_< 3, 3 > Matrix3
typedef Eigen::Block< Matrix,
Dynamic, Dynamic > 
MatrixBlock
typedef boost::shared_ptr
< Measurement
MeasurementPtr
typedef Collection< MeasurementMeasurements
typedef boost::weak_ptr
< Measurement
MeasurementWPtr
typedef boost::shared_ptr
< const Parameter
ParameterConstPtr
typedef boost::shared_ptr
< Parameter
ParameterPtr
typedef boost::function< void(ParameterPtr)> ParameterRegisterFunc
typedef Eigen::Quaternion
< ScalarType
Quaternion
typedef Measurement_< RateModelRate
typedef Eigen::Matrix
< ScalarType, 1, Dynamic > 
RowVector
typedef RowVector_< 3 > RowVector3
typedef double ScalarType
typedef boost::shared_ptr
< SubState
SubStatePtr
typedef boost::weak_ptr< SubStateSubStateWPtr
typedef SymmetricMatrix_< 3 > SymmetricMatrix3
typedef boost::shared_ptr< SystemSystemPtr
typedef Collection< SystemSystems
typedef unsigned int SystemStatus
typedef boost::weak_ptr< SystemSystemWPtr
typedef VectorBlock
< ColumnVector, 3 > 
VectorBlock3
typedef VectorBlock
< ColumnVector, 4 > 
VectorBlock4
typedef Measurement_
< ZeroRateModel
ZeroRate

Enumerations

enum  {
  STATUS_ALIGNMENT = 0x1, STATUS_DEGRADED = 0x2, STATUS_READY = 0x4, STATUS_MASK = 0xf,
  STATE_ROLLPITCH = 0x10, STATE_YAW = 0x20, STATE_RATE_XY = 0x100, STATE_RATE_Z = 0x200,
  STATE_VELOCITY_XY = 0x1000, STATE_VELOCITY_Z = 0x2000, STATE_POSITION_XY = 0x10000, STATE_POSITION_Z = 0x20000,
  STATE_MASK = 0x33330, STATE_PSEUDO_ROLLPITCH = 0x40, STATE_PSEUDO_YAW = 0x80, STATE_PSEUDO_RATE_XY = 0x400,
  STATE_PSEUDO_RATE_Z = 0x800, STATE_PSEUDO_VELOCITY_XY = 0x4000, STATE_PSEUDO_VELOCITY_Z = 0x8000, STATE_PSEUDO_POSITION_XY = 0x40000,
  STATE_PSEUDO_POSITION_Z = 0x80000, STATE_PSEUDO_MASK = 0xcccc0
}

Functions

std::string getSystemStatusString (const SystemStatus &status, const SystemStatus &asterisk_status=0)
static ParameterList operator+ (ParameterList const &list1, ParameterList const &list2)
static std::ostream & operator<< (std::ostream &os, const SystemStatus &status)
template<typename T >
std::ostream & operator<< (std::ostream &os, const std::vector< T > &vector)

Typedef Documentation

Definition at line 100 of file imu_model.h.

Definition at line 100 of file types.h.

typedef Eigen::Matrix<ScalarType,Dynamic,1> hector_pose_estimation::ColumnVector

Definition at line 46 of file matrix.h.

Definition at line 79 of file matrix.h.

Definition at line 54 of file matrix.h.

Definition at line 55 of file matrix.h.

Definition at line 105 of file types.h.

Definition at line 61 of file gravity.h.

Definition at line 97 of file imu_model.h.

Definition at line 54 of file heading.h.

typedef Eigen::DenseIndex hector_pose_estimation::IndexType

Definition at line 45 of file matrix.h.

typedef boost::shared_ptr<Input> hector_pose_estimation::InputPtr

Definition at line 90 of file types.h.

Definition at line 93 of file types.h.

typedef boost::weak_ptr<Input> hector_pose_estimation::InputWPtr

Definition at line 92 of file types.h.

typedef Eigen::Matrix<ScalarType,Dynamic,Dynamic> hector_pose_estimation::Matrix

Definition at line 48 of file matrix.h.

Definition at line 123 of file matrix.h.

typedef Eigen::Block<Matrix,Dynamic,Dynamic> hector_pose_estimation::MatrixBlock

Definition at line 58 of file matrix.h.

Definition at line 85 of file types.h.

Definition at line 88 of file types.h.

Definition at line 87 of file types.h.

typedef boost::shared_ptr<const Parameter> hector_pose_estimation::ParameterConstPtr

Definition at line 43 of file parameters.h.

typedef boost::shared_ptr<Parameter> hector_pose_estimation::ParameterPtr

Definition at line 41 of file parameters.h.

Definition at line 44 of file parameters.h.

typedef Eigen::Quaternion<ScalarType> hector_pose_estimation::Quaternion

Definition at line 49 of file matrix.h.

Definition at line 57 of file rate.h.

typedef Eigen::Matrix<ScalarType,1,Dynamic> hector_pose_estimation::RowVector

Definition at line 47 of file matrix.h.

Definition at line 100 of file matrix.h.

Definition at line 44 of file matrix.h.

typedef boost::shared_ptr<SubState> hector_pose_estimation::SubStatePtr

Definition at line 102 of file types.h.

Definition at line 103 of file types.h.

Definition at line 278 of file matrix.h.

typedef boost::shared_ptr<System> hector_pose_estimation::SystemPtr

Definition at line 77 of file types.h.

Definition at line 80 of file types.h.

Definition at line 66 of file types.h.

typedef boost::weak_ptr<System> hector_pose_estimation::SystemWPtr

Definition at line 79 of file types.h.

Definition at line 52 of file matrix.h.

Definition at line 53 of file matrix.h.

Definition at line 62 of file zerorate.h.


Enumeration Type Documentation

anonymous enum
Enumerator:
STATUS_ALIGNMENT 
STATUS_DEGRADED 
STATUS_READY 
STATUS_MASK 
STATE_ROLLPITCH 
STATE_YAW 
STATE_RATE_XY 
STATE_RATE_Z 
STATE_VELOCITY_XY 
STATE_VELOCITY_Z 
STATE_POSITION_XY 
STATE_POSITION_Z 
STATE_MASK 
STATE_PSEUDO_ROLLPITCH 
STATE_PSEUDO_YAW 
STATE_PSEUDO_RATE_XY 
STATE_PSEUDO_RATE_Z 
STATE_PSEUDO_VELOCITY_XY 
STATE_PSEUDO_VELOCITY_Z 
STATE_PSEUDO_POSITION_XY 
STATE_PSEUDO_POSITION_Z 
STATE_PSEUDO_MASK 

Definition at line 40 of file types.h.


Function Documentation

std::string hector_pose_estimation::getSystemStatusString ( const SystemStatus &  status,
const SystemStatus &  asterisk_status = 0 
)

Definition at line 33 of file types.cpp.

static ParameterList hector_pose_estimation::operator+ ( ParameterList const &  list1,
ParameterList const &  list2 
) [inline, static]

Definition at line 182 of file parameters.h.

static std::ostream& hector_pose_estimation::operator<< ( std::ostream &  os,
const SystemStatus &  status 
) [inline, static]

Definition at line 69 of file types.h.

template<typename T >
std::ostream& hector_pose_estimation::operator<< ( std::ostream &  os,
const std::vector< T > &  vector 
)

Definition at line 146 of file parameters.cpp.



hector_pose_estimation_core
Author(s): Johannes Meyer
autogenerated on Mon Oct 6 2014 00:24:16