Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
ISM::Recognizer Class Reference

#include <Recognizer.hpp>

Public Member Functions

void arrangePatternsAccordingToTreeHeight ()
 
void clearData ()
 
PatternNameAndVotingSpaceTuple getBufferedVotingSpace ()
 
std::map< ObjectPtr, std::vector< VotedPosePtr > > getVotingCache ()
 
const std::vector< RecognitionResultPtrrecognizePattern (const ObjectSetPtr &objectSet, const double filterThreshold=0.0, const int resultsPerPattern=-1, const std::string targetPatternName="")
 
 Recognizer (const std::string &dbfilename, double bin_size, double maxProjectionAngleDeviation, bool enabledSelfVoteCheck, int raterType=0)
 
void setObjectTypes (std::set< std::string > objectTypes)
 
void setPatternDefinitions (ISM::PatternNameToPatternMap patternDefinitions)
 
void setVoteSpecifiersPerObject (ISM::ObjectTypeToVoteMap voteSpecifiersPerObject)
 
void setVotingSpaceToBeBuffered (std::string patternName)
 

Private Member Functions

PosePtr calculatePoseFromVote (const PosePtr &pose, const VoteSpecifierPtr &vote) const
 
void calculateVotedPosesForAllObjects ()
 
void fillAndEvalVotingSpaceAtTreeHeight (unsigned int treeHeight)
 
void getPatternDefinitions ()
 
int objectAlreadyInSet (const ObjectPtr &o)
 
int resultAlreadyExisting (const RecognitionResultPtr &res)
 

Static Private Member Functions

static std::vector< RecognitionResultPtrassembleIsmTrees (const std::vector< RecognitionResultPtr > &ismResults, const double filterThreshold, const int resultsPerPattern, const std::string targetPatternName)
 
static std::vector< RecognitionResultPtrgetSubPatternsForResult (RecognitionResultPtr result, std::map< std::string, std::vector< RecognitionResultPtr > > patternNameToResults)
 

Private Attributes

double bin_size
 
bool enabledSelfVoteCheck
 
ObjectSetPtr inputSet
 
std::vector< RecognitionResultPtrismResults
 
double maxProjectionAngleDeviation
 
const int mRaterType
 
std::set< std::string > objectTypes
 
PatternNameToPatternMap patternDefinitions
 
std::string patternForVotingSpaceViz
 
TreeHeightToPatternName patternPerTreeHeight
 
PatternNameToVotedPoses patternToVotedPoses
 
TableHelperPtr tableHelper
 
ObjectTypeToVoteMap voteSpecifiersPerObject
 
std::map< ObjectPtr, std::vector< VotedPosePtr > > votingCache
 
PatternNameAndVotingSpaceTuple votingSpaceBuffer
 

Detailed Description

Recognizer class. Class in which scene recognition with (non-)hierarchical isms is performed based on a hough voting scheme and vote backprojection. See Meissner et al. 2013 in Section IV and V (B).

Definition at line 35 of file Recognizer.hpp.

Constructor & Destructor Documentation

ISM::Recognizer::Recognizer ( const std::string &  dbfilename,
double  bin_size,
double  maxProjectionAngleDeviation,
bool  enabledSelfVoteCheck,
int  raterType = 0 
)

Create recognition interface to an sqlite db.

Parameters
dbfilenameFile containing scenes we want to be able to detect with this recognizer.
bin_sizeSide length of cubes (bins) making up voxel grid in which hough voting is performed. Maximal accepted distance between scene reference hypotheses of different objects in a bin.
maxProjectionAngleDeviationMaximal accepted difference in orientations of scene reference hypotheses of different objects in a bin.
enabledSelfVoteCheckSelf-Vote-Check: Ensures the use of votedPose from a selfvoting object as originForFitting, if such an object exist.
raterTypeObjective function that is used for rating how well votedPoses in voxel grid match each other (especially in recognition results).

Definition at line 37 of file Recognizer.cpp.

Member Function Documentation

void ISM::Recognizer::arrangePatternsAccordingToTreeHeight ( )

Definition at line 263 of file Recognizer.cpp.

std::vector< RecognitionResultPtr > ISM::Recognizer::assembleIsmTrees ( const std::vector< RecognitionResultPtr > &  ismResults,
const double  filterThreshold,
const int  resultsPerPattern,
const std::string  targetPatternName 
)
staticprivate

Definition at line 355 of file Recognizer.cpp.

PosePtr ISM::Recognizer::calculatePoseFromVote ( const PosePtr pose,
const VoteSpecifierPtr vote 
) const
private

Definition at line 243 of file Recognizer.cpp.

void ISM::Recognizer::calculateVotedPosesForAllObjects ( )
private

Definition at line 69 of file Recognizer.cpp.

void ISM::Recognizer::clearData ( )
inline

Definition at line 123 of file Recognizer.hpp.

void ISM::Recognizer::fillAndEvalVotingSpaceAtTreeHeight ( unsigned int  treeHeight)
private

