Public Member Functions | Private Member Functions | Private Attributes | List of all members
ProbabilisticSceneRecognition::GMMParameterEstimator Class Reference

#include <GMMParameterEstimator.h>

Public Member Functions

void addDatum (Eigen::Vector3d pSample)
 
void addDatum (Eigen::Quaternion< double > pSample)
 
void getModel (GaussianMixtureModel &gmm)
 
 GMMParameterEstimator (unsigned int pNumberOfDimensions, unsigned int pNumberOfKernelsMin, unsigned int pNumberOfKernelsMax, unsigned int pNumberOfRuns, unsigned int pNumberOfSyntheticSamples, double pIntervalPosition, double pIntervalOrientation, std::string pPathOrientationPlots, unsigned int pAttemptsPerKernel)
 
void learn ()
 
void plotModel ()
 
 ~GMMParameterEstimator ()
 

Private Member Functions

bool runExpectationMaximization (const std::vector< std::vector< double >> data, unsigned int nc, unsigned int &nparams, double &llk, double &bic, GaussianMixtureModel &model, bool useGenericMatrices=true)
 

Private Attributes

unsigned int mAttemptsPerRun
 
GaussianMixtureModel mBestGMM
 
std::vector< std::vector< double > > mData
 
double mIntervalOrientation
 
double mIntervalPosition
 
unsigned int mNumberDimensions
 
unsigned int mNumberKernels
 
unsigned int mNumberKernelsMax
 
unsigned int mNumberKernelsMin
 
unsigned int mNumberOfRuns
 
unsigned int mNumberOfSyntheticSamples
 
std::string mPathOrientationPlots
 

Detailed Description

This is a learner for gaussian mixture models (GMMs). It uses an EM algorithm to learn the mixture distribution. A maximumum likelihood process is used, so different numbers of kernels up to a maximal number are tried. The GMM with the highest likelihood is taken.

The implementation is taken from the probt documentation and can be found in the following subdirectory: /doc/html/d1/d22/a00057.html'

Author
Joachim Gehrung
Version
See SVN

Definition at line 57 of file GMMParameterEstimator.h.

Constructor & Destructor Documentation

ProbabilisticSceneRecognition::GMMParameterEstimator::GMMParameterEstimator ( unsigned int  pNumberOfDimensions,
unsigned int  pNumberOfKernelsMin,
unsigned int  pNumberOfKernelsMax,
unsigned int  pNumberOfRuns,
unsigned int  pNumberOfSyntheticSamples,
double  pIntervalPosition,
double  pIntervalOrientation,
std::string  pPathOrientationPlots,
unsigned int  pAttemptsPerKernel 
)

Constructor.

Parameters
pNumberOfDimensionsThe number of dimensions of the learning samples.
pNumberOfKernelsMinThe minimal number of kernels to try during GMM learning.
pNumberOfKernelsMaxThe maximal number of kernels to try during GMM learning.
pNumberOfRunsThe number of runs per kernel.
pNumberOfSyntheticSamplesThe number of synthetic voised samples to gereate from a given seed sample.
pIntervalPositionThe position interval for the sample relaxiation.
pIntervalOrientationThe orientation interval for the sample relaxiation.
pPathOrientationPlotsPath to the orientation plots.
pAttemptsPerKernelAttempts to find a valid kernel until learner gives up.

Definition at line 22 of file GMMParameterEstimator.cpp.

ProbabilisticSceneRecognition::GMMParameterEstimator::~GMMParameterEstimator ( )

Destructor.

Definition at line 36 of file GMMParameterEstimator.cpp.

Member Function Documentation

void ProbabilisticSceneRecognition::GMMParameterEstimator::addDatum ( Eigen::Vector3d  pSample)

Adds a single datum to the learner.

Parameters
pSampleA single sample.

Definition at line 40 of file GMMParameterEstimator.cpp.

void ProbabilisticSceneRecognition::GMMParameterEstimator::addDatum ( Eigen::Quaternion< double >  pSample)

Adds a single datum to the learner.

Parameters
pSampleA single sample.

Definition at line 74 of file GMMParameterEstimator.cpp.

