Public Types | Public Member Functions | Static Public Member Functions | Private Attributes
hector_pose_estimation::State Class Reference

#include <state.h>

List of all members.

Public Types

typedef VectorBlock< Vector, 3 > AccelerationType
typedef VectorBlock< const
Vector, 3 > 
ConstAccelerationType
typedef Block< const
Covariance::Base, Dimension,
Dimension
ConstCovarianceBlock
typedef VectorBlock< const
Vector, 4 > 
ConstOrientationType
typedef VectorBlock< const
Vector, 3 > 
ConstPositionType
typedef VectorBlock< const
Vector, 3 > 
ConstRateType
typedef VectorBlock< const
Vector, Dimension
ConstVectorSegment
typedef VectorBlock< const
Vector, 3 > 
ConstVelocityType
typedef SymmetricMatrix Covariance
typedef Block
< Covariance::Base, Dimension,
Dimension
CovarianceBlock
typedef VectorBlock< Vector, 4 > OrientationType
typedef VectorBlock< Vector, 3 > PositionType
typedef VectorBlock< Vector, 3 > RateType
typedef Matrix_< 3, 3 > RotationMatrix
enum  StateIndex {
  QUATERNION_X = 0, QUATERNION_Y, QUATERNION_Z, QUATERNION_W,
  POSITION_X, POSITION_Y, POSITION_Z, VELOCITY_X,
  VELOCITY_Y, VELOCITY_Z, Dimension, RATE_X = -1,
  RATE_Y = -1, RATE_Z = -1, ACCELERATION_X = -1, ACCELERATION_Y = -1,
  ACCELERATION_Z = -1
}
typedef std::vector< SubStatePtrSubStates
typedef boost::function< bool(SystemStatus &)> SystemStatusCallback
typedef ColumnVector Vector
enum  VectorIndex { X = 0, Y = 1, Z = 2, W = 3 }
typedef VectorBlock< Vector,
Dimension
VectorSegment
typedef VectorBlock< Vector, 3 > VelocityType

Public Member Functions

virtual AccelerationType acceleration ()
template<int SubDimension>
boost::shared_ptr< SubState_
< SubDimension > > 
addSubState (const Model *model, const std::string &name=std::string())
virtual void addSystemStatusCallback (const SystemStatusCallback &callback)
virtual BaseStatebase ()
virtual const BaseStatebase () const
virtual ConstAccelerationType getAcceleration () const
virtual IndexType getAccelerationIndex () const
virtual const CovariancegetCovariance () const
virtual IndexType getDimension () const
virtual SystemStatus getMeasurementStatus () const
virtual ConstOrientationType getOrientation () const
virtual IndexType getOrientationIndex () const
virtual ConstPositionType getPosition () const
virtual IndexType getPositionIndex () const
virtual ConstRateType getRate () const
virtual IndexType getRateIndex () const
RotationMatrix getRotationMatrix () const
void getRotationMatrix (RotationMatrix &R) const
template<int Size>
VectorBlock< const Vector, Size > getSegment (IndexType start) const
template<int SubDimension>
boost::shared_ptr< SubState_
< SubDimension > > 
getSubState (const Model *model) const
template<int SubDimension>
boost::shared_ptr< SubState_
< SubDimension > > 
getSubState (const std::string &name) const
const SubStatesgetSubStates () const
virtual SystemStatus getSystemStatus () const
const ros::TimegetTimestamp () const
virtual const VectorgetVector () const
virtual ConstVelocityType getVelocity () const
virtual IndexType getVelocityIndex () const
double getYaw () const
virtual bool inSystemStatus (SystemStatus test_status) const
virtual double normalize ()
virtual OrientationType orientation ()
virtual CovarianceP ()
virtual CovarianceBlock P0 ()
virtual PositionType position ()
virtual RateType rate ()
virtual void reset ()
template<typename Derived >
void setAcceleration (const Eigen::MatrixBase< Derived > &acceleration)
virtual bool setMeasurementStatus (SystemStatus new_status)
template<typename Derived >
void setOrientation (const Eigen::MatrixBase< Derived > &orientation)
template<typename Derived >
void setPosition (const Eigen::MatrixBase< Derived > &position)
template<typename Derived >
void setRate (const Eigen::MatrixBase< Derived > &rate)
virtual bool setSystemStatus (SystemStatus new_status)
void setTimestamp (const ros::Time &timestamp)
template<typename Derived >
void setVelocity (const Eigen::MatrixBase< Derived > &velocity)
 State ()
 State (const Vector &vector, const Covariance &covariance)
