Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
hector_pose_estimation::State Class Reference

#include <state.h>

Inheritance diagram for hector_pose_estimation::State:
Inheritance graph
[legend]

Public Types

typedef SubState_< 3, 3 > AccelerationStateType
 
typedef VectorBlock< Vector, 3 > AccelerationType
 
typedef VectorBlock< const Vector, 3 > ConstAccelerationType
 
typedef Block< const Covariance::Base > ConstCovarianceBlock
 
typedef VectorBlock< const Vector, 4 > ConstOrientationType
 
typedef VectorBlock< const Vector, 3 > ConstPositionType
 
typedef VectorBlock< const Vector, 3 > ConstRateType
 
typedef VectorBlock< const VectorConstVectorSegment
 
typedef VectorBlock< const Vector, 3 > ConstVelocityType
 
typedef SymmetricMatrix Covariance
 
typedef Block< Covariance::Base > CovarianceBlock
 
typedef SubState_< 4, 3 > OrientationStateType
 
typedef VectorBlock< Vector, 4 > OrientationType
 
typedef SubState_< 3, 3 > PositionStateType
 
typedef VectorBlock< Vector, 3 > PositionType
 
typedef SubState_< 3, 3 > RateStateType
 
typedef VectorBlock< Vector, 3 > RateType
 
typedef Matrix_< 3, 3 >::type RotationMatrix
 
typedef std::vector< SubStatePtrSubStates
 
typedef Matrix SystemMatrix
 
typedef boost::function< bool(SystemStatus &)> SystemStatusCallback
 
typedef ColumnVector Vector
 
typedef VectorBlock< VectorVectorSegment
 
typedef SubState_< 3, 3 > VelocityStateType
 
typedef VectorBlock< Vector, 3 > VelocityType
 

Public Member Functions

virtual const boost::shared_ptr< AccelerationStateType > & acceleration () const
 
template<int SubVectorDimension, int SubCovarianceDimension>
boost::shared_ptr< SubState_< SubVectorDimension, SubCovarianceDimension > > addSubState (const std::string &name=std::string())
 
template<int SubVectorDimension, int SubCovarianceDimension>
boost::shared_ptr< SubState_< SubVectorDimension, SubCovarianceDimension > > addSubState (const Model *model, const std::string &name=std::string())
 
template<int _VectorDimension, int _CovarianceDimension>
boost::shared_ptr< SubState_< _VectorDimension, _CovarianceDimension > > addSubState (const std::string &name)
 
template<int _VectorDimension, int _CovarianceDimension>
boost::shared_ptr< SubState_< _VectorDimension, _CovarianceDimension > > addSubState (const Model *model, const std::string &name)
 
virtual void addSystemStatusCallback (const SystemStatusCallback &callback)
 
virtual BaseStatebase ()
 
virtual const BaseStatebase () const
 
virtual ConstAccelerationType getAcceleration () const
 
virtual const CovariancegetCovariance () const
 
virtual IndexType getCovarianceDimension () const
 
void getEuler (double &roll, double &pitch, double &yaw) const
 
ColumnVector3 getEuler () const
 
virtual SystemStatus getMeasurementStatus () const
 
virtual ConstOrientationType getOrientation () const
 
virtual ConstPositionType getPosition () const
 
virtual ConstRateType getRate () const
 
void getRotationMatrix (RotationMatrix &R) const
 
template<int Size>
VectorBlock< const Vector, Size > getSegment (IndexType start) const
 
template<int SubVectorDimension, int SubCovarianceDimension>
boost::shared_ptr< SubState_< SubVectorDimension, SubCovarianceDimension > > getSubState (const Model *model) const
 
template<int SubVectorDimension, int SubCovarianceDimension>
boost::shared_ptr< SubState_< SubVectorDimension, SubCovarianceDimension > > getSubState (const std::string &name) const
 
template<int _VectorDimension, int _CovarianceDimension>
boost::shared_ptr< SubState_< _VectorDimension, _CovarianceDimension > > getSubState (const Model *model) const
 
