#include <best_path.h>
Public Member Functions | |
BestPath (std::string database_filename) | |
AttributedPointCloud | predictUnfoundPoses (ISM::PosePtr &reference_pose, std::string pattern_name, double percentage_of_records_for_prediction) |
predictUnfoundPoses Processes the following steps for each object in the objectpattern set. More... | |
~BestPath () | |
Public Member Functions inherited from pose_prediction_ism::PredictorWithScore | |
PredictorWithScore (std::string database_filename, std::string name_space, PredictorType predictor_type) | |
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 Types | |
typedef std::map< IsmObject, PathWithScore > | BestPathMap |
Private Member Functions | |
double | calculatePathScore (IsmObjects path) |
void | createAttributedPointCloud (ISM::PosePtr reference_pose_ptr, double percentage_of_records_for_prediction) |
void | createBestPathMap (std::string type, IsmObjects predecessors) |
void | printBestPaths () |
Private Attributes | |
BestPathMap | best_path_map_ |
Additional Inherited Members | |
Protected Types inherited from pose_prediction_ism::PredictorWithScore | |
typedef std::pair< IsmObjects, double > | PathWithScore |
Protected Types inherited from pose_prediction_ism::PosePredictor | |
typedef std::pair< std::string, std::string > | IsmObject |
typedef std::vector< IsmObject > | IsmObjects |
typedef std::set< IsmObject > | IsmObjectSet |
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_ |
UniformDistributionGenerator * | udg_dist_ |
UniformDistributionGenerator * | udg_rot_ |
ISM::PatternToObjectToVoteMap | votes_ |
Definition at line 24 of file best_path.h.
|
private |
Definition at line 32 of file best_path.h.
pose_prediction_ism::BestPath::BestPath | ( | std::string | database_filename | ) |
Definition at line 23 of file best_path.cpp.
pose_prediction_ism::BestPath::~BestPath | ( | ) |
Definition at line 28 of file best_path.cpp.
|
privatevirtual |
Implements pose_prediction_ism::PredictorWithScore.
Definition at line 116 of file best_path.cpp.
|
privatevirtual |
Implements pose_prediction_ism::PosePredictor.
Definition at line 100 of file best_path.cpp.
|
private |
Definition at line 51 of file best_path.cpp.
|
virtual |
predictUnfoundPoses Processes the following steps for each object in the objectpattern set.
reference_pose | |
pattern_name |
Implements pose_prediction_ism::PosePredictor.
Definition at line 32 of file best_path.cpp.
|
private |
Definition at line 125 of file best_path.cpp.
|
private |
Definition at line 35 of file best_path.h.