Public Member Functions | Public Attributes | List of all members
MotionModel Class Reference

Nonholonomic Motion model abstraction layer. More...

#include <motionModel.h>

Inheritance diagram for MotionModel:
Inheritance graph
[legend]

Public Member Functions

void initEstimator (Vector5d &x, Matrix5d &P)
 
void initEstimator (Vector3d &z)
 
void initFilter (Point measurement)
 
void makeA ()
 Make the process Jacobian matrix. More...
 
void makeBaseV ()
 Make measurement noise sensitivity matrix. More...
 
void makeBaseW ()
 
void makeH ()
 
void makeMeasure ()
 Make measurement, used when measurement is not possible (i'm not using it now) More...
 
void makeProcess ()
 
void makeQ ()
 Make process noise covariance matrix. More...
 
void makeR ()
 
 MotionModel ()
 
 MotionModel ()
 
void setIdentity (kMatrix &M, int size, double value=1)
 
void stepEstimator (Vector3d z)
 
void stepEstimator (Vector2d measurement)
 

Public Attributes

nonholonomicEKFilter _estimator
 Local estimator for process, Kalman filter with a constant velocity. More...
 
Matrix5d _P
 Posteriori error covariance. More...
 
Vector5d _x
 Estimated state. More...
 
Vector5d _xp
 Predicted x. More...
 
Vector3d _z
 Measurement vector. More...
 
double dt
 
Vector2d inovation_error
 
Matrix4d PosteriorCovariance
 
Vector4d x_estimated
 
Vector4d x_predicted
 

Detailed Description

Nonholonomic Motion model abstraction layer.

This class encapsulates the underlaying motion model used. It provides an abstraction layer for the Mht class to work with, without having to deal with the Kalman filter directly.

Definition at line 46 of file motionModel.h.

Constructor & Destructor Documentation

MotionModel::MotionModel ( )

Definition at line 34 of file motionModel.cpp.

MotionModel::MotionModel ( )
inline

Definition at line 213 of file gnn.cpp.

Member Function Documentation

void MotionModel::initEstimator ( Vector5d x,
Matrix5d P 
)

Definition at line 42 of file motionModel.cpp.

void MotionModel::initEstimator ( Vector3d z)

Definition at line 48 of file motionModel.cpp.

void MotionModel::initFilter ( Point  measurement)
inline

Definition at line 227 of file gnn.cpp.

void MotionModel::makeA ( )
inline

Make the process Jacobian matrix.

Definition at line 307 of file gnn.cpp.

void MotionModel::makeBaseV ( )
inline

Make measurement noise sensitivity matrix.

Definition at line 348 of file gnn.cpp.

void MotionModel::makeBaseW ( )
inline

Definition at line 340 of file gnn.cpp.

void MotionModel::makeH ( )
inline

Definition at line 331 of file gnn.cpp.

void MotionModel::makeMeasure ( )
inline

Make measurement, used when measurement is not possible (i'm not using it now)

Definition at line 420 of file gnn.cpp.

void MotionModel::makeProcess ( )
inline

Definition at line 395 of file gnn.cpp.

void MotionModel::makeQ ( )
inline

Make process noise covariance matrix.

Definition at line 365 of file gnn.cpp.

void MotionModel::makeR ( )
inline

Definition at line 353 of file gnn.cpp.

void MotionModel::setIdentity ( kMatrix M,
int  size,
double  value = 1 
)
inline

Definition at line 217 of file gnn.cpp.

void MotionModel::stepEstimator ( Vector3d  z)

Definition at line 99 of file motionModel.cpp.

void MotionModel::stepEstimator ( Vector2d  measurement)
inline

Definition at line 247 of file gnn.cpp.

Member Data Documentation

nonholonomicEKFilter MotionModel::_estimator

Local estimator for process, Kalman filter with a constant velocity.

Definition at line 59 of file motionModel.h.

Matrix5d MotionModel::_P

Posteriori error covariance.

Definition at line 56 of file motionModel.h.

Vector5d MotionModel::_x

Estimated state.

Definition at line 50 of file motionModel.h.

Vector5d MotionModel::_xp

Predicted x.

Definition at line 52 of file motionModel.h.

Vector3d MotionModel::_z

Measurement vector.

Definition at line 54 of file motionModel.h.

double MotionModel::dt

Definition at line 208 of file gnn.cpp.

Vector2d MotionModel::inovation_error

Definition at line 209 of file gnn.cpp.

Matrix4d MotionModel::PosteriorCovariance

Definition at line 212 of file gnn.cpp.

Vector4d MotionModel::x_estimated

Definition at line 211 of file gnn.cpp.

Vector4d MotionModel::x_predicted

Definition at line 210 of file gnn.cpp.


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


mtt
Author(s): Jorge Almeida
autogenerated on Mon Mar 2 2015 01:32:18