template<int _VectorDimension, int _CovarianceDimension>
boost::shared_ptr< SubState_< _VectorDimension, _CovarianceDimension > > getSubState (const std::string &name) const
 
const SubStatesgetSubStates () const
 
virtual SystemStatus getSystemStatus () const
 
const ros::TimegetTimestamp () const
 
virtual const VectorgetVector () const
 
virtual IndexType getVectorDimension () const
 
virtual ConstVelocityType getVelocity () const
 
double getYaw () const
 
virtual bool inSystemStatus (SystemStatus test_status) const
 
virtual void normalize ()
 
virtual const boost::shared_ptr< OrientationStateType > & orientation () const
 
virtual CovarianceP ()
 
virtual const boost::shared_ptr< PositionStateType > & position () const
 
const State::RotationMatrixR () const
 
virtual const boost::shared_ptr< RateStateType > & rate () const
 
virtual void reset ()
 
template<typename Derived >
void setAcceleration (const Eigen::MatrixBase< Derived > &acceleration)
 
virtual bool setMeasurementStatus (SystemStatus new_status)
 
void setOrientation (const Quaternion &orientation)
 
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)
 
void setRollPitch (const Quaternion &orientation)
 
void setRollPitch (ScalarType roll, ScalarType pitch)
 
virtual bool setSystemStatus (SystemStatus new_status)
 
void setTimestamp (const ros::Time &timestamp)
 
template<typename Derived >
void setVelocity (const Eigen::MatrixBase< Derived > &velocity)
 
void setYaw (const Quaternion &orientation)
 
void setYaw (ScalarType yaw)
 
virtual void update (const Vector &vector_update)
 
virtual void updated ()
 
virtual bool updateMeasurementStatus (SystemStatus set, SystemStatus clear)
 
virtual void updateOrientation (const ColumnVector3 &rotation_vector)
 
virtual bool updateSystemStatus (SystemStatus set, SystemStatus clear)
 
virtual bool valid () const
 
virtual const boost::shared_ptr< VelocityStateType > & velocity () const
 
virtual Vectorx ()
 
virtual ~State ()
 

Protected Member Functions

AccelerationType accelerationPart ()
 
void accelerationSet ()
 
void construct ()
 
OrientationType orientationPart ()
 
void orientationSet ()
 
PositionType positionPart ()
 
void positionSet ()
 
RateType ratePart ()
 
void rateSet ()
 
void rollpitchSet ()
 
 State ()
 
VelocityType velocityPart ()
 
void velocitySet ()
 
void yawSet ()
 

Protected Attributes

boost::shared_ptr< AccelerationStateTypeacceleration_
 
boost::shared_ptr< BaseStatebase_
 
Covariance covariance_
 
Vector fake_acceleration_
 
Vector fake_orientation_
 
Vector fake_position_
 
Vector fake_rate_
 
Vector fake_velocity_
 
SystemStatus measurement_status_
 
boost::shared_ptr< OrientationStateTypeorientation_
 
boost::shared_ptr< PositionStateTypeposition_
 
RotationMatrix R_
 
bool R_valid_
 
boost::shared_ptr< RateStateTyperate_
 
std::vector< SystemStatusCallbackstatus_callbacks_
 
SubStates substates_
 
std::map< const Model *, SubStateWPtrsubstates_by_model_
 
std::map< std::string, SubStateWPtrsubstates_by_name_
 
SystemStatus system_status_
 
ros::Time timestamp_
 
Vector vector_
 
boost::shared_ptr< VelocityStateTypevelocity_
 

Detailed Description

Definition at line 42 of file state.h.

Member Typedef Documentation

Definition at line 65 of file state.h.

Definition at line 66 of file state.h.

Definition at line 67 of file state.h.

typedef Block<const Covariance::Base> hector_pose_estimation::State::ConstCovarianceBlock

Definition at line 51 of file state.h.

Definition at line 55 of file state.h.

Definition at line 61 of file state.h.

Definition at line 58 of file state.h.

Definition at line 50 of file state.h.

Definition at line 64 of file state.h.

Definition at line 45 of file state.h.