virtual void updated ()
virtual bool updateMeasurementStatus (SystemStatus set, SystemStatus clear)
virtual bool updateSystemStatus (SystemStatus set, SystemStatus clear)
virtual bool valid () const
virtual VelocityType velocity ()
virtual Vectorx ()
virtual VectorSegment x0 ()
virtual ~State ()

Static Public Member Functions

static IndexType getDimension0 ()

Private Attributes

boost::shared_ptr< BaseStatebase_
Covariance covariance_
Vector fake_acceleration_
Vector fake_orientation_
Vector fake_position_
Vector fake_rate_
Vector fake_velocity_
SystemStatus measurement_status_
std::vector< SystemStatusCallbackstatus_callbacks_
SubStates substates_
std::map< const Model
*, SubStateWPtr
substates_by_model_
std::map< std::string,
SubStateWPtr
substates_by_name_
SystemStatus system_status_
ros::Time timestamp_
Vector vector_

Detailed Description

Definition at line 55 of file state.h.


Member Typedef Documentation

Definition at line 107 of file state.h.

Definition at line 108 of file state.h.

Definition at line 97 of file state.h.

Definition at line 100 of file state.h.

Definition at line 104 of file state.h.

Definition at line 102 of file state.h.

Definition at line 96 of file state.h.

Definition at line 106 of file state.h.

Definition at line 93 of file state.h.

Definition at line 95 of file state.h.

Definition at line 99 of file state.h.

Definition at line 103 of file state.h.

Definition at line 101 of file state.h.

Definition at line 112 of file state.h.

Definition at line 110 of file state.h.

Definition at line 149 of file state.h.

Definition at line 92 of file state.h.

Definition at line 94 of file state.h.

Definition at line 105 of file state.h.


Member Enumeration Documentation

Enumerator:
QUATERNION_X 
QUATERNION_Y 
QUATERNION_Z 
QUATERNION_W 
POSITION_X 
POSITION_Y 
POSITION_Z 
VELOCITY_X 
VELOCITY_Y 
VELOCITY_Z 
Dimension 
RATE_X 
RATE_Y 
RATE_Z 
ACCELERATION_X 
ACCELERATION_Y 
ACCELERATION_Z 

Definition at line 64 of file state.h.

Enumerator:
X 
Y 
Z 
W 

Definition at line 57 of file state.h.


Constructor & Destructor Documentation

Definition at line 34 of file state.cpp.

hector_pose_estimation::State::State ( const Vector vector,
const Covariance covariance 
)

Definition at line 42 of file state.cpp.

Definition at line 50 of file state.cpp.


Member Function Documentation

Definition at line 160 of file state.h.

template<int SubDimension>
boost::shared_ptr< SubState_< SubDimension > > hector_pose_estimation::State::addSubState ( const Model model,
const std::string &  name = std::string() 
)

Definition at line 134 of file substate.h.

Definition at line 146 of file state.cpp.

virtual BaseState& hector_pose_estimation::State::base ( ) [inline, virtual]

Definition at line 128 of file state.h.

virtual const BaseState& hector_pose_estimation::State::base ( ) const [inline, virtual]

Definition at line 129 of file state.h.

Definition at line 161 of file state.h.

Definition at line 178 of file state.h.

virtual const Covariance& hector_pose_estimation::State::getCovariance ( ) const [inline, virtual]

Definition at line 132 of file state.h.

virtual IndexType hector_pose_estimation::State::getDimension ( ) const [inline, virtual]

Definition at line 120 of file state.h.

Definition at line 119 of file state.h.

Definition at line 141 of file state.h.

Definition at line 153 of file state.h.

Definition at line 174 of file state.h.

Definition at line 157 of file state.h.

virtual IndexType hector_pose_estimation::State::getPositionIndex ( ) const [inline, virtual]

Definition at line 176 of file state.h.

virtual ConstRateType hector_pose_estimation::State::getRate ( ) const [inline, virtual]

Definition at line 155 of file state.h.