void ProbabilisticSceneRecognition::GMMParameterEstimator::getModel ( GaussianMixtureModel gmm)

Copies the gaussian mixture model into the given container.

Parameters
gmmThe container to copy the gaussian mixture model into.

Definition at line 208 of file GMMParameterEstimator.cpp.

void ProbabilisticSceneRecognition::GMMParameterEstimator::learn ( )

Learns a gaussian mixture model from the given data.

Definition at line 121 of file GMMParameterEstimator.cpp.

void ProbabilisticSceneRecognition::GMMParameterEstimator::plotModel ( )

Plots the model using ProBT.

Definition at line 214 of file GMMParameterEstimator.cpp.

bool ProbabilisticSceneRecognition::GMMParameterEstimator::runExpectationMaximization ( const std::vector< std::vector< double >>  data,
unsigned int  nc,
unsigned int &  nparams,
double &  llk,
double &  bic,
GaussianMixtureModel model,
bool  useGenericMatrices = true 
)
private

Runs the EM algorithm for a given number of kernels. Uses OpenCV.

Parameters
dataworking data.
ncNumber of kernels to do the EM algorithm for.
nparamsNumber of parameters as determined by the EM algorithm.
llkLog likelihood of the model evaluated under the learning data.
bicBayesian Information Criterion score of the model evaluated under the learning data.
modelGaussian mixture model in form of a joind distribution.
useGenericMatricesWhether to use generic matrices as covariance matrices (true) or more stable but less precise diagonal matrices.
Returns
whether EM training was successfull.

Definition at line 287 of file GMMParameterEstimator.cpp.

Member Data Documentation

unsigned int ProbabilisticSceneRecognition::GMMParameterEstimator::mAttemptsPerRun
private

Number of attempts to find a valid kernel until learner gives up.

Definition at line 168 of file GMMParameterEstimator.h.

GaussianMixtureModel ProbabilisticSceneRecognition::GMMParameterEstimator::mBestGMM
private

The learned GMM with the best BIC score from OpenCV.

Definition at line 178 of file GMMParameterEstimator.h.

std::vector<std::vector<double> > ProbabilisticSceneRecognition::GMMParameterEstimator::mData
private

The data to learn from.

Definition at line 173 of file GMMParameterEstimator.h.

double ProbabilisticSceneRecognition::GMMParameterEstimator::mIntervalOrientation
private

Definition at line 158 of file GMMParameterEstimator.h.

double ProbabilisticSceneRecognition::GMMParameterEstimator::mIntervalPosition
private

The intervals (position and orientation) for the sample relaxiation.

Definition at line 158 of file GMMParameterEstimator.h.

unsigned int ProbabilisticSceneRecognition::GMMParameterEstimator::mNumberDimensions
private

The number of dimensions of the learning samples.

Definition at line 137 of file GMMParameterEstimator.h.

unsigned int ProbabilisticSceneRecognition::GMMParameterEstimator::mNumberKernels
private

Definition at line 143 of file GMMParameterEstimator.h.

unsigned int ProbabilisticSceneRecognition::GMMParameterEstimator::mNumberKernelsMax
private

Definition at line 143 of file GMMParameterEstimator.h.

unsigned int ProbabilisticSceneRecognition::GMMParameterEstimator::mNumberKernelsMin
private

The minimal, maximal and the full number of kernels. We do EM learning of GMMs for kernels [min,max] and take the GMM with the highest likelihood.

Definition at line 143 of file GMMParameterEstimator.h.

unsigned int ProbabilisticSceneRecognition::GMMParameterEstimator::mNumberOfRuns
private

The number of runs per kernel, used for picking the best model.

Definition at line 148 of file GMMParameterEstimator.h.

unsigned int ProbabilisticSceneRecognition::GMMParameterEstimator::mNumberOfSyntheticSamples
private

For every sample, n noised samples are generated to make orientation and position learning more tolerant.

Definition at line 153 of file GMMParameterEstimator.h.

std::string ProbabilisticSceneRecognition::GMMParameterEstimator::mPathOrientationPlots
private

Path to the orientation plots.

Definition at line 163 of file GMMParameterEstimator.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