typedef Block<Covariance::Base> hector_pose_estimation::State::CovarianceBlock

Definition at line 49 of file state.h.

Definition at line 53 of file state.h.

Definition at line 54 of file state.h.

Definition at line 59 of file state.h.

Definition at line 60 of file state.h.

Definition at line 56 of file state.h.

Definition at line 57 of file state.h.

Definition at line 71 of file state.h.

Definition at line 69 of file state.h.

Definition at line 46 of file state.h.

Definition at line 109 of file state.h.

Definition at line 44 of file state.h.

Definition at line 48 of file state.h.

Definition at line 62 of file state.h.

Definition at line 63 of file state.h.

Constructor & Destructor Documentation

hector_pose_estimation::State::~State ( )
virtual

Definition at line 76 of file state.cpp.

hector_pose_estimation::State::State ( )
protected

Definition at line 74 of file state.cpp.

Member Function Documentation

virtual const boost::shared_ptr<AccelerationStateType>& hector_pose_estimation::State::acceleration ( ) const
inlinevirtual

Definition at line 116 of file state.h.

AccelerationType hector_pose_estimation::State::accelerationPart ( )
protected
void hector_pose_estimation::State::accelerationSet ( )
protected
template<int SubVectorDimension, int SubCovarianceDimension>
boost::shared_ptr<SubState_<SubVectorDimension,SubCovarianceDimension> > hector_pose_estimation::State::addSubState ( const std::string &  name = std::string())
template<int SubVectorDimension, int SubCovarianceDimension>
boost::shared_ptr<SubState_<SubVectorDimension,SubCovarianceDimension> > hector_pose_estimation::State::addSubState ( const Model model,
const std::string &  name = std::string() 
)
template<int _VectorDimension, int _CovarianceDimension>
boost::shared_ptr<SubState_<_VectorDimension, _CovarianceDimension> > hector_pose_estimation::State::addSubState ( const std::string &  name)

Definition at line 167 of file substate.h.

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

Definition at line 172 of file substate.h.

void hector_pose_estimation::State::addSystemStatusCallback ( const SystemStatusCallback callback)
virtual

Definition at line 249 of file state.cpp.

virtual BaseState& hector_pose_estimation::State::base ( )
inlinevirtual

Definition at line 85 of file state.h.

virtual const BaseState& hector_pose_estimation::State::base ( ) const
inlinevirtual

Definition at line 86 of file state.h.

void hector_pose_estimation::State::construct ( )
protected

Definition at line 78 of file state.cpp.

State::ConstAccelerationType hector_pose_estimation::State::getAcceleration ( ) const
virtual

Definition at line 120 of file state.cpp.

virtual const Covariance& hector_pose_estimation::State::getCovariance ( ) const
inlinevirtual

Definition at line 89 of file state.h.

virtual IndexType hector_pose_estimation::State::getCovarianceDimension ( ) const
inlinevirtual

Definition at line 77 of file state.h.

void hector_pose_estimation::State::getEuler ( double &  roll,
double &  pitch,
double &  yaw 
) const

Definition at line 145 of file state.cpp.

ColumnVector3 hector_pose_estimation::State::getEuler ( ) const

Definition at line 153 of file state.cpp.

virtual SystemStatus hector_pose_estimation::State::getMeasurementStatus ( ) const
inlinevirtual

Definition at line 101 of file state.h.

State::ConstOrientationType hector_pose_estimation::State::getOrientation ( ) const
virtual

Definition at line 116 of file state.cpp.

State::ConstPositionType hector_pose_estimation::State::getPosition ( ) const
virtual

Definition at line 118 of file state.cpp.

State::ConstRateType hector_pose_estimation::State::getRate ( ) const
virtual

Definition at line 117 of file state.cpp.

void hector_pose_estimation::State::getRotationMatrix ( RotationMatrix R) const

Definition at line 122 of file state.cpp.

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

Definition at line 90 of file state.h.

