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

#include <ShapeTermLearner.h>

Inheritance diagram for ProbabilisticSceneRecognition::ShapeTermLearner:
Inheritance graph
[legend]

Public Member Functions

void learn (boost::shared_ptr< OcmModel > pModel)
 
 ShapeTermLearner (std::string pSceneName="")
 
 ~ShapeTermLearner ()
 
- Public Member Functions inherited from ProbabilisticSceneRecognition::TermLearner
 TermLearner ()
 
virtual ~TermLearner ()
 

Private Member Functions

void getParameter (std::string pParameterName, double &pParameter)
 
void getParameter (std::string pParameterName, int &pParameter)
 
void learn (boost::shared_ptr< OcmTree > pNode)
 
void learnNodePose (boost::shared_ptr< OcmTree > pParent, boost::shared_ptr< OcmTree > pChild)
 

Private Attributes

int mAttemptsPerRun
 
double mIntervalOrientation
 
double mIntervalPosition
 
int mNumberKernelsMax
 
int mNumberKernelsMin
 
int mNumberOfSyntheticSamples
 
std::string mPathOrientationPlots
 
ros::NodeHandle mPrivateNamespaceHandle
 
int mRunsPerKernel
 
std::string mSceneName
 

Detailed Description

A learner for the shape term of the OCM.

Author
Joachim Gehrung
Version
See SVN

Definition at line 42 of file ShapeTermLearner.h.

Constructor & Destructor Documentation

ProbabilisticSceneRecognition::ShapeTermLearner::ShapeTermLearner ( std::string  pSceneName = "")

Constructor.

Parameters
pSceneNameThe name of the scene.

Definition at line 22 of file ShapeTermLearner.cpp.

ProbabilisticSceneRecognition::ShapeTermLearner::~ShapeTermLearner ( )

Destructor.

Definition at line 29 of file ShapeTermLearner.cpp.

Member Function Documentation

void ProbabilisticSceneRecognition::ShapeTermLearner::getParameter ( std::string  pParameterName,
double &  pParameter 
)
private

Fetches the parameter from the ROS parameter server. First attempts to get the parameter specified for this scene (~/mSceneName/pParameterName), and, if that fails, for the private namespace (~/pParameterName). If that fails as well, a runtime_error is thrown.

Parameters
pParameterNameName of the parameter to fetch.
pParameterWhere to write the fetched value.

Definition at line 130 of file ShapeTermLearner.cpp.

void ProbabilisticSceneRecognition::ShapeTermLearner::getParameter ( std::string  pParameterName,
int &  pParameter 
)
private

Fetches the parameter from the ROS parameter server. First attempts to get the parameter specified for this scene (~/mSceneName/pParameterName), and, if that fails, for the private namespace (~/pParameterName). If that fails as well, a runtime_error is thrown.

Parameters
pParameterNameName of the parameter to fetch.
pParameterWhere to write the fetched value.

Definition at line 143 of file ShapeTermLearner.cpp.

void ProbabilisticSceneRecognition::ShapeTermLearner::learn ( boost::shared_ptr< OcmModel pModel)
virtual

Learns the term parameters.

Parameters
pModelThe OCM model that provides raw data and containers for the parameters to learn.

Implements ProbabilisticSceneRecognition::TermLearner.

Definition at line 33 of file ShapeTermLearner.cpp.

void ProbabilisticSceneRecognition::ShapeTermLearner::learn ( boost::shared_ptr< OcmTree pNode)
private

Learns the term parameters.

Parameters
pNodeOCM parent node that provides raw data and containers for the parameters to learn.

Definition at line 46 of file ShapeTermLearner.cpp.

void ProbabilisticSceneRecognition::ShapeTermLearner::learnNodePose ( boost::shared_ptr< OcmTree pParent,
boost::shared_ptr< OcmTree pChild 
)
private

Learns the shape term parameters for a parent/child pair.

Parameters
pParentThe parent node the pose should be learned relative to.
pChildThe child node to assign the learned pose to.

Definition at line 59 of file ShapeTermLearner.cpp.

Member Data Documentation

int ProbabilisticSceneRecognition::ShapeTermLearner::mAttemptsPerRun
private

The number of attempts per run to find a valid model until the learner gives up.

Definition at line 138 of file ShapeTermLearner.h.

double ProbabilisticSceneRecognition::ShapeTermLearner::mIntervalOrientation
private

Definition at line 123 of file ShapeTermLearner.h.

double ProbabilisticSceneRecognition::ShapeTermLearner::mIntervalPosition
private

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

Definition at line 123 of file ShapeTermLearner.h.

int ProbabilisticSceneRecognition::ShapeTermLearner::mNumberKernelsMax
private

Definition at line 108 of file ShapeTermLearner.h.

int ProbabilisticSceneRecognition::ShapeTermLearner::mNumberKernelsMin
private

The minmal and maximal number of kernels.

Definition at line 108 of file ShapeTermLearner.h.

int ProbabilisticSceneRecognition::ShapeTermLearner::mNumberOfSyntheticSamples
private

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

Definition at line 118 of file ShapeTermLearner.h.

std::string ProbabilisticSceneRecognition::ShapeTermLearner::mPathOrientationPlots
private

Path to the orientation plots.

Definition at line 128 of file ShapeTermLearner.h.

ros::NodeHandle ProbabilisticSceneRecognition::ShapeTermLearner::mPrivateNamespaceHandle
private

Interface to the private namespace of the ros node.

Definition at line 133 of file ShapeTermLearner.h.

int ProbabilisticSceneRecognition::ShapeTermLearner::mRunsPerKernel
private

The number of runs per kernel.

Definition at line 113 of file ShapeTermLearner.h.

std::string ProbabilisticSceneRecognition::ShapeTermLearner::mSceneName
private

The name of the scene.

Definition at line 143 of file ShapeTermLearner.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