Public Member Functions | Private Member Functions
BFL::MCPdfPosVel Class Reference

Class representing a posvel mcpdf. More...

#include <mcpdf_pos_vel.h>

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

List of all members.

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.
MatrixWrapper::Matrix getHistogramVel (const tf::Vector3 &min, const tf::Vector3 &max, const tf::Vector3 &step) const
 Get vel histogram from certain area.
void getParticleCloud (const tf::Vector3 &step, double threshold, sensor_msgs::PointCloud &cloud) const
 Get evenly distributed particle cloud.
 MCPdfPosVel (unsigned int num_samples)
 Constructor.
virtual unsigned int numParticlesGet () const
virtual WeightedSample
< StatePosVel
SampleGet (unsigned int particle) const
virtual ~MCPdfPosVel ()
 Destructor.

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.

Detailed Description

Class representing a posvel mcpdf.

Definition at line 48 of file mcpdf_pos_vel.h.


Constructor & Destructor Documentation

MCPdfPosVel::MCPdfPosVel ( unsigned int  num_samples)

Constructor.

Definition at line 51 of file mcpdf_pos_vel.cpp.

Destructor.

Definition at line 55 of file mcpdf_pos_vel.cpp.


Member Function Documentation

Reimplemented from BFL::BFL::MCPdf< StatePosVel >.

Definition at line 66 of file mcpdf_pos_vel.cpp.

MatrixWrapper::Matrix 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 148 of file mcpdf_pos_vel.cpp.

MatrixWrapper::Matrix 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 134 of file mcpdf_pos_vel.cpp.

MatrixWrapper::Matrix 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 141 of file mcpdf_pos_vel.cpp.

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

Get evenly distributed particle cloud.

Definition at line 83 of file mcpdf_pos_vel.cpp.

unsigned int MCPdfPosVel::numParticlesGet ( ) const [virtual]

Definition at line 177 of file mcpdf_pos_vel.cpp.

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

Reimplemented from BFL::BFL::MCPdf< StatePosVel >.

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