|
| PositionVelocityState () |
|
virtual | ~PositionVelocityState () |
|
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 BaseState & | base () |
|
virtual const BaseState & | base () const |
|
virtual ConstAccelerationType | getAcceleration () const |
|
virtual const Covariance & | getCovariance () 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 SubStates & | getSubStates () const |
|
virtual SystemStatus | getSystemStatus () const |
|
const ros::Time & | getTimestamp () const |
|
virtual const Vector & | getVector () 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 Covariance & | P () |
|
virtual const boost::shared_ptr< PositionStateType > & | position () const |
|
const State::RotationMatrix & | R () 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 ×tamp) |
|
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 Vector & | x () |
|
virtual | ~State () |
|
|
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 Vector > | ConstVectorSegment |
|
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< SubStatePtr > | SubStates |
|
typedef Matrix | SystemMatrix |
|
typedef boost::function< bool(SystemStatus &)> | SystemStatusCallback |
|
typedef ColumnVector | Vector |
|
typedef VectorBlock< Vector > | VectorSegment |
|
typedef SubState_< 3, 3 > | VelocityStateType |
|
typedef VectorBlock< Vector, 3 > | VelocityType |
|
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 () |
|
boost::shared_ptr< AccelerationStateType > | acceleration_ |
|
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_ |
|
boost::shared_ptr< OrientationStateType > | orientation_ |
|
boost::shared_ptr< PositionStateType > | position_ |
|
RotationMatrix | R_ |
|
bool | R_valid_ |
|
boost::shared_ptr< RateStateType > | rate_ |
|
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_ |
|
boost::shared_ptr< VelocityStateType > | velocity_ |
|
Definition at line 222 of file state.h.