Public Member Functions | Private Attributes
estimation::DetectorParticle Class Reference

#include <detector_particle.h>

List of all members.

Public Member Functions

 DetectorParticle (unsigned int num_particles)
 constructor
void getEstimate (tf::Vector3 &est) const
 get filter posterior
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.
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
void initialize (const tf::Vector3 &mu, const tf::Vector3 &size, const double time)
 initialize detector
bool isInitialized () const
 return if detector was initialized
bool updateCorrection (const tf::Vector3 &meas, const MatrixWrapper::SymmetricMatrix &cov, const double time)
bool updatePrediction (const double dt)
 update detector
 ~DetectorParticle ()
 destructor

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)

constructor

Definition at line 53 of file detector_particle.cpp.

destructor

Definition at line 65 of file detector_particle.cpp.


Member Function Documentation

get filter posterior

Definition at line 134 of file detector_particle.cpp.

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

Definition at line 140 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 157 of file detector_particle.cpp.

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

Definition at line 127 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 72 of file detector_particle.cpp.

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 108 of file detector_particle.cpp.

update detector

Definition at line 93 of file detector_particle.cpp.


Member Data Documentation

Definition at line 108 of file detector_particle.h.

Definition at line 103 of file detector_particle.h.

Definition at line 109 of file detector_particle.h.

Definition at line 105 of file detector_particle.h.

Definition at line 110 of file detector_particle.h.

Definition at line 102 of file detector_particle.h.

Definition at line 109 of file detector_particle.h.

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 Sat Jun 8 2019 18:40:22