virtual IndexType hector_pose_estimation::State::getRateIndex ( ) const [inline, virtual]

Definition at line 175 of file state.h.

Definition at line 88 of file state.cpp.

Definition at line 94 of file state.cpp.

template<int Size>
VectorBlock<const Vector, Size> hector_pose_estimation::State::getSegment ( IndexType  start) const [inline]

Definition at line 133 of file state.h.

boost::shared_ptr< BaseState > hector_pose_estimation::State::getSubState< 0 > ( const Model model) const [inline]

Definition at line 119 of file substate.h.

template<int SubDimension>
boost::shared_ptr< SubState_< SubDimension > > hector_pose_estimation::State::getSubState ( const std::string &  name) const

Definition at line 129 of file substate.h.

Definition at line 180 of file state.h.

virtual SystemStatus hector_pose_estimation::State::getSystemStatus ( ) const [inline, virtual]

Definition at line 140 of file state.h.

Definition at line 185 of file state.h.

virtual const Vector& hector_pose_estimation::State::getVector ( ) const [inline, virtual]

Definition at line 131 of file state.h.

Definition at line 159 of file state.h.

virtual IndexType hector_pose_estimation::State::getVelocityIndex ( ) const [inline, virtual]

Definition at line 177 of file state.h.

Definition at line 102 of file state.cpp.

bool hector_pose_estimation::State::inSystemStatus ( SystemStatus  test_status) const [virtual]

Definition at line 108 of file state.cpp.

Definition at line 152 of file state.cpp.

Definition at line 152 of file state.h.

virtual Covariance& hector_pose_estimation::State::P ( ) [inline, virtual]

Definition at line 136 of file state.h.

virtual CovarianceBlock hector_pose_estimation::State::P0 ( ) [inline, virtual]

Definition at line 138 of file state.h.

Definition at line 156 of file state.h.

virtual RateType hector_pose_estimation::State::rate ( ) [inline, virtual]

Definition at line 154 of file state.h.

Definition at line 54 of file state.cpp.

template<typename Derived >
void hector_pose_estimation::State::setAcceleration ( const Eigen::MatrixBase< Derived > &  acceleration)

Definition at line 237 of file state.h.

Definition at line 128 of file state.cpp.

template<typename Derived >
void hector_pose_estimation::State::setOrientation ( const Eigen::MatrixBase< Derived > &  orientation)

Definition at line 213 of file state.h.

template<typename Derived >
void hector_pose_estimation::State::setPosition ( const Eigen::MatrixBase< Derived > &  position)

Definition at line 225 of file state.h.

template<typename Derived >
void hector_pose_estimation::State::setRate ( const Eigen::MatrixBase< Derived > &  rate)

Definition at line 219 of file state.h.

Definition at line 112 of file state.cpp.

void hector_pose_estimation::State::setTimestamp ( const ros::Time timestamp) [inline]

Definition at line 186 of file state.h.

template<typename Derived >
void hector_pose_estimation::State::setVelocity ( const Eigen::MatrixBase< Derived > &  velocity)

Definition at line 231 of file state.h.

Definition at line 82 of file state.cpp.

Definition at line 142 of file state.cpp.

Definition at line 138 of file state.cpp.

bool hector_pose_estimation::State::valid ( ) const [virtual]

Definition at line 78 of file state.cpp.

Definition at line 158 of file state.h.

virtual Vector& hector_pose_estimation::State::x ( ) [inline, virtual]

Definition at line 135 of file state.h.

virtual VectorSegment hector_pose_estimation::State::x0 ( ) [inline, virtual]

Definition at line 137 of file state.h.


Member Data Documentation

boost::shared_ptr<BaseState> hector_pose_estimation::State::base_ [private]

Definition at line 207 of file state.h.

Definition at line 190 of file state.h.

Definition at line 199 of file state.h.

Definition at line 195 of file state.h.

Definition at line 197 of file state.h.

Definition at line 196 of file state.h.

Definition at line 198 of file state.h.

Definition at line 193 of file state.h.

Definition at line 201 of file state.h.

Definition at line 203 of file state.h.

Definition at line 204 of file state.h.

Definition at line 205 of file state.h.

Definition at line 192 of file state.h.

Definition at line 209 of file state.h.

Definition at line 189 of file state.h.


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


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