Public Member Functions | Private Attributes | Static Private Attributes | List of all members
ProbabilisticSceneRecognition::PSMInference::GaussianKernel Class Reference

#include <GaussianKernel.h>

Public Member Functions

double evaluate (Eigen::VectorXd pEvidence)
 
 GaussianKernel (unsigned int pDimension, boost::property_tree::ptree &pPt)
 
double getWeight ()
 
void initializeVisualizer (boost::shared_ptr< Visualization::ProbabilisticSecondarySceneObjectVisualization > mVisualizer)
 
void load (boost::property_tree::ptree &pPt)
 
void visualize (boost::shared_ptr< Visualization::ProbabilisticSecondarySceneObjectVisualization > mVisualizer, Eigen::VectorXd pEvidence)
 
 ~GaussianKernel ()
 

Private Attributes

boost::shared_ptr< Eigen::MatrixXd > mCovariance
 
unsigned int mDimension
 
boost::shared_ptr< Eigen::VectorXd > mMean
 
boost::shared_ptr< Eigen::Matrix3d > mPositionCovariance
 
boost::shared_ptr< Eigen::Vector3d > mPositionMean
 
double mWeight
 

Static Private Attributes

static const int MC_SAMPLES = 100
 

Detailed Description

This class implements a single 6D gaussian kernel. It stores a weight, mean vector and covariance matrix.

Definition at line 46 of file inference/model/foreground/ocm/shape/GaussianKernel.h.

Constructor & Destructor Documentation

ProbabilisticSceneRecognition::PSMInference::GaussianKernel::GaussianKernel ( unsigned int  pDimension,
boost::property_tree::ptree &  pPt 
)

Constructor.

Parameters
pDimensionThe number of dimensions of the kernel.
pPtData structure for performing XML operations.

Definition at line 24 of file inference/model/foreground/ocm/shape/GaussianKernel.cpp.

ProbabilisticSceneRecognition::PSMInference::GaussianKernel::~GaussianKernel ( )

Destructor.

Definition at line 38 of file inference/model/foreground/ocm/shape/GaussianKernel.cpp.

Member Function Documentation

double ProbabilisticSceneRecognition::PSMInference::GaussianKernel::evaluate ( Eigen::VectorXd  pEvidence)

Evaluate the gaussian kernel with the given evidence.

Parameters
pEvidenceThe evidence to evaluate the kernel with.
Returns
Probability for the given evidence.

Definition at line 71 of file inference/model/foreground/ocm/shape/GaussianKernel.cpp.

double ProbabilisticSceneRecognition::PSMInference::GaussianKernel::getWeight ( )

Return the weight of the gaussian kernel.

Definition at line 76 of file inference/model/foreground/ocm/shape/GaussianKernel.cpp.

void ProbabilisticSceneRecognition::PSMInference::GaussianKernel::initializeVisualizer ( boost::shared_ptr< Visualization::ProbabilisticSecondarySceneObjectVisualization >  mVisualizer)

Initializes the visualization mechanism.

Parameters
mVisualizerThe visualizer for the secondary scene object represented by this node.

Definition at line 61 of file inference/model/foreground/ocm/shape/GaussianKernel.cpp.

void ProbabilisticSceneRecognition::PSMInference::GaussianKernel::load ( boost::property_tree::ptree &  pPt)

Loads the working data from an XML file.

Parameters
pPtData structure for performing XML operations.

Definition at line 43 of file inference/model/foreground/ocm/shape/GaussianKernel.cpp.

void ProbabilisticSceneRecognition::PSMInference::GaussianKernel::visualize ( boost::shared_ptr< Visualization::ProbabilisticSecondarySceneObjectVisualization >  mVisualizer,
Eigen::VectorXd  pEvidence 
)

Evaluates the gaussian kernel for the given evidence and visualizes the result.

Parameters
mVisualizerThe visualizer for the secondary scene object represented by this node.
pEvidenceThe evidence for that the visualization should take place.

Definition at line 66 of file inference/model/foreground/ocm/shape/GaussianKernel.cpp.

Member Data Documentation

const int ProbabilisticSceneRecognition::PSMInference::GaussianKernel::MC_SAMPLES = 100
staticprivate

The number of samples used for monte carlo integration of the gaussian.

Definition at line 52 of file inference/model/foreground/ocm/shape/GaussianKernel.h.

boost::shared_ptr<Eigen::MatrixXd> ProbabilisticSceneRecognition::PSMInference::GaussianKernel::mCovariance
private

The covariance matrix of the multivariate gaussian.

Definition at line 124 of file inference/model/foreground/ocm/shape/GaussianKernel.h.

unsigned int ProbabilisticSceneRecognition::PSMInference::GaussianKernel::mDimension
private

The number of dimensions of the distribution.

Definition at line 109 of file inference/model/foreground/ocm/shape/GaussianKernel.h.

boost::shared_ptr<Eigen::VectorXd> ProbabilisticSceneRecognition::PSMInference::GaussianKernel::mMean
private

The mean vector of the multivariate gaussian.

Definition at line 119 of file inference/model/foreground/ocm/shape/GaussianKernel.h.

boost::shared_ptr<Eigen::Matrix3d> ProbabilisticSceneRecognition::PSMInference::GaussianKernel::mPositionCovariance
private

The position part of the covariance matrix.

Definition at line 134 of file inference/model/foreground/ocm/shape/GaussianKernel.h.

boost::shared_ptr<Eigen::Vector3d> ProbabilisticSceneRecognition::PSMInference::GaussianKernel::mPositionMean
private

The position part of the mean vector.

Definition at line 129 of file inference/model/foreground/ocm/shape/GaussianKernel.h.

double ProbabilisticSceneRecognition::PSMInference::GaussianKernel::mWeight
private

The weight of the gaussian kernel determining how string it contributes to the gaussian mixture distribution.

Definition at line 114 of file inference/model/foreground/ocm/shape/GaussianKernel.h.


The documentation for this class was generated from the following files:


asr_psm
Author(s): Braun Kai, Gehrung Joachim, Heizmann Heinrich, Meißner Pascal
autogenerated on Fri Nov 15 2019 04:00:09