Public Member Functions | Private Member Functions | List of all members
BFL::MCPdfPosVel Class Reference

Class representing a posvel mcpdf. More...

#include <mcpdf_pos_vel.h>

Inheritance diagram for BFL::MCPdfPosVel:
Inheritance graph
[legend]

Public Member Functions

virtual StatePosVel ExpectedValueGet () const
 
MatrixWrapper::Matrix getHistogramPos (const tf::Vector3 &min, const tf::Vector3 &max, const tf::Vector3 &step) const
 Get pos histogram from certain area. More...
 
MatrixWrapper::Matrix getHistogramVel (const tf::Vector3 &min, const tf::Vector3 &max, const tf::Vector3 &step) const
 Get vel histogram from certain area. More...
 
void getParticleCloud (const tf::Vector3 &step, double threshold, sensor_msgs::PointCloud &cloud) const
 Get evenly distributed particle cloud. More...
 
 MCPdfPosVel (unsigned int num_samples)
 Constructor. More...
 
virtual unsigned int numParticlesGet () const
 
virtual WeightedSample< StatePosVelSampleGet (unsigned int particle) const
 
virtual ~MCPdfPosVel ()
 Destructor. More...
 
- Public Member Functions inherited from BFL::BFL::MCPdf< StatePosVel >
virtual MCPdf< StatePosVel > * Clone () const
 
SymmetricMatrix CovarianceGet () const
 
SymmetricMatrix CovarianceGet () const
 
MatrixWrapper::SymmetricMatrix CovarianceGet () const
 
vector< double > & CumulativePDFGet ()
 
unsigned int ExpectedValueGet () const
 
ColumnVector ExpectedValueGet () const
 
StatePosVel ExpectedValueGet () const
 
const vector< WeightedSample< StatePosVel > > & ListOfSamplesGet () const
 
bool ListOfSamplesSet (const vector< WeightedSample< StatePosVel > > &list_of_samples)
 
bool ListOfSamplesSet (const vector< Sample< StatePosVel > > &list_of_samples)
 
bool ListOfSamplesUpdate (const vector< WeightedSample< StatePosVel > > &list_of_samples)
 
bool ListOfSamplesUpdate (const vector< Sample< StatePosVel > > &list_of_samples)
 
 MCPdf (unsigned int num_samples=0, unsigned int dimension=0)
 
 MCPdf (const MCPdf< StatePosVel > &)
 
 MCPdf (const MCPdf &pdf)
 
 MCPdf (unsigned int num_samples, unsigned int dimension)
 
unsigned int NumSamplesGet () const
 
void NumSamplesSet (unsigned int num_samples)
 
bool SampleFrom (Sample< StatePosVel > &one_sample, int method=DEFAULT, void *args=NULL) const
 
bool SampleFrom (vector< Sample< StatePosVel > > &list_samples, const unsigned int num_samples, int method=DEFAULT, void *args=NULL) const
 
const WeightedSample< StatePosVel > & SampleGet (unsigned int i) const
 
virtual ~MCPdf ()
 
- Public Member Functions inherited from BFL::BFL::Pdf< T >
unsigned int DimensionGet () const
 
virtual void DimensionSet (unsigned int dim)
 
 Pdf (unsigned int dimension=0)
 
virtual Probability ProbabilityGet (const T &input) const
 
virtual bool SampleFrom (vector< Sample< T > > &list_samples, const unsigned int num_samples, int method=DEFAULT, void *args=NULL) const
 
virtual bool SampleFrom (Sample< T > &one_sample, int method=DEFAULT, void *args=NULL) const
 
virtual ~Pdf ()
 

Private Member Functions

MatrixWrapper::Matrix getHistogram (const tf::Vector3 &min, const tf::Vector3 &max, const tf::Vector3 &step, bool pos_hist) const
 Get histogram from certain area. More...
 

Additional Inherited Members

- Protected Member Functions inherited from BFL::BFL::MCPdf< StatePosVel >
void CumPDFUpdate ()
 
bool NormalizeWeights ()
 
bool SumWeightsUpdate ()
 
- Protected Attributes inherited from BFL::BFL::MCPdf< StatePosVel >
vector< double > _CumPDF
 
vector< WeightedSample< StatePosVel > > _listOfSamples
 
double _SumWeights
 

Detailed Description

Class representing a posvel mcpdf.

Definition at line 48 of file mcpdf_pos_vel.h.

Constructor & Destructor Documentation

BFL::MCPdfPosVel::MCPdfPosVel ( unsigned int  num_samples)
explicit

Constructor.

Definition at line 48 of file mcpdf_pos_vel.cpp.

BFL::MCPdfPosVel::~MCPdfPosVel ( )
virtual

Destructor.

Definition at line 52 of file mcpdf_pos_vel.cpp.

Member Function Documentation

StatePosVel BFL::MCPdfPosVel::ExpectedValueGet ( ) const
virtual

Reimplemented from BFL::BFL::Pdf< T >.

Definition at line 61 of file mcpdf_pos_vel.cpp.

MatrixWrapper::Matrix BFL::MCPdfPosVel::getHistogram ( const tf::Vector3 min,
const tf::Vector3 max,
const tf::Vector3 step,
bool  pos_hist 
) const
private

Get histogram from certain area.

Definition at line 143 of file mcpdf_pos_vel.cpp.

MatrixWrapper::Matrix BFL::MCPdfPosVel::getHistogramPos ( const tf::Vector3 min,
const tf::Vector3 max,
const tf::Vector3 step 
) const

Get pos histogram from certain area.

Get histogram from pos.

Definition at line 127 of file mcpdf_pos_vel.cpp.

MatrixWrapper::Matrix BFL::MCPdfPosVel::getHistogramVel ( const tf::Vector3 min,
const tf::Vector3 max,
const tf::Vector3 step 
) const

Get vel histogram from certain area.

Get histogram from vel.

Definition at line 135 of file mcpdf_pos_vel.cpp.

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

Get evenly distributed particle cloud.

Definition at line 77 of file mcpdf_pos_vel.cpp.

unsigned int BFL::MCPdfPosVel::numParticlesGet ( ) const
virtual

Definition at line 171 of file mcpdf_pos_vel.cpp.

WeightedSample< StatePosVel > BFL::MCPdfPosVel::SampleGet ( unsigned int  particle) const
virtual

Definition at line 55 of file mcpdf_pos_vel.cpp.


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