Public Types | Public Member Functions | Public Attributes | Static Public Attributes | Friends | List of all members
Target Class Reference

#include <target.h>

Inheritance diagram for Target:
Inheritance graph
[legend]

Public Types

typedef boost::shared_ptr< TargetPtr
 

Public Member Functions

void associate (Target::Ptr target)
 
void calculateProperties ()
 
double checkAssociationCriteria (Target::Ptr target)
 
void cleanTargetAssociations (void)
 
void decrementMissedAssociations (int dec=1)
 
double getDistance (MeasurementPtr &mes, int algorithm=0)
 
double getDistanceToPredictedPosition (TargetPtr &target, int algorithm=0)
 
void incrementMissedAssociations (int inc=1)
 
void stepModel ()
 
 Target ()
 
 Target (TargetPtr prev_target)
 
 Target (TargetPtr prev_target, MeasurementPtr measurement)
 
 Target (MeasurementPtr measurement)
 
void zeroMissedAssociations (void)
 
 ~Target ()
 
- Public Member Functions inherited from MotionModel
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

vector< MeasurementPtr_assigned_measurements
 
double _aux1
 
long _cluster
 
vector< long > _concurrent_targets
 
long _exuid
 
long _hypothesis
 
long _id
 
long _missed_associations
 
vector< Vector5d_past_states
 
long _uid
 
string _variant
 
Point centroid
 
Point estimated_position
 
Point estimated_velocity
 
bool found
 
long id
 
double length
 
long life_time
 
long local_id
 
Point measurement
 
MotionModel motion_model
 
bool occluded
 
long occluded_time
 
vector< Point::Ptrpoints
 
Point predicted_position
 
double rmin
 
SearchArea search_area
 
double stt
 
double tm
 
bool to_remove
 
- Public Attributes inherited from MotionModel
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
 

Static Public Attributes

static long _euid =0
 
static long _ntotal =0
 

Friends

ostream & operator<< (ostream &o, Target &t)
 

Detailed Description

Definition at line 52 of file target.h.

Member Typedef Documentation

typedef boost::shared_ptr<Target> Target::Ptr

Definition at line 431 of file gnn.cpp.

Constructor & Destructor Documentation

Target::Target ( )

Definition at line 105 of file target.cpp.

Target::~Target ( )

Definition at line 114 of file target.cpp.

Target::Target ( TargetPtr  prev_target)

Definition at line 121 of file target.cpp.

Target::Target ( TargetPtr  prev_target,
MeasurementPtr  measurement 
)

Definition at line 183 of file target.cpp.

Target::Target ( MeasurementPtr  measurement)

Definition at line 218 of file target.cpp.

Member Function Documentation

void Target::associate ( Target::Ptr  target)
inline

Definition at line 453 of file gnn.cpp.

void Target::calculateProperties ( )
inline

Definition at line 433 of file gnn.cpp.

double Target::checkAssociationCriteria ( Target::Ptr  target)
inline

Definition at line 467 of file gnn.cpp.

void Target::cleanTargetAssociations ( void  )

Definition at line 299 of file target.cpp.

void Target::decrementMissedAssociations ( int  dec = 1)

Definition at line 52 of file target.cpp.

double Target::getDistance ( MeasurementPtr mes,
int  algorithm = 0 
)

Definition at line 63 of file target.cpp.

double Target::getDistanceToPredictedPosition ( TargetPtr target,
int  algorithm = 0 
)

Definition at line 266 of file target.cpp.

void Target::incrementMissedAssociations ( int  inc = 1)

Definition at line 45 of file target.cpp.

void Target::stepModel ( )
inline

Definition at line 495 of file gnn.cpp.

void Target::zeroMissedAssociations ( void  )

Definition at line 58 of file target.cpp.

Friends And Related Function Documentation

ostream& operator<< ( ostream &  o,
Target t 
)
friend

Definition at line 34 of file target.cpp.

Member Data Documentation

vector<MeasurementPtr> Target::_assigned_measurements

Definition at line 72 of file target.h.

double Target::_aux1

Definition at line 70 of file target.h.

long Target::_cluster

Definition at line 59 of file target.h.

vector<long> Target::_concurrent_targets

Definition at line 73 of file target.h.

long Target::_euid =0
static

Definition at line 67 of file target.h.

long Target::_exuid

Definition at line 64 of file target.h.

long Target::_hypothesis

Definition at line 58 of file target.h.

long Target::_id

Definition at line 60 of file target.h.

long Target::_missed_associations

Definition at line 61 of file target.h.

long Target::_ntotal =0
static

Definition at line 68 of file target.h.

vector<Vector5d> Target::_past_states

Definition at line 74 of file target.h.

long Target::_uid

Definition at line 63 of file target.h.

string Target::_variant

Definition at line 62 of file target.h.

Point Target::centroid

Definition at line 515 of file gnn.cpp.

Point Target::estimated_position

Definition at line 516 of file gnn.cpp.

Point Target::estimated_velocity

Definition at line 519 of file gnn.cpp.

bool Target::found

Definition at line 530 of file gnn.cpp.

long Target::id

Definition at line 525 of file gnn.cpp.

double Target::length

Definition at line 532 of file gnn.cpp.

long Target::life_time

Definition at line 528 of file gnn.cpp.

long Target::local_id

Definition at line 526 of file gnn.cpp.

Point Target::measurement

Definition at line 518 of file gnn.cpp.

MotionModel Target::motion_model

Definition at line 521 of file gnn.cpp.

bool Target::occluded

Definition at line 523 of file gnn.cpp.

long Target::occluded_time

Definition at line 529 of file gnn.cpp.

vector<Point::Ptr> Target::points

Definition at line 536 of file gnn.cpp.

Point Target::predicted_position

Definition at line 517 of file gnn.cpp.

double Target::rmin

Definition at line 524 of file gnn.cpp.

SearchArea Target::search_area

Definition at line 534 of file gnn.cpp.

double Target::stt

Definition at line 56 of file target.h.

double Target::tm

Definition at line 524 of file gnn.cpp.

bool Target::to_remove

Definition at line 531 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:19