Public Member Functions | Private Member Functions | Private Attributes | List of all members
estimation::TrackerKalman Class Reference

#include <tracker_kalman.h>

Inheritance diagram for estimation::TrackerKalman:
Inheritance graph
[legend]

Public Member Functions

virtual void getEstimate (BFL::StatePosVel &est) const
 get filter posterior More...
 
virtual void getEstimate (people_msgs::PositionMeasurement &est) const
 
virtual double getLifetime () const
 return the lifetime of the tracker More...
 
virtual double getQuality () const
 return measure for tracker quality: 0=bad 1=good More...
 
virtual double getTime () const
 return the time of the tracker More...
 
virtual void initialize (const BFL::StatePosVel &mu, const BFL::StatePosVel &sigma, const double time)
 initialize tracker More...
 
virtual bool isInitialized () const
 return if tracker was initialized More...
 
 TrackerKalman (const std::string &name, const BFL::StatePosVel &sysnoise)
 constructor More...
 
virtual bool updateCorrection (const tf::Vector3 &meas, const MatrixWrapper::SymmetricMatrix &cov)
 
virtual bool updatePrediction (const double time)
 update tracker More...
 
virtual ~TrackerKalman ()
 destructor More...
 
- Public Member Functions inherited from estimation::Tracker
const std::string & getName () const
 return the name of the tracker More...
 
 Tracker (const std::string &name)
 constructor More...
 
virtual ~Tracker ()
 destructor More...
 

Private Member Functions

double calculateQuality ()
 

Private Attributes

BFL::ExtendedKalmanFilterfilter_
 
double filter_time_
 
double init_time_
 
BFL::LinearAnalyticMeasurementModelGaussianUncertaintymeas_model_
 
BFL::LinearAnalyticConditionalGaussianmeas_pdf_
 
BFL::Gaussian prior_
 
double quality_
 
MatrixWrapper::Matrix sys_matrix_
 
BFL::LinearAnalyticSystemModelGaussianUncertaintysys_model_
 
BFL::LinearAnalyticConditionalGaussiansys_pdf_
 
MatrixWrapper::SymmetricMatrix sys_sigma_
 
bool tracker_initialized_
 

Detailed Description

Definition at line 61 of file tracker_kalman.h.

Constructor & Destructor Documentation

estimation::TrackerKalman::TrackerKalman ( const std::string &  name,
const BFL::StatePosVel sysnoise 
)

constructor

Definition at line 51 of file tracker_kalman.cpp.

estimation::TrackerKalman::~TrackerKalman ( )
virtual

destructor

Definition at line 99 of file tracker_kalman.cpp.

Member Function Documentation

double estimation::TrackerKalman::calculateQuality ( )
private

Definition at line 197 of file tracker_kalman.cpp.

void estimation::TrackerKalman::getEstimate ( BFL::StatePosVel est) const
virtual

get filter posterior

Implements estimation::Tracker.

Definition at line 175 of file tracker_kalman.cpp.

void estimation::TrackerKalman::getEstimate ( people_msgs::PositionMeasurement &  est) const
virtual

Implements estimation::Tracker.

Definition at line 185 of file tracker_kalman.cpp.

double estimation::TrackerKalman::getLifetime ( ) const
virtual

return the lifetime of the tracker

Implements estimation::Tracker.

Definition at line 207 of file tracker_kalman.cpp.

virtual double estimation::TrackerKalman::getQuality ( ) const
inlinevirtual

return measure for tracker quality: 0=bad 1=good

Implements estimation::Tracker.

Definition at line 80 of file tracker_kalman.h.

double estimation::TrackerKalman::getTime ( ) const
virtual

return the time of the tracker

Implements estimation::Tracker.

Definition at line 215 of file tracker_kalman.cpp.

void estimation::TrackerKalman::initialize ( const BFL::StatePosVel mu,
const BFL::StatePosVel sigma,
const double  time 
)
virtual

initialize tracker

Implements estimation::Tracker.

Definition at line 109 of file tracker_kalman.cpp.

virtual bool estimation::TrackerKalman::isInitialized ( ) const
inlinevirtual

return if tracker was initialized

Implements estimation::Tracker.

Definition at line 74 of file tracker_kalman.h.

bool estimation::TrackerKalman::updateCorrection ( const tf::Vector3 meas,
const MatrixWrapper::SymmetricMatrix &  cov 
)
virtual

Implements estimation::Tracker.

Definition at line 155 of file tracker_kalman.cpp.

bool estimation::TrackerKalman::updatePrediction ( const double  time)
virtual

update tracker

Implements estimation::Tracker.

Definition at line 132 of file tracker_kalman.cpp.

Member Data Documentation

BFL::ExtendedKalmanFilter* estimation::TrackerKalman::filter_
private

Definition at line 103 of file tracker_kalman.h.

double estimation::TrackerKalman::filter_time_
private

Definition at line 115 of file tracker_kalman.h.

double estimation::TrackerKalman::init_time_
private

Definition at line 115 of file tracker_kalman.h.

BFL::LinearAnalyticMeasurementModelGaussianUncertainty* estimation::TrackerKalman::meas_model_
private

Definition at line 107 of file tracker_kalman.h.

BFL::LinearAnalyticConditionalGaussian* estimation::TrackerKalman::meas_pdf_
private

Definition at line 106 of file tracker_kalman.h.

BFL::Gaussian estimation::TrackerKalman::prior_
private

Definition at line 102 of file tracker_kalman.h.

double estimation::TrackerKalman::quality_
private

Definition at line 115 of file tracker_kalman.h.

MatrixWrapper::Matrix estimation::TrackerKalman::sys_matrix_
private

Definition at line 108 of file tracker_kalman.h.

BFL::LinearAnalyticSystemModelGaussianUncertainty* estimation::TrackerKalman::sys_model_
private

Definition at line 105 of file tracker_kalman.h.

BFL::LinearAnalyticConditionalGaussian* estimation::TrackerKalman::sys_pdf_
private

Definition at line 104 of file tracker_kalman.h.

MatrixWrapper::SymmetricMatrix estimation::TrackerKalman::sys_sigma_
private

Definition at line 109 of file tracker_kalman.h.

bool estimation::TrackerKalman::tracker_initialized_
private

Definition at line 114 of file tracker_kalman.h.


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


people_tracking_filter
Author(s): Caroline Pantofaru
autogenerated on Sun Feb 21 2021 03:56:47