Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | Private Attributes | List of all members
pose_prediction_ism::PosePredictor Class Referenceabstract

#include <pose_predictor.h>

Inheritance diagram for pose_prediction_ism::PosePredictor:
Inheritance graph
[legend]

Public Member Functions

void clearPointCloud ()
 
void disableRandom ()
 
void enableRandom (double sphere_radius, double max_projection_angle)
 
AttributedPointCloud getAttributedPointCloud () const
 
std::string getMarkerNameSpace () const
 
PredictorType getPredictorType () const
 
virtual AttributedPointCloud predictUnfoundPoses (ISM::PosePtr &reference_pose, std::string pattern_name, double percentage_of_records_for_prediction)=0
 predictUnfoundPoses Processes the following steps for each object in the objectpattern set. More...
 
void setFoundObjects (const FoundObjects &value)
 
void setPredictionGenerationFactor (double prediction_generation_factor_)
 
void traverseISM (std::string pattern_name, unsigned int level)
 

Protected Types

typedef std::pair< std::string, std::string > IsmObject
 
typedef std::vector< IsmObjectIsmObjects
 
typedef std::set< IsmObjectIsmObjectSet
 
typedef std::map< IsmObject, unsigned int > SizeMap
 
typedef boost::variate_generator< boost::mt19937, boost::uniform_real<> > UniformDistributionGenerator
 

Protected Member Functions

void addPointToPointCloud (ISM::PosePtr pose_to_add, std::string type, std::string identifier)
 RecognizerPredictionISM::addPointToPointCloud Adds an ISM Pose with object type and identifier as attributed point to the attributed point cloud if the number of hypotheses is higher than the threshold. More...
 
virtual void createAttributedPointCloud (ISM::PosePtr reference_pose_ptr, double percentage_of_records_for_prediction)=0
 
IsmObjectSet getObjectTypesAndIdsBelongingToPattern (std::string type)
 
bool isFoundObject (IsmObject object)
 
bool isPointCloudEmpty ()
 
bool isReferenceObject (IsmObject object)
 
 PosePredictor (std::string database_filename, std::string name_space, PredictorType predictor_type)
 
ISM::PosePtr predictPose (ISM::PosePtr reference_pose_ptr, IsmObjects path_to_object)
 
 ~PosePredictor ()
 

Protected Attributes

AttributedPointCloud attributed_point_cloud_
 
double average_votes_ = 0
 
double prediction_generation_factor_ = 1
 
SizeMap specifiers_size_map_
 
UniformDistributionGeneratorudg_dist_
 
UniformDistributionGeneratorudg_rot_
 
ISM::PatternToObjectToVoteMap votes_
 

Private Attributes

FoundObjects found_objects_
 
double MAX_PROJECTION_ANGLE = 0.0
 
const std::string NAME_SPACE_
 
const PredictorType PREDICTOR_TYPE_
 
double SPHERE_RADIUS = 0.0
 
ISM::TableHelperPtr table_helper_
 
bool USE_RANDOMS = false
 

Detailed Description

Definition at line 46 of file pose_predictor.h.

Member Typedef Documentation

typedef std::pair<std::string, std::string> pose_prediction_ism::PosePredictor::IsmObject
protected

Definition at line 49 of file pose_predictor.h.

Definition at line 50 of file pose_predictor.h.

Definition at line 51 of file pose_predictor.h.

typedef std::map<IsmObject , unsigned int> pose_prediction_ism::PosePredictor::SizeMap
protected

Definition at line 125 of file pose_predictor.h.

typedef boost::variate_generator<boost::mt19937, boost::uniform_real<> > pose_prediction_ism::PosePredictor::UniformDistributionGenerator
protected

Definition at line 126 of file pose_predictor.h.

Constructor & Destructor Documentation

pose_prediction_ism::PosePredictor::PosePredictor ( std::string  database_filename,
std::string  name_space,
PredictorType  predictor_type 
)
protected

Definition at line 23 of file pose_predictor.cpp.

pose_prediction_ism::PosePredictor::~PosePredictor ( )
protected

Destructor.

Definition at line 60 of file pose_predictor.cpp.

Member Function Documentation

void pose_prediction_ism::PosePredictor::addPointToPointCloud ( ISM::PosePtr  pose_to_add,
std::string  type,
std::string  identifier 
)
inlineprotected

RecognizerPredictionISM::addPointToPointCloud Adds an ISM Pose with object type and identifier as attributed point to the attributed point cloud if the number of hypotheses is higher than the threshold.

Parameters
poseToAdd
type
identifier

Definition at line 149 of file pose_predictor.h.

void pose_prediction_ism::PosePredictor::clearPointCloud ( )
inline

Definition at line 87 of file pose_predictor.h.

virtual void pose_prediction_ism::PosePredictor::createAttributedPointCloud ( ISM::PosePtr  reference_pose_ptr,
double  percentage_of_records_for_prediction 
)
protectedpure virtual
void pose_prediction_ism::PosePredictor::disableRandom ( )
inline

Definition at line 116 of file pose_predictor.h.

void pose_prediction_ism::PosePredictor::enableRandom ( double  sphere_radius,
double  max_projection_angle 
)
inline

Definition at line 107 of file pose_predictor.h.

AttributedPointCloud pose_prediction_ism::PosePredictor::getAttributedPointCloud ( ) const

Definition at line 141 of file pose_predictor.cpp.

std::string pose_prediction_ism::PosePredictor::getMarkerNameSpace ( ) const

Definition at line 136 of file pose_predictor.cpp.

IsmObjectSet pose_prediction_ism::PosePredictor::getObjectTypesAndIdsBelongingToPattern ( std::string  type)
inlineprotected

Definition at line 173 of file pose_predictor.h.

PredictorType pose_prediction_ism::PosePredictor::getPredictorType ( ) const

Definition at line 145 of file pose_predictor.cpp.

bool pose_prediction_ism::PosePredictor::isFoundObject ( IsmObject  object)
inlineprotected

Definition at line 153 of file pose_predictor.h.

bool pose_prediction_ism::PosePredictor::isPointCloudEmpty ( )
inlineprotected

Definition at line 163 of file pose_predictor.h.

bool pose_prediction_ism::PosePredictor::isReferenceObject ( IsmObject  object)
inlineprotected

Definition at line 168 of file pose_predictor.h.

ISM::PosePtr pose_prediction_ism::PosePredictor::predictPose ( ISM::PosePtr  reference_pose_ptr,
IsmObjects  path_to_object 
)
protected

Definition at line 77 of file pose_predictor.cpp.

virtual AttributedPointCloud pose_prediction_ism::PosePredictor::predictUnfoundPoses ( ISM::PosePtr &  reference_pose,
std::string  pattern_name,
double  percentage_of_records_for_prediction 
)
pure virtual

predictUnfoundPoses Processes the following steps for each object in the objectpattern set.

  • Look whether we have an unfound object (reference object can never be
    found as they do not exist). Else ignore vote, as we already know itsattributedPoint.pose.
  • If the object was not found
    • Get all votes that fit to combination of this reference
      (to reference and non-reference objects) and unfound object.
    • If we have a reference object
      • search under it for unknown object.
    • If we have a non-reference object
      • we have not found and save its position.
    • Save that we found this object as missing in our currently considered scene hypotheses.
Parameters
reference_pose
pattern_name

Implemented in pose_prediction_ism::PaperPredictionNonNormalized, pose_prediction_ism::PaperPredictionNormalized, pose_prediction_ism::RandomPath, pose_prediction_ism::ShortestPath, and pose_prediction_ism::BestPath.

void pose_prediction_ism::PosePredictor::setFoundObjects ( const FoundObjects value)

Definition at line 130 of file pose_predictor.cpp.

void pose_prediction_ism::PosePredictor::setPredictionGenerationFactor ( double  prediction_generation_factor_)
inline

Definition at line 100 of file pose_predictor.h.

void pose_prediction_ism::PosePredictor::traverseISM ( std::string  pattern_name,
unsigned int  level 
)

Definition at line 64 of file pose_predictor.cpp.

Member Data Documentation

AttributedPointCloud pose_prediction_ism::PosePredictor::attributed_point_cloud_
protected

Definition at line 140 of file pose_predictor.h.

double pose_prediction_ism::PosePredictor::average_votes_ = 0
protected

Definition at line 138 of file pose_predictor.h.

FoundObjects pose_prediction_ism::PosePredictor::found_objects_
private

Definition at line 188 of file pose_predictor.h.

double pose_prediction_ism::PosePredictor::MAX_PROJECTION_ANGLE = 0.0
private

Definition at line 186 of file pose_predictor.h.

const std::string pose_prediction_ism::PosePredictor::NAME_SPACE_
private

Definition at line 182 of file pose_predictor.h.

double pose_prediction_ism::PosePredictor::prediction_generation_factor_ = 1
protected

Definition at line 136 of file pose_predictor.h.

const PredictorType pose_prediction_ism::PosePredictor::PREDICTOR_TYPE_
private

Definition at line 183 of file pose_predictor.h.

SizeMap pose_prediction_ism::PosePredictor::specifiers_size_map_
protected

Definition at line 130 of file pose_predictor.h.

double pose_prediction_ism::PosePredictor::SPHERE_RADIUS = 0.0
private

Definition at line 185 of file pose_predictor.h.

ISM:: TableHelperPtr pose_prediction_ism::PosePredictor::table_helper_
private

Definition at line 187 of file pose_predictor.h.

UniformDistributionGenerator* pose_prediction_ism::PosePredictor::udg_dist_
protected

Definition at line 127 of file pose_predictor.h.

UniformDistributionGenerator* pose_prediction_ism::PosePredictor::udg_rot_
protected

Definition at line 128 of file pose_predictor.h.

bool pose_prediction_ism::PosePredictor::USE_RANDOMS = false
private

Definition at line 184 of file pose_predictor.h.

ISM::PatternToObjectToVoteMap pose_prediction_ism::PosePredictor::votes_
protected

Definition at line 134 of file pose_predictor.h.


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


asr_lib_pose_prediction_ism
Author(s): Heizmann Heinrich, Heller Florian, Meißner Pascal, Stöckle Patrick
autogenerated on Thu Jan 9 2020 07:19:57