28 #include <Eigen/Geometry> 29 #include <Eigen/Eigenvalues> 31 #include <boost/lexical_cast.hpp> 32 #include <boost/property_tree/ptree.hpp> 34 #include <asr_msgs/AsrObject.h> 38 #include <opencv2/opencv.hpp> 40 #include <visualization/gnuplot/GMMGnuplotVisualization.h> 73 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);
85 void addDatum(Eigen::Vector3d pSample);
92 void addDatum(Eigen::Quaternion<double> pSample);
128 unsigned int& nparams,
132 bool useGenericMatrices =
true);
173 std::vector<std::vector<double> >
mData;
void getModel(GaussianMixtureModel &gmm)
bool runExpectationMaximization(const std::vector< std::vector< double >> data, unsigned int nc, unsigned int &nparams, double &llk, double &bic, GaussianMixtureModel &model, bool useGenericMatrices=true)
unsigned int mNumberKernels
void addDatum(Eigen::Vector3d pSample)
std::string mPathOrientationPlots
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)
double mIntervalOrientation
unsigned int mNumberKernelsMin
std::vector< std::vector< double > > mData
unsigned int mNumberKernelsMax
unsigned int mNumberOfRuns
unsigned int mNumberOfSyntheticSamples
unsigned int mNumberDimensions
GaussianMixtureModel mBestGMM
unsigned int mAttemptsPerRun