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

#include <TopologyManager.h>

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

Public Member Functions

boost::shared_ptr< SceneModel::Topology > getFullyMeshedTopology ()
 
virtual boost::shared_ptr< SceneModel::Topology > getNextNeighbour ()
 
boost::shared_ptr< SceneModel::Topology > getRandomTopology ()
 
std::vector< boost::shared_ptr< SceneModel::Topology > > getStarTopologies ()
 
virtual bool hasNextNeighbour ()
 
void makeTree (boost::shared_ptr< SceneModel::Topology > pTopology)
 
void printHistory (unsigned int pRunNumber)
 
void resetTopologies ()
 
virtual void setReferenceInstance (boost::shared_ptr< SceneModel::Topology > instance)
 
 TopologyManager (std::vector< boost::shared_ptr< ISM::ObjectSet >> pExamplesList, const std::vector< std::string > &pObjectTypes, boost::shared_ptr< SceneModel::AbstractTopologyCreator > pTopologyCreator, boost::shared_ptr< AbstractTopologyEvaluator > pEvaluator)
 
 ~TopologyManager ()
 

Private Attributes

boost::shared_ptr< AbstractTopologyEvaluatormEvaluator
 
std::vector< boost::shared_ptr< ISM::ObjectSet > > mExamplesList
 
std::vector< std::vector< std::pair< boost::shared_ptr< SceneModel::Topology >, bool > > > mHistory
 
std::string mHistoryFilePath
 
unsigned int mHistoryIndex
 
std::string mHistoryOutput
 
std::vector< boost::shared_ptr< SceneModel::Topology > > mNeighbours
 
std::vector< std::string > mObjectTypes
 
PrintHelper mPrintHelper
 
bool mRevisitTopologies
 
std::map< std::string, boost::shared_ptr< SceneModel::Topology > > mSeenTopologies
 
ISM::SVGHelperPtr mSVGHelper
 
boost::shared_ptr< SceneModel::AbstractTopologyCreator > mTopologyCreator
 Generator creating the topologies. More...
 

Detailed Description

Class used to access topologies of certain types and neighbour topologies for use in combinatorial optimization. All topologies get evaluated before they are returned. Keeps track of the history of topolgy access and thus optimization.

Definition at line 40 of file TopologyManager.h.

Constructor & Destructor Documentation

ProbabilisticSceneRecognition::TopologyManager::TopologyManager ( std::vector< boost::shared_ptr< ISM::ObjectSet >>  pExamplesList,
const std::vector< std::string > &  pObjectTypes,
boost::shared_ptr< SceneModel::AbstractTopologyCreator >  pTopologyCreator,
boost::shared_ptr< AbstractTopologyEvaluator pEvaluator 
)

Constructor.

Parameters
pExamplesListList of object evidence used as basis of the topologies.
pTopologyCreatorGenerator creating the topologies.
pEvaluatorEvaluator to evaluate the topologies.

Definition at line 22 of file TopologyManager.cpp.

ProbabilisticSceneRecognition::TopologyManager::~TopologyManager ( )

Desctructor.

Definition at line 46 of file TopologyManager.cpp.

Member Function Documentation

boost::shared_ptr< SceneModel::Topology > ProbabilisticSceneRecognition::TopologyManager::getFullyMeshedTopology ( )

Get fully meshed topology for the object types in the evidence list.

Returns
fully meshed topology.

Definition at line 113 of file TopologyManager.cpp.

boost::shared_ptr< SceneModel::Topology > ProbabilisticSceneRecognition::TopologyManager::getNextNeighbour ( )
virtual

Get the next neighbour of the current reference topology.

Returns
the next neighbour of the current reference topology.

Definition at line 52 of file TopologyManager.cpp.

boost::shared_ptr< SceneModel::Topology > ProbabilisticSceneRecognition::TopologyManager::getRandomTopology ( )

Get a random topology for the object types in the evidence list.

Returns
a random topology.

Definition at line 142 of file TopologyManager.cpp.

std::vector< boost::shared_ptr< SceneModel::Topology > > ProbabilisticSceneRecognition::TopologyManager::getStarTopologies ( )

Get all the star topologies for the object types in the evidence list.

Returns
star topologies.

Definition at line 125 of file TopologyManager.cpp.

