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

#include <detector_particle.h>

Public Member Functions

 DetectorParticle (unsigned int num_particles)
 constructor More...
 
void getEstimate (tf::Vector3 &est) const
 get filter posterior More...
 
void getEstimate (people_msgs::PositionMeasurement &est) const
 
MatrixWrapper::Matrix getHistogram (const tf::Vector3 &min, const tf::Vector3 &max, const tf::Vector3 &step) const
 Get histogram from certain area. More...
 
void getParticleCloud (const tf::Vector3 &step, double threshold, sensor_msgs::PointCloud &cloud) const
 
double getQuality () const
 return measure for detector quality: 0=bad 1=good More...
 
void initialize (const tf::Vector3 &mu, const tf::Vector3 &size, const double time)
 initialize detector More...
 
bool isInitialized () const
 return if detector was initialized More...
 
bool updateCorrection (const tf::Vector3 &meas, const MatrixWrapper::SymmetricMatrix &cov, const double time)
 
bool updatePrediction (const double dt)
 update detector More...
 
 ~DetectorParticle ()
 destructor More...
 

Private Attributes

bool detector_initialized_
 
BFL::BootstrapFilter< tf::Vector3, tf::Vector3 > * filter_
 
double filter_time_
 
BFL::MeasModelVector meas_model_
 
unsigned int num_particles_
 
BFL::MCPdfVector prior_
 
double quality_
 
BFL::SysModelVector sys_model_
 

Detailed Description

Definition at line 60 of file detector_particle.h.

Constructor & Destructor Documentation

estimation::DetectorParticle::DetectorParticle ( unsigned int  num_particles)
explicit

constructor

Definition at line 46 of file detector_particle.cpp.

estimation::DetectorParticle::~DetectorParticle ( )

destructor

Definition at line 56 of file detector_particle.cpp.

Member Function Documentation

void estimation::DetectorParticle::getEstimate ( tf::Vector3 est) const

get filter posterior

Definition at line 118 of file detector_particle.cpp.

void estimation::DetectorParticle::getEstimate ( people_msgs::PositionMeasurement &  est) const

Definition at line 123 of file detector_particle.cpp.

Matrix estimation::DetectorParticle::getHistogram ( const tf::Vector3 min,
const tf::Vector3 max,
const tf::Vector3 step 
) const

Get histogram from certain area.

Definition at line 136 of file detector_particle.cpp.

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

Definition at line 112 of file detector_particle.cpp.

double estimation::DetectorParticle::getQuality ( ) const
inline

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

Definition at line 79 of file detector_particle.h.

void estimation::DetectorParticle::initialize ( const tf::Vector3 mu,
const tf::Vector3 size,
const double  time 
)

initialize detector

Definition at line 62 of file detector_particle.cpp.

bool estimation::DetectorParticle::isInitialized ( ) const
inline

return if detector was initialized

Definition at line 73 of file detector_particle.h.

bool estimation::DetectorParticle::updateCorrection ( const tf::Vector3 meas,
const MatrixWrapper::SymmetricMatrix &  cov,
const double  time 
)

Definition at line 93 of file detector_particle.cpp.

bool estimation::DetectorParticle::updatePrediction ( const double  dt)

update detector

Definition at line 80 of file detector_particle.cpp.

Member Data Documentation

bool estimation::DetectorParticle::detector_initialized_
private

Definition at line 108 of file detector_particle.h.

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

Definition at line 103 of file detector_particle.h.

double estimation::DetectorParticle::filter_time_
private

Definition at line 109 of file detector_particle.h.

BFL::MeasModelVector estimation::DetectorParticle::meas_model_
private

Definition at line 105 of file detector_particle.h.

unsigned int estimation::DetectorParticle::num_particles_
private

Definition at line 110 of file detector_particle.h.

BFL::MCPdfVector estimation::DetectorParticle::prior_
private

Definition at line 102 of file detector_particle.h.

double estimation::DetectorParticle::quality_
private

Definition at line 109 of file detector_particle.h.

BFL::SysModelVector estimation::DetectorParticle::sys_model_
private

Definition at line 104 of file detector_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