Definition at line 140 of file Recognizer.cpp.

PatternNameAndVotingSpaceTuple ISM::Recognizer::getBufferedVotingSpace ( )
inline

Definition at line 140 of file Recognizer.hpp.

void ISM::Recognizer::getPatternDefinitions ( )
private

Definition at line 248 of file Recognizer.cpp.

std::vector< RecognitionResultPtr > ISM::Recognizer::getSubPatternsForResult ( RecognitionResultPtr  result,
std::map< std::string, std::vector< RecognitionResultPtr > >  patternNameToResults 
)
staticprivate

Definition at line 419 of file Recognizer.cpp.

std::map<ObjectPtr, std::vector<VotedPosePtr> > ISM::Recognizer::getVotingCache ( )
inline

Definition at line 96 of file Recognizer.hpp.

int ISM::Recognizer::objectAlreadyInSet ( const ObjectPtr o)
private

Definition at line 232 of file Recognizer.cpp.

const std::vector< RecognitionResultPtr > ISM::Recognizer::recognizePattern ( const ObjectSetPtr objectSet,
const double  filterThreshold = 0.0,
const int  resultsPerPattern = -1,
const std::string  targetPatternName = "" 
)

Find instances of scenes (or scene models) loaded beforehand in a spatial configuration of objects provided to this method. Returns hypotheses on existing scenes as subsets of that configuration that match a model during scene recognition by our hough voting scheme. Hyptheses are rated by confidences being the percentage of objects in the scene we detected in the provided object configuration.

Parameters
objectSetObject configuration in which scenes are tried to be detected.
filterThresholdMinimum confidence that a recognition result must dispose of, to be returned.
resultsPerPatternMaximum number of recognition results for each scene in db loaded beforehand.
patternNamename of pattern which should be recognized.
Returns
Recognition results in decreasing order of confidence.

Definition at line 47 of file Recognizer.cpp.

int ISM::Recognizer::resultAlreadyExisting ( const RecognitionResultPtr res)
private

Definition at line 220 of file Recognizer.cpp.

void ISM::Recognizer::setObjectTypes ( std::set< std::string >  objectTypes)
inline

Definition at line 108 of file Recognizer.hpp.

void ISM::Recognizer::setPatternDefinitions ( ISM::PatternNameToPatternMap  patternDefinitions)
inline

Definition at line 113 of file Recognizer.hpp.

void ISM::Recognizer::setVoteSpecifiersPerObject ( ISM::ObjectTypeToVoteMap  voteSpecifiersPerObject)
inline

Definition at line 103 of file Recognizer.hpp.

void ISM::Recognizer::setVotingSpaceToBeBuffered ( std::string  patternName)
inline

Definition at line 135 of file Recognizer.hpp.

Member Data Documentation

double ISM::Recognizer::bin_size
private

Definition at line 43 of file Recognizer.hpp.

bool ISM::Recognizer::enabledSelfVoteCheck
private

Definition at line 59 of file Recognizer.hpp.

ObjectSetPtr ISM::Recognizer::inputSet
private

Definition at line 40 of file Recognizer.hpp.

std::vector<RecognitionResultPtr> ISM::Recognizer::ismResults
private

Definition at line 64 of file Recognizer.hpp.

double ISM::Recognizer::maxProjectionAngleDeviation
private

Definition at line 44 of file Recognizer.hpp.

const int ISM::Recognizer::mRaterType
private

Definition at line 62 of file Recognizer.hpp.

std::set<std::string> ISM::Recognizer::objectTypes
private

Definition at line 47 of file Recognizer.hpp.

PatternNameToPatternMap ISM::Recognizer::patternDefinitions
private

Definition at line 52 of file Recognizer.hpp.

std::string ISM::Recognizer::patternForVotingSpaceViz
private

Definition at line 68 of file Recognizer.hpp.

TreeHeightToPatternName ISM::Recognizer::patternPerTreeHeight
private

Definition at line 55 of file Recognizer.hpp.

PatternNameToVotedPoses ISM::Recognizer::patternToVotedPoses
private

Definition at line 57 of file Recognizer.hpp.

TableHelperPtr ISM::Recognizer::tableHelper
private

Definition at line 38 of file Recognizer.hpp.

ObjectTypeToVoteMap ISM::Recognizer::voteSpecifiersPerObject
private

Definition at line 50 of file Recognizer.hpp.

std::map<ObjectPtr, std::vector<VotedPosePtr> > ISM::Recognizer::votingCache
private

Definition at line 66 of file Recognizer.hpp.

PatternNameAndVotingSpaceTuple ISM::Recognizer::votingSpaceBuffer
private

Definition at line 70 of file Recognizer.hpp.


The documentation for this class was generated from the following files:


asr_lib_ism
Author(s): Hanselmann Fabian, Heller Florian, Heizmann Heinrich, Kübler Marcel, Mehlhaus Jonas, Meißner Pascal, Qattan Mohamad, Reckling Reno, Stroh Daniel
autogenerated on Wed Jan 8 2020 04:02:41