$search

hector_pose_estimation Namespace Reference

Namespaces

namespace  internal

Classes

class  Baro
class  BaroModel
class  BaroUpdate
class  ColumnVector_
struct  functor_wrapper
class  GenericQuaternionSystemModel
class  GlobalReference
class  GPS
class  GPSModel
struct  GPSUpdate
class  Gravity
class  GravityModel
class  HeadingModel
class  Height
class  HeightBaroCommon
class  HeightModel
class  ImuInput
class  Input_
struct  Input_< GenericQuaternionSystemModel >
class  Magnetic
class  MagneticModel
class  Matrix_
class  Measurement
class  Measurement_
class  MeasurementModel
class  MeasurementUpdate
class  Parameter
class  ParameterList
class  PoseEstimation
class  PoseUpdate
class  PositionXYModel
class  PositionZModel
class  Queue
class  Queue_
class  RateModel
class  RegisterParameterImpl
class  RowVector_
class  SymmetricMatrix_
class  System
class  System_
class  SystemInput
class  SystemModel
class  TwistModel
class  TypedParameter
class  Update_
class  YawModel
class  ZeroRateModel

Typedefs

typedef Measurement_
< HeadingModel
Heading
typedef boost::shared_ptr
< Measurement
MeasurementPtr
typedef boost::shared_ptr
< const Parameter
ParameterConstPtr
typedef boost::shared_ptr
< Parameter
ParameterPtr
typedef boost::function< void(ParameterPtr)> ParameterRegisterFunc
typedef Measurement_< RateModelRate
typedef SymmetricMatrix_
< StateDimension
StateCovariance
typedef ColumnVector_
< StateDimension
StateVector
typedef boost::shared_ptr< SystemSystemPtr
typedef unsigned int SystemStatus
typedef Measurement_
< ZeroRateModel
ZeroRate

Enumerations

enum  {
  STATE_ALIGNMENT = 1, STATE_DEGRADED = 2, STATE_READY = 4, STATE_ROLLPITCH = 8,
  STATE_YAW = 16, STATE_XY_VELOCITY = 32, STATE_XY_POSITION = 64, STATE_Z_VELOCITY = 128,
  STATE_Z_POSITION = 256, STATE_ALL = -1
}
enum  StateIndex {
  QUATERNION_W = 1, QUATERNION_X, QUATERNION_Y, QUATERNION_Z,
  POSITION_X, POSITION_Y, POSITION_Z, VELOCITY_X,
  VELOCITY_Y, VELOCITY_Z, BIAS_ACCEL_X, BIAS_ACCEL_Y,
  BIAS_ACCEL_Z, BIAS_GYRO_X, BIAS_GYRO_Y, BIAS_GYRO_Z
}

Functions

void covarianceBflToMsg (MatrixWrapper::SymmetricMatrix const &bfl, geometry_msgs::PoseWithCovariance::_covariance_type &msg)
void covarianceMsgToBfl (geometry_msgs::PoseWithCovariance::_covariance_type const &msg, MatrixWrapper::SymmetricMatrix_Wrapper &bfl)
std::string getSystemStatusString (const SystemStatus &status)
static ParameterList operator+ (ParameterList const &list1, ParameterList const &list2)
static std::ostream & operator<< (std::ostream &os, const SystemStatus &status)
void pointBflToMsg (MatrixWrapper::ColumnVector_Wrapper const &bfl, geometry_msgs::Point &msg)
void pointMsgToBfl (geometry_msgs::Point const &msg, MatrixWrapper::ColumnVector_Wrapper &bfl)
void quaternionBflToMsg (MatrixWrapper::ColumnVector_Wrapper const &bfl, geometry_msgs::Quaternion &msg)
void quaternionMsgToBfl (geometry_msgs::Quaternion const &msg, MatrixWrapper::ColumnVector_Wrapper &bfl)
static void registerParamRos (ParameterPtr &parameter, ros::NodeHandle nh)

Variables

static const double GRAVITY = -9.8065
static const unsigned int StateDimension = BIAS_GYRO_Z
static const char *const SystemStatusStrings []