template<int SubVectorDimension, int SubCovarianceDimension>
boost::shared_ptr<SubState_<SubVectorDimension,SubCovarianceDimension> > hector_pose_estimation::State::getSubState ( const Model model) const
template<int SubVectorDimension, int SubCovarianceDimension>
boost::shared_ptr<SubState_<SubVectorDimension,SubCovarianceDimension> > hector_pose_estimation::State::getSubState ( const std::string &  name) const
template<int _VectorDimension, int _CovarianceDimension>
boost::shared_ptr<SubState_<_VectorDimension, _CovarianceDimension> > hector_pose_estimation::State::getSubState ( const Model model) const

Definition at line 152 of file substate.h.

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

Definition at line 162 of file substate.h.

const SubStates& hector_pose_estimation::State::getSubStates ( ) const
inline

Definition at line 141 of file state.h.

virtual SystemStatus hector_pose_estimation::State::getSystemStatus ( ) const
inlinevirtual

Definition at line 100 of file state.h.

const ros::Time& hector_pose_estimation::State::getTimestamp ( ) const
inline

Definition at line 147 of file state.h.

virtual const Vector& hector_pose_estimation::State::getVector ( ) const
inlinevirtual

Definition at line 88 of file state.h.

virtual IndexType hector_pose_estimation::State::getVectorDimension ( ) const
inlinevirtual

Definition at line 76 of file state.h.

State::ConstVelocityType hector_pose_estimation::State::getVelocity ( ) const
virtual

Definition at line 119 of file state.cpp.

double hector_pose_estimation::State::getYaw ( ) const

Definition at line 139 of file state.cpp.

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

Definition at line 211 of file state.cpp.

void hector_pose_estimation::State::normalize ( )
virtual

Definition at line 255 of file state.cpp.

virtual const boost::shared_ptr<OrientationStateType>& hector_pose_estimation::State::orientation ( ) const
inlinevirtual

Definition at line 112 of file state.h.

OrientationType hector_pose_estimation::State::orientationPart ( )
protected
void hector_pose_estimation::State::orientationSet ( )
protected
virtual Covariance& hector_pose_estimation::State::P ( )
inlinevirtual

Definition at line 93 of file state.h.

virtual const boost::shared_ptr<PositionStateType>& hector_pose_estimation::State::position ( ) const
inlinevirtual

Definition at line 114 of file state.h.

PositionType hector_pose_estimation::State::positionPart ( )
protected
void hector_pose_estimation::State::positionSet ( )
protected
const State::RotationMatrix & hector_pose_estimation::State::R ( ) const

Definition at line 131 of file state.cpp.

virtual const boost::shared_ptr<RateStateType>& hector_pose_estimation::State::rate ( ) const
inlinevirtual

Definition at line 113 of file state.h.

RateType hector_pose_estimation::State::ratePart ( )
protected
void hector_pose_estimation::State::rateSet ( )
protected
void hector_pose_estimation::State::reset ( )
virtual

Definition at line 84 of file state.cpp.

void hector_pose_estimation::State::rollpitchSet ( )
protected
template<typename Derived >
void hector_pose_estimation::State::setAcceleration ( const Eigen::MatrixBase< Derived > &  acceleration)
bool hector_pose_estimation::State::setMeasurementStatus ( SystemStatus  new_status)
virtual

Definition at line 231 of file state.cpp.

void hector_pose_estimation::State::setOrientation ( const Quaternion orientation)

Definition at line 262 of file state.cpp.

template<typename Derived >
void hector_pose_estimation::State::setOrientation ( const Eigen::MatrixBase< Derived > &  orientation)
template<typename Derived >
void hector_pose_estimation::State::setPosition ( const Eigen::MatrixBase< Derived > &  position)
template<typename Derived >
void hector_pose_estimation::State::setRate ( const Eigen::MatrixBase< Derived > &  rate)
void hector_pose_estimation::State::setRollPitch ( const Quaternion orientation)

Definition at line 267 of file state.cpp.

void hector_pose_estimation::State::setRollPitch ( ScalarType  roll,
ScalarType  pitch 
)

Definition at line 275 of file state.cpp.

bool hector_pose_estimation::State::setSystemStatus ( SystemStatus  new_status)
virtual