bool ProbabilisticSceneRecognition::TopologyManager::hasNextNeighbour ( )
virtual

Check whether the current reference topology has (unseen) neighbours.

Returns
whether the current reference topology has neighbours.

Definition at line 69 of file TopologyManager.cpp.

void ProbabilisticSceneRecognition::TopologyManager::makeTree ( boost::shared_ptr< SceneModel::Topology >  pTopology)

Make a tree with references out of a given topology.

Parameters
pTopologyto transform into a tree with references.

Definition at line 154 of file TopologyManager.cpp.

void ProbabilisticSceneRecognition::TopologyManager::printHistory ( unsigned int  pRunNumber)

Print history of topology access since construction or last call of resetTopologies().

Parameters
pRunNumberUnique ID of current run.

Definition at line 183 of file TopologyManager.cpp.

void ProbabilisticSceneRecognition::TopologyManager::resetTopologies ( )

Forget which topologies have already been used in optimization before running another round. Keeps cached topologies so thex don't have to be rebuilt and reevaluated.

Definition at line 175 of file TopologyManager.cpp.

void ProbabilisticSceneRecognition::TopologyManager::setReferenceInstance ( boost::shared_ptr< SceneModel::Topology >  instance)
virtual

Set a new reference topology to get the neighbours for.

Parameters
instancethe new reference topology.

Definition at line 74 of file TopologyManager.cpp.

Member Data Documentation

boost::shared_ptr<AbstractTopologyEvaluator> ProbabilisticSceneRecognition::TopologyManager::mEvaluator
private

Evaluator to evaluate the topologies.

Definition at line 121 of file TopologyManager.h.

std::vector<boost::shared_ptr<ISM::ObjectSet> > ProbabilisticSceneRecognition::TopologyManager::mExamplesList
private

List of object evidence used as basis of the topologies.

Definition at line 129 of file TopologyManager.h.

std::vector<std::vector<std::pair<boost::shared_ptr<SceneModel::Topology>, bool> > > ProbabilisticSceneRecognition::TopologyManager::mHistory
private

The history of topology access and thus optimization. The boolean in the pair indicates whether the topology was selected for use as reference in the next step.

Definition at line 140 of file TopologyManager.h.

std::string ProbabilisticSceneRecognition::TopologyManager::mHistoryFilePath
private

Path to the files to write the histories into if mHistoryOutput is set to "file".

Definition at line 156 of file TopologyManager.h.

unsigned int ProbabilisticSceneRecognition::TopologyManager::mHistoryIndex
private

Index of the current optimization step in mHistory. increased by setReferenceInstance().

Definition at line 145 of file TopologyManager.h.

std::string ProbabilisticSceneRecognition::TopologyManager::mHistoryOutput
private

Output target of the optimization run history. From "none", "screen", "file".

Definition at line 151 of file TopologyManager.h.

std::vector<boost::shared_ptr<SceneModel::Topology> > ProbabilisticSceneRecognition::TopologyManager::mNeighbours
private

List of all unvisited neighbours of current reference topology.

Definition at line 112 of file TopologyManager.h.

std::vector<std::string> ProbabilisticSceneRecognition::TopologyManager::mObjectTypes
private

List of different object types in the examples list.

Definition at line 134 of file TopologyManager.h.

PrintHelper ProbabilisticSceneRecognition::TopologyManager::mPrintHelper
private

Class used to print lines as headers, marked with dividers.

Definition at line 171 of file TopologyManager.h.

bool ProbabilisticSceneRecognition::TopologyManager::mRevisitTopologies
private

Whether to revisit topologies already seen in this optimization run.

Definition at line 166 of file TopologyManager.h.

std::map<std::string, boost::shared_ptr<SceneModel::Topology> > ProbabilisticSceneRecognition::TopologyManager::mSeenTopologies
private

List of all topologies visited since construction or last call of resetTopologies().

Definition at line 116 of file TopologyManager.h.

ISM::SVGHelperPtr ProbabilisticSceneRecognition::TopologyManager::mSVGHelper
private

Helps to write history to svg file if output is set to "svg".

Definition at line 161 of file TopologyManager.h.

boost::shared_ptr<SceneModel::AbstractTopologyCreator> ProbabilisticSceneRecognition::TopologyManager::mTopologyCreator
private

Generator creating the topologies.

Definition at line 125 of file TopologyManager.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