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

#include <tracker_particle.h>

Inheritance diagram for estimation::TrackerParticle:
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
 
MatrixWrapper::Matrix getHistogramPos (const tf::Vector3 &min, const tf::Vector3 &max, const tf::Vector3 &step) const
 Get histogram from certain area. More...
 
MatrixWrapper::Matrix getHistogramVel (const tf::Vector3 &min, const tf::Vector3 &max, const tf::Vector3 &step) const
 
virtual double getLifetime () const
 return the lifetime of the tracker More...
 
void getParticleCloud (const tf::Vector3 &step, double threshold, sensor_msgs::PointCloud &cloud) const
 
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...
 
 TrackerParticle (const std::string &name, unsigned int num_particles, 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 ~TrackerParticle ()
 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 Attributes

BFL::BootstrapFilter< BFL::StatePosVel, tf::Vector3 > * filter_
 
double filter_time_
 
double init_time_
 
BFL::MeasModelPos meas_model_
 
unsigned int num_particles_
 
BFL::MCPdfPosVel prior_
 
double quality_
 
BFL::SysModelPosVel sys_model_
 
bool tracker_initialized_
 

Detailed Description

Definition at line 61 of file tracker_particle.h.

Constructor & Destructor Documentation

estimation::TrackerParticle::TrackerParticle ( const std::string &  name,
unsigned int  num_particles,
const BFL::StatePosVel sysnoise 
)

constructor

Definition at line 47 of file tracker_particle.cpp.

estimation::TrackerParticle::~TrackerParticle ( )
virtual

destructor

Definition at line 58 of file tracker_particle.cpp.

Member Function Documentation

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

get filter posterior

Implements estimation::Tracker.

Definition at line 121 of file tracker_particle.cpp.

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

Implements estimation::Tracker.

Definition at line 126 of file tracker_particle.cpp.

Matrix estimation::TrackerParticle::getHistogramPos ( const tf::Vector3 min,
const tf::Vector3 max,
const tf::Vector3 step 
) const

Get histogram from certain area.

Definition at line 139 of file tracker_particle.cpp.

Matrix estimation::TrackerParticle::getHistogramVel ( const tf::Vector3 min,
const tf::Vector3 max,
const tf::Vector3 step 
) const

Definition at line 144 of file tracker_particle.cpp.

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

return the lifetime of the tracker

Implements estimation::Tracker.

Definition at line 149 of file tracker_particle.cpp.

void estimation::TrackerParticle::getParticleCloud ( const tf::Vector3 step,
double  threshold,
sensor_msgs::PointCloud &  cloud 
) const

Definition at line 115 of file tracker_particle.cpp.

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

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

Implements estimation::Tracker.

Definition at line 80 of file tracker_particle.h.

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

return the time of the tracker

Implements estimation::Tracker.

Definition at line 157 of file tracker_particle.cpp.

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

initialize tracker

Implements estimation::Tracker.

Definition at line 64 of file tracker_particle.cpp.

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

return if tracker was initialized

Implements estimation::Tracker.

Definition at line 74 of file tracker_particle.h.

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

Implements estimation::Tracker.

Definition at line 100 of file tracker_particle.cpp.

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

update tracker

Implements estimation::Tracker.

Definition at line 83 of file tracker_particle.cpp.

Member Data Documentation

BFL::BootstrapFilter<BFL::StatePosVel, tf::Vector3>* estimation::TrackerParticle::filter_
private

Definition at line 110 of file tracker_particle.h.

double estimation::TrackerParticle::filter_time_
private

Definition at line 116 of file tracker_particle.h.

double estimation::TrackerParticle::init_time_
private

Definition at line 116 of file tracker_particle.h.

BFL::MeasModelPos estimation::TrackerParticle::meas_model_
private

Definition at line 112 of file tracker_particle.h.

unsigned int estimation::TrackerParticle::num_particles_
private

Definition at line 117 of file tracker_particle.h.

BFL::MCPdfPosVel estimation::TrackerParticle::prior_
private

Definition at line 109 of file tracker_particle.h.

double estimation::TrackerParticle::quality_
private

Definition at line 116 of file tracker_particle.h.

BFL::SysModelPosVel estimation::TrackerParticle::sys_model_
private

Definition at line 111 of file tracker_particle.h.

bool estimation::TrackerParticle::tracker_initialized_
private

Definition at line 115 of file tracker_particle.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