Definition at line 215 of file state.cpp.

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

Definition at line 148 of file state.h.

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

Definition at line 281 of file state.cpp.

void hector_pose_estimation::State::setYaw ( ScalarType  yaw)

Definition at line 288 of file state.cpp.

void hector_pose_estimation::State::update ( const Vector vector_update)
virtual

Definition at line 160 of file state.cpp.

void hector_pose_estimation::State::updated ( )
virtual

Definition at line 110 of file state.cpp.

bool hector_pose_estimation::State::updateMeasurementStatus ( SystemStatus  set,
SystemStatus  clear 
)
virtual

Definition at line 245 of file state.cpp.

void hector_pose_estimation::State::updateOrientation ( const ColumnVector3 rotation_vector)
virtual

Definition at line 195 of file state.cpp.

bool hector_pose_estimation::State::updateSystemStatus ( SystemStatus  set,
SystemStatus  clear 
)
virtual

Definition at line 241 of file state.cpp.

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

Definition at line 106 of file state.cpp.

virtual const boost::shared_ptr<VelocityStateType>& hector_pose_estimation::State::velocity ( ) const
inlinevirtual

Definition at line 115 of file state.h.

VelocityType hector_pose_estimation::State::velocityPart ( )
protected
void hector_pose_estimation::State::velocitySet ( )
protected
virtual Vector& hector_pose_estimation::State::x ( )
inlinevirtual

Definition at line 92 of file state.h.

void hector_pose_estimation::State::yawSet ( )
protected

Member Data Documentation

boost::shared_ptr<AccelerationStateType> hector_pose_estimation::State::acceleration_
protected

Definition at line 186 of file state.h.

boost::shared_ptr<BaseState> hector_pose_estimation::State::base_
protected

Definition at line 181 of file state.h.

Covariance hector_pose_estimation::State::covariance_
protected

Definition at line 170 of file state.h.

Vector hector_pose_estimation::State::fake_acceleration_
protected

Definition at line 192 of file state.h.

Vector hector_pose_estimation::State::fake_orientation_
protected

Definition at line 188 of file state.h.

Vector hector_pose_estimation::State::fake_position_
protected

Definition at line 190 of file state.h.

Vector hector_pose_estimation::State::fake_rate_
protected

Definition at line 189 of file state.h.

Vector hector_pose_estimation::State::fake_velocity_
protected

Definition at line 191 of file state.h.

SystemStatus hector_pose_estimation::State::measurement_status_
protected

Definition at line 173 of file state.h.

boost::shared_ptr<OrientationStateType> hector_pose_estimation::State::orientation_
protected

Definition at line 182 of file state.h.

boost::shared_ptr<PositionStateType> hector_pose_estimation::State::position_
protected

Definition at line 184 of file state.h.

RotationMatrix hector_pose_estimation::State::R_
mutableprotected

Definition at line 197 of file state.h.

bool hector_pose_estimation::State::R_valid_
mutableprotected

Definition at line 198 of file state.h.

boost::shared_ptr<RateStateType> hector_pose_estimation::State::rate_
protected

Definition at line 183 of file state.h.

std::vector<SystemStatusCallback> hector_pose_estimation::State::status_callbacks_
protected

Definition at line 175 of file state.h.

SubStates hector_pose_estimation::State::substates_
protected

Definition at line 177 of file state.h.

std::map<const Model *, SubStateWPtr> hector_pose_estimation::State::substates_by_model_
protected

Definition at line 178 of file state.h.

std::map<std::string, SubStateWPtr> hector_pose_estimation::State::substates_by_name_
protected

Definition at line 179 of file state.h.

SystemStatus hector_pose_estimation::State::system_status_
protected

Definition at line 172 of file state.h.

ros::Time hector_pose_estimation::State::timestamp_
protected

Definition at line 194 of file state.h.

Vector hector_pose_estimation::State::vector_
protected

Definition at line 169 of file state.h.

boost::shared_ptr<VelocityStateType> hector_pose_estimation::State::velocity_
protected

Definition at line 185 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 Thu Feb 18 2021 03:29:31