#include <state.h>
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< SubStatePtr > | SubStates |
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 BaseState & | base () |
virtual const BaseState & | base () const |
virtual ConstAccelerationType | getAcceleration () const |
virtual IndexType | getAccelerationIndex () const |
virtual const Covariance & | getCovariance () 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 SubStates & | getSubStates () const |
virtual SystemStatus | getSystemStatus () const |
const ros::Time & | getTimestamp () const |
virtual const Vector & | getVector () 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 Covariance & | P () |
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 ×tamp) |
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 Vector & | x () |
virtual VectorSegment | x0 () |
virtual | ~State () |
Static Public Member Functions | |
static IndexType | getDimension0 () |
Private Attributes | |
boost::shared_ptr< BaseState > | base_ |
Covariance | covariance_ |
Vector | fake_acceleration_ |
Vector | fake_orientation_ |
Vector | fake_position_ |
Vector | fake_rate_ |
Vector | fake_velocity_ |
SystemStatus | measurement_status_ |
std::vector< SystemStatusCallback > | status_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_ |
typedef VectorBlock<Vector,3> hector_pose_estimation::State::AccelerationType |
typedef VectorBlock<const Vector,3> hector_pose_estimation::State::ConstAccelerationType |
typedef Block<const Covariance::Base,Dimension,Dimension> hector_pose_estimation::State::ConstCovarianceBlock |
typedef VectorBlock<const Vector,4> hector_pose_estimation::State::ConstOrientationType |
typedef VectorBlock<const Vector,3> hector_pose_estimation::State::ConstPositionType |
typedef VectorBlock<const Vector,3> hector_pose_estimation::State::ConstRateType |
typedef VectorBlock<const Vector,Dimension> hector_pose_estimation::State::ConstVectorSegment |
typedef VectorBlock<const Vector,3> hector_pose_estimation::State::ConstVelocityType |
typedef VectorBlock<Vector,4> hector_pose_estimation::State::OrientationType |
typedef VectorBlock<Vector,3> hector_pose_estimation::State::PositionType |
typedef VectorBlock<Vector,3> hector_pose_estimation::State::RateType |
typedef Matrix_<3,3> hector_pose_estimation::State::RotationMatrix |
typedef std::vector<SubStatePtr> hector_pose_estimation::State::SubStates |
typedef boost::function<bool(SystemStatus&)> hector_pose_estimation::State::SystemStatusCallback |
typedef VectorBlock<Vector,Dimension> hector_pose_estimation::State::VectorSegment |
typedef VectorBlock<Vector,3> hector_pose_estimation::State::VelocityType |
hector_pose_estimation::State::State | ( | const Vector & | vector, |
const Covariance & | covariance | ||
) |
hector_pose_estimation::State::~State | ( | ) | [virtual] |
virtual AccelerationType hector_pose_estimation::State::acceleration | ( | ) | [inline, virtual] |
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.
void hector_pose_estimation::State::addSystemStatusCallback | ( | const SystemStatusCallback & | callback | ) | [virtual] |
virtual BaseState& hector_pose_estimation::State::base | ( | ) | [inline, virtual] |
virtual const BaseState& hector_pose_estimation::State::base | ( | ) | const [inline, virtual] |
virtual ConstAccelerationType hector_pose_estimation::State::getAcceleration | ( | ) | const [inline, virtual] |
virtual IndexType hector_pose_estimation::State::getAccelerationIndex | ( | ) | const [inline, virtual] |
virtual const Covariance& hector_pose_estimation::State::getCovariance | ( | ) | const [inline, virtual] |
virtual IndexType hector_pose_estimation::State::getDimension | ( | ) | const [inline, virtual] |
static IndexType hector_pose_estimation::State::getDimension0 | ( | ) | [inline, static] |
virtual SystemStatus hector_pose_estimation::State::getMeasurementStatus | ( | ) | const [inline, virtual] |
virtual ConstOrientationType hector_pose_estimation::State::getOrientation | ( | ) | const [inline, virtual] |
virtual IndexType hector_pose_estimation::State::getOrientationIndex | ( | ) | const [inline, virtual] |
virtual ConstPositionType hector_pose_estimation::State::getPosition | ( | ) | const [inline, virtual] |
virtual IndexType hector_pose_estimation::State::getPositionIndex | ( | ) | const [inline, virtual] |
virtual ConstRateType hector_pose_estimation::State::getRate | ( | ) | const [inline, virtual] |
virtual IndexType hector_pose_estimation::State::getRateIndex | ( | ) | const [inline, virtual] |
void hector_pose_estimation::State::getRotationMatrix | ( | RotationMatrix & | R | ) | const |
VectorBlock<const Vector, Size> hector_pose_estimation::State::getSegment | ( | IndexType | start | ) | const [inline] |
boost::shared_ptr< BaseState > hector_pose_estimation::State::getSubState< 0 > | ( | const Model * | model | ) | const [inline] |
Definition at line 119 of file substate.h.
boost::shared_ptr< SubState_< SubDimension > > hector_pose_estimation::State::getSubState | ( | const std::string & | name | ) | const |
Definition at line 129 of file substate.h.
const SubStates& hector_pose_estimation::State::getSubStates | ( | ) | const [inline] |
virtual SystemStatus hector_pose_estimation::State::getSystemStatus | ( | ) | const [inline, virtual] |
const ros::Time& hector_pose_estimation::State::getTimestamp | ( | ) | const [inline] |
virtual const Vector& hector_pose_estimation::State::getVector | ( | ) | const [inline, virtual] |
virtual ConstVelocityType hector_pose_estimation::State::getVelocity | ( | ) | const [inline, virtual] |
virtual IndexType hector_pose_estimation::State::getVelocityIndex | ( | ) | const [inline, virtual] |
double hector_pose_estimation::State::getYaw | ( | ) | const |
bool hector_pose_estimation::State::inSystemStatus | ( | SystemStatus | test_status | ) | const [virtual] |
double hector_pose_estimation::State::normalize | ( | ) | [virtual] |
virtual OrientationType hector_pose_estimation::State::orientation | ( | ) | [inline, virtual] |
virtual Covariance& hector_pose_estimation::State::P | ( | ) | [inline, virtual] |
virtual CovarianceBlock hector_pose_estimation::State::P0 | ( | ) | [inline, virtual] |
virtual PositionType hector_pose_estimation::State::position | ( | ) | [inline, virtual] |
virtual RateType hector_pose_estimation::State::rate | ( | ) | [inline, virtual] |
void hector_pose_estimation::State::reset | ( | ) | [virtual] |
void hector_pose_estimation::State::setAcceleration | ( | const Eigen::MatrixBase< Derived > & | acceleration | ) |
bool hector_pose_estimation::State::setMeasurementStatus | ( | SystemStatus | new_status | ) | [virtual] |
void hector_pose_estimation::State::setOrientation | ( | const Eigen::MatrixBase< Derived > & | orientation | ) |
void hector_pose_estimation::State::setPosition | ( | const Eigen::MatrixBase< Derived > & | position | ) |
void hector_pose_estimation::State::setRate | ( | const Eigen::MatrixBase< Derived > & | rate | ) |
bool hector_pose_estimation::State::setSystemStatus | ( | SystemStatus | new_status | ) | [virtual] |
void hector_pose_estimation::State::setTimestamp | ( | const ros::Time & | timestamp | ) | [inline] |
void hector_pose_estimation::State::setVelocity | ( | const Eigen::MatrixBase< Derived > & | velocity | ) |
void hector_pose_estimation::State::updated | ( | ) | [virtual] |
bool hector_pose_estimation::State::updateMeasurementStatus | ( | SystemStatus | set, |
SystemStatus | clear | ||
) | [virtual] |
bool hector_pose_estimation::State::updateSystemStatus | ( | SystemStatus | set, |
SystemStatus | clear | ||
) | [virtual] |
bool hector_pose_estimation::State::valid | ( | ) | const [virtual] |
virtual VelocityType hector_pose_estimation::State::velocity | ( | ) | [inline, virtual] |
virtual Vector& hector_pose_estimation::State::x | ( | ) | [inline, virtual] |
virtual VectorSegment hector_pose_estimation::State::x0 | ( | ) | [inline, virtual] |
boost::shared_ptr<BaseState> hector_pose_estimation::State::base_ [private] |
std::vector<SystemStatusCallback> hector_pose_estimation::State::status_callbacks_ [private] |
std::map<const Model *, SubStateWPtr> hector_pose_estimation::State::substates_by_model_ [private] |
std::map<std::string, SubStateWPtr> hector_pose_estimation::State::substates_by_name_ [private] |
Vector hector_pose_estimation::State::vector_ [private] |