Typedef Documentation

Definition at line 58 of file heading.h.

Definition at line 93 of file measurement.h.

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

Definition at line 47 of file parameters.h.

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

Definition at line 45 of file parameters.h.

Definition at line 48 of file parameters.h.

Definition at line 55 of file rate.h.

Definition at line 64 of file types.h.

Definition at line 63 of file types.h.

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

Definition at line 81 of file system.h.

Definition at line 80 of file types.h.

Definition at line 56 of file zerorate.h.


Enumeration Type Documentation

anonymous enum
Enumerator:
STATE_ALIGNMENT 
STATE_DEGRADED 
STATE_READY 
STATE_ROLLPITCH 
STATE_YAW 
STATE_XY_VELOCITY 
STATE_XY_POSITION 
STATE_Z_VELOCITY 
STATE_Z_POSITION 
STATE_ALL 

Definition at line 66 of file types.h.

Enumerator:
QUATERNION_W 
QUATERNION_X 
QUATERNION_Y 
QUATERNION_Z 
POSITION_X 
POSITION_Y 
POSITION_Z 
VELOCITY_X 
VELOCITY_Y 
VELOCITY_Z 
BIAS_ACCEL_X 
BIAS_ACCEL_Y 
BIAS_ACCEL_Z 
BIAS_GYRO_X 
BIAS_GYRO_Y 
BIAS_GYRO_Z 

Definition at line 39 of file types.h.


Function Documentation

void hector_pose_estimation::covarianceBflToMsg ( MatrixWrapper::SymmetricMatrix const &  bfl,
geometry_msgs::PoseWithCovariance::_covariance_type msg 
)

Definition at line 46 of file bfl_conversions.h.

void hector_pose_estimation::covarianceMsgToBfl ( geometry_msgs::PoseWithCovariance::_covariance_type const &  msg,
MatrixWrapper::SymmetricMatrix_Wrapper bfl 
)

Definition at line 38 of file bfl_conversions.h.

std::string hector_pose_estimation::getSystemStatusString ( const SystemStatus &  status  ) 

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

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

Definition at line 86 of file types.h.

void hector_pose_estimation::pointBflToMsg ( MatrixWrapper::ColumnVector_Wrapper const &  bfl,
geometry_msgs::Point msg 
)

Definition at line 60 of file bfl_conversions.h.

void hector_pose_estimation::pointMsgToBfl ( geometry_msgs::Point const &  msg,
MatrixWrapper::ColumnVector_Wrapper bfl 
)

Definition at line 53 of file bfl_conversions.h.

void hector_pose_estimation::quaternionBflToMsg ( MatrixWrapper::ColumnVector_Wrapper const &  bfl,
geometry_msgs::Quaternion msg 
)

Definition at line 74 of file bfl_conversions.h.

void hector_pose_estimation::quaternionMsgToBfl ( geometry_msgs::Quaternion const &  msg,
MatrixWrapper::ColumnVector_Wrapper bfl 
)

Definition at line 66 of file bfl_conversions.h.

static void hector_pose_estimation::registerParamRos ( ParameterPtr &  parameter,
ros::NodeHandle  nh 
) [static]

Definition at line 56 of file parameters.cpp.


Variable Documentation

const double hector_pose_estimation::GRAVITY = -9.8065 [static]

Definition at line 33 of file generic_quaternion_system_model.cpp.

const unsigned int hector_pose_estimation::StateDimension = BIAS_GYRO_Z [static]

Definition at line 62 of file types.h.

const char* const hector_pose_estimation::SystemStatusStrings[] [static]
Initial value:
 {
    "ALIGNMENT", "DEGRADED", "READY", "ROLLPITCH", "YAW", "XY_VELOCITY", "XY_POSITION", "Z_VELOCITY", "Z_POSITION"
  }

Definition at line 82 of file types.h.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


hector_pose_estimation_core
Author(s): Johannes Meyer
autogenerated on Tue Mar 5 12:32:35 2013