#include <SceneLearningEngine.h>
Public Member Functions | |
void | extractTracksFromDbFile (const std::string &dbFileName) |
void | generateSceneModel () |
void | learn () |
void | readLearnerInput () |
void | saveSceneModel () |
SceneLearningEngine () | |
void | visualizeSceneModel () |
~SceneLearningEngine () | |
Private Member Functions | |
void | initializeSceneModel (double pWorkspaceVolume, double mStaticBreakRatio, double mTogetherRatio, double mMaxAngleDeviation) |
void | initializeVisualizationChain () |
Private Attributes | |
bool | mAddTimestampsToFilename |
std::string | mBaseFrameId |
std::string | mDateTime |
ros::NodeHandle | mGeneratorHandle |
std::string | mInputDbFilename |
bool | mIntermediateResults |
ros::NodeHandle | mPrivateNamespaceHandle |
double | mScaleFactor |
std::string | mSceneModelDirectory |
boost::shared_ptr< SceneModelLearner > | mSceneModelLearner |
std::string | mSceneModelName |
std::string | mSceneModelType |
double | mSigmaMultiplicator |
boost::shared_ptr< Visualization::ProbabilisticSceneModelVisualization > | mVisualizer |
ISM::RecordedPatternPtr | recordedPattern |
boost::shared_ptr< ISM::TableHelper > | tableHelper |
Class for learning the model required for probabilistic scene recognition.
Definition at line 48 of file SceneLearningEngine.h.
ProbabilisticSceneRecognition::SceneLearningEngine::SceneLearningEngine | ( | ) |
Constructor.
Definition at line 25 of file SceneLearningEngine.cpp.
ProbabilisticSceneRecognition::SceneLearningEngine::~SceneLearningEngine | ( | ) |
Destructor.
Definition at line 102 of file SceneLearningEngine.cpp.
void ProbabilisticSceneRecognition::SceneLearningEngine::extractTracksFromDbFile | ( | const std::string & | dbFileName | ) |
Open database and extract ISM::ObjectSets. All object sets that the database contains, are transfered to the distribution parameter learners.
pPbdSceneGraphsBagPath | Path of file to be parsed ISM::ObjectSets. |
Definition at line 119 of file SceneLearningEngine.cpp.
void ProbabilisticSceneRecognition::SceneLearningEngine::generateSceneModel | ( | ) |
All learnt information is transfered into a scene model description.
Definition at line 140 of file SceneLearningEngine.cpp.
|
private |
Initializes the scene model with the parameters specified via the node handle.
pWorkspaceVolume | Volume of the workspace the scene takes place in. |
pStaticBreakRatio | The maximum ration the relationship between two objects may break. |
pTogetherRatio | The minimum ratio that two objects must be together. |
pMaxAngleDeviation | Maximum angle deviation between two objects before counting as break. |
Definition at line 185 of file SceneLearningEngine.cpp.
|
private |
Initializes the chain responsible for visualization.
Definition at line 190 of file SceneLearningEngine.cpp.
void ProbabilisticSceneRecognition::SceneLearningEngine::learn | ( | ) |
Learn recorded pattern and pass it to mSampleList.
void ProbabilisticSceneRecognition::SceneLearningEngine::readLearnerInput | ( | ) |
Extract ISM::ObjectSets from all databases given as CLI parameters. Transfer all measurements for each scene into distribution parameter learners.
Definition at line 107 of file SceneLearningEngine.cpp.
void ProbabilisticSceneRecognition::SceneLearningEngine::saveSceneModel | ( | ) |
Learnt scene model is written to an xml file whose name consists of a scene model identifier set before and a timestamp.
Definition at line 153 of file SceneLearningEngine.cpp.
void ProbabilisticSceneRecognition::SceneLearningEngine::visualizeSceneModel | ( | ) |
All distributions in the decomposition of the scene model and the learning data are plotted.
Definition at line 174 of file SceneLearningEngine.cpp.
|
private |
Set true to add timestamps to filename.
Definition at line 142 of file SceneLearningEngine.h.
|
private |
The coordinate frame in which the visualization should take place.
Definition at line 147 of file SceneLearningEngine.h.
|
private |
The timestamp for the point in time the learner was started.
Definition at line 162 of file SceneLearningEngine.h.
|
private |
Interface to basic ros node functionality enhanced by the given class.
Definition at line 118 of file SceneLearningEngine.h.
|
private |
Path to the directory the .sqlite file containing the training data.
Definition at line 182 of file SceneLearningEngine.h.
|
private |
Set true to visualize intermediate results instead.
Definition at line 137 of file SceneLearningEngine.h.
|
private |
Interface to the private namespace of the ros node.
Definition at line 123 of file SceneLearningEngine.h.
|
private |
The visualization is pretty small, this scale factor enlarges it.
Definition at line 152 of file SceneLearningEngine.h.
|
private |
Path to the directory the XML file containing the model is stored after learning.
Definition at line 177 of file SceneLearningEngine.h.
|
private |
The learner for the probabilistic scene model.
Definition at line 191 of file SceneLearningEngine.h.
|
private |
Name of the scene model.
Definition at line 167 of file SceneLearningEngine.h.
|
private |
Determines the type of representation of the scene model that should be learned.
Definition at line 172 of file SceneLearningEngine.h.
|
private |
This factor determines the radii of the covariance ellipse.
Definition at line 157 of file SceneLearningEngine.h.
|
private |
Class for coordinating the scene visualizers.
Definition at line 196 of file SceneLearningEngine.h.
|
private |
Recorded Pattern Pointer
Definition at line 187 of file SceneLearningEngine.h.
|
private |
TableHelper to extract Objects from ".sqlite"-file.
Definition at line 128 of file SceneLearningEngine.h.