Public Member Functions | Private Member Functions | Private Attributes | List of all members
pose_prediction_ism::PaperPredictionNormalized Class Reference

#include <old_prediction_normalized.h>

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

Public Member Functions

 PaperPredictionNormalized (std::string dbfileName)
 
AttributedPointCloud predictUnfoundPoses (ISM::PosePtr &referencePose, std::string patternName, double percentage_of_records_for_prediction)
 RecognizerPredictionISM::calcUnfoundPoses Processes the following steps for each object in the objectpattern set. More...
 
 ~PaperPredictionNormalized ()
 
- Public Member Functions inherited from pose_prediction_ism::PosePredictor
void clearPointCloud ()
 
void disableRandom ()
 
void enableRandom (double sphere_radius, double max_projection_angle)
 
AttributedPointCloud getAttributedPointCloud () const
 
std::string getMarkerNameSpace () const
 
PredictorType getPredictorType () const
 
void setFoundObjects (const FoundObjects &value)
 
void setPredictionGenerationFactor (double prediction_generation_factor_)
 
void traverseISM (std::string pattern_name, unsigned int level)
 

Private Member Functions

void calculateRecursiveUnfoundPoses (ISM::PosePtr &referencePose, std::string patternName, unsigned int weight, unsigned int level)
 
void createAttributedPointCloud (ISM::PosePtr reference_pose_ptr, double percentage_of_records_for_prediction)
 
void createAttributedPointCloudFromMap (double numberOfSpecifiers)
 
void nonReferenceObjectProcessing (IsmObject object, ISM::VoteSpecifierPtr specifier, ISM::PosePtr &referencePose, unsigned int weight)
 
bool referenceObjectProcessing (std::string objectType, ISM::VoteSpecifierPtr specifier, ISM::PosePtr &referencePose, unsigned int weight, unsigned int specifiersSize, unsigned int level)
 referenceObjectProcessing Processes a reference object. Processes the following steps. More...
 

Private Attributes

std::map< IsmObject, std::vector< ISM::PosePtr > > objectPoseMap
 
SizeMap objectSizeMap
 

Additional Inherited Members

- Protected Types inherited from pose_prediction_ism::PosePredictor
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 inherited from pose_prediction_ism::PosePredictor
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...
 
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 inherited from pose_prediction_ism::PosePredictor
AttributedPointCloud attributed_point_cloud_
 
double average_votes_ = 0
 
double prediction_generation_factor_ = 1
 
SizeMap specifiers_size_map_
 
UniformDistributionGeneratorudg_dist_
 
UniformDistributionGeneratorudg_rot_
 
ISM::PatternToObjectToVoteMap votes_
 

Detailed Description

Definition at line 22 of file old_prediction_normalized.h.

Constructor & Destructor Documentation

pose_prediction_ism::PaperPredictionNormalized::PaperPredictionNormalized ( std::string  dbfileName)

Definition at line 22 of file old_prediction_normalized.cpp.

pose_prediction_ism::PaperPredictionNormalized::~PaperPredictionNormalized ( )

Definition at line 27 of file old_prediction_normalized.cpp.

Member Function Documentation

void pose_prediction_ism::PaperPredictionNormalized::calculateRecursiveUnfoundPoses ( ISM::PosePtr &  referencePose,
std::string  patternName,
unsigned int  weight,
unsigned int  level 
)
private

Definition at line 115 of file old_prediction_normalized.cpp.

void pose_prediction_ism::PaperPredictionNormalized::createAttributedPointCloud ( ISM::PosePtr  reference_pose_ptr,
double  percentage_of_records_for_prediction 
)
privatevirtual

Implements pose_prediction_ism::PosePredictor.

Definition at line 110 of file old_prediction_normalized.cpp.

void pose_prediction_ism::PaperPredictionNormalized::createAttributedPointCloudFromMap ( double  numberOfSpecifiers)
private

Definition at line 90 of file old_prediction_normalized.cpp.

void pose_prediction_ism::PaperPredictionNormalized::nonReferenceObjectProcessing ( IsmObject  object,
ISM::VoteSpecifierPtr  specifier,
ISM::PosePtr &  referencePose,
unsigned int  weight 
)
private

Definition at line 31 of file old_prediction_normalized.cpp.

AttributedPointCloud pose_prediction_ism::PaperPredictionNormalized::predictUnfoundPoses ( ISM::PosePtr &  referencePose,
std::string  patternName,
double  percentage_of_records_for_prediction 
)
virtual

RecognizerPredictionISM::calcUnfoundPoses 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
referencePose
patternName
weight
depth

Implements pose_prediction_ism::PosePredictor.

Definition at line 44 of file old_prediction_normalized.cpp.

bool pose_prediction_ism::PaperPredictionNormalized::referenceObjectProcessing ( std::string  objectType,
ISM::VoteSpecifierPtr  specifier,
ISM::PosePtr &  referencePose,
unsigned int  weight,
unsigned int  specifiersSize,
unsigned int  level 
)
private

referenceObjectProcessing Processes a reference object. Processes the following steps.

  • Calculate absolute pose of unknown object.
  • Calculate full pose for next call of this function.
  • Check whether this reference object is identical to
    the reference of the ism in which it is object. If this reference object is equal to the reference of the ism in which it resides.
    • Every single vote for a hypotheses in specifier has to be repreated
      for all redundancies in lower parts of the tree.
    • One level higher in the scene model hierarchy, object pose hypotheses
      should be replicated for every vote in specifiers as well as every time
      this function would have been called. Reference object in this ism gets
      reference of next higher ism.
    • If position of this object in scene is equal to pose of reference, then
      it has been chosen as reference and its pose will be equal to the reference
      through all votes. So we do not need to process any other votes here.
    If this reference object is not equal to the reference of the ism in which it resides.
    • One level higher in the scene model hierarchy, object pose hypotheses
      should be replicated for every time this function would have been called.
Parameters
objectTypeThe object type
specifierThe vote specifier
referencePoseThe reference pose of this function call
weightThe weight of this call
specifiersSizeThe size of the specifier container.
Returns
Returns true, if we do not have to process further

Definition at line 57 of file old_prediction_normalized.cpp.

Member Data Documentation

std::map<IsmObject , std::vector<ISM::PosePtr> > pose_prediction_ism::PaperPredictionNormalized::objectPoseMap
private

Definition at line 106 of file old_prediction_normalized.h.

SizeMap pose_prediction_ism::PaperPredictionNormalized::objectSizeMap
private

Definition at line 107 of file old_prediction_normalized.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