#include <SceneObjectDescription.h>
Public Member Functions | |
std::string | getDescription () |
double | getSceneObjectPriori () |
double | getSceneObjectProbability () |
void | initializeVisualizer (boost::shared_ptr< Visualization::ProbabilisticSceneVisualization > mSuperior) |
void | load (boost::property_tree::ptree &pPt) |
SceneObjectDescription () | |
void | setBestStatus (bool pStatus) |
void | update (std::vector< ISM::Object > pEvidenceList, std::ofstream &pRuntimeLogger) |
~SceneObjectDescription () | |
Private Attributes | |
boost::shared_ptr< SceneObjectContent > | mContent |
std::string | mDescription |
double | mPriori |
std::string | mType |
boost::shared_ptr< Visualization::ProbabilisticPrimarySceneObjectVisualization > | mVisualizer |
This class models a single instance of a scene object. A scene object contains information about the object as well as the scene. One could describe it as an object in the context of a scene.
Definition at line 53 of file SceneObjectDescription.h.
ProbabilisticSceneRecognition::SceneObjectDescription::SceneObjectDescription | ( | ) |
Constructor.
Definition at line 22 of file SceneObjectDescription.cpp.
ProbabilisticSceneRecognition::SceneObjectDescription::~SceneObjectDescription | ( | ) |
Destructor.
Definition at line 26 of file SceneObjectDescription.cpp.
std::string ProbabilisticSceneRecognition::SceneObjectDescription::getDescription | ( | ) |
Returns the description of the scene object.
Definition at line 120 of file SceneObjectDescription.cpp.
double ProbabilisticSceneRecognition::SceneObjectDescription::getSceneObjectPriori | ( | ) |
Returns the a priori probability of the scene object.
Definition at line 115 of file SceneObjectDescription.cpp.
double ProbabilisticSceneRecognition::SceneObjectDescription::getSceneObjectProbability | ( | ) |
Returns the probability for the scene object modelled by this class.
Definition at line 105 of file SceneObjectDescription.cpp.
void ProbabilisticSceneRecognition::SceneObjectDescription::initializeVisualizer | ( | boost::shared_ptr< Visualization::ProbabilisticSceneVisualization > | mSuperior | ) |
Initializes the visualization mechanism.
mSuperior | The superior visualizer coordinating the scene visualizers. |
Definition at line 65 of file SceneObjectDescription.cpp.
void ProbabilisticSceneRecognition::SceneObjectDescription::load | ( | boost::property_tree::ptree & | pPt | ) |
Loads the model from an XML file.
pPt | Data structure for performing XML operations. |
Definition at line 30 of file SceneObjectDescription.cpp.
void ProbabilisticSceneRecognition::SceneObjectDescription::setBestStatus | ( | bool | pStatus | ) |
Marks the scene object with the best score.
pStatus | True, to select the scene object as the one with the best score. |
Definition at line 125 of file SceneObjectDescription.cpp.
void ProbabilisticSceneRecognition::SceneObjectDescription::update | ( | std::vector< ISM::Object > | pEvidenceList, |
std::ofstream & | pRuntimeLogger | ||
) |
Updates the model with new evidence.
pEvidenceList | A list containing all evidences. |
pRuntimeLogger | A file handle for runtime logging. |
Definition at line 81 of file SceneObjectDescription.cpp.
|
private |
A wrapper for the model that states how the scene object is modelled.
Definition at line 136 of file SceneObjectDescription.h.
|
private |
A short description of the scene object (e.g. Cup, Blue Plate, ...).
Definition at line 131 of file SceneObjectDescription.h.
|
private |
A priori probability of the scene object.
Definition at line 121 of file SceneObjectDescription.h.
|
private |
The type of the content wrapped in this class.
Definition at line 126 of file SceneObjectDescription.h.
|
private |
Coordinates the secondary scene object visualizers.
Definition at line 141 of file SceneObjectDescription.h.