Given a point cloud, computes the fit against multiple meshes and chooses the best ones. More...
#include <exhaustive_fit_detector.h>
Public Member Functions | |
void | addModelToExclusionList (int model_id) |
void | clearExclusionList () |
ExhaustiveFitDetector () | |
Just a stub; does not load models. | |
template<class PointCloudType > | |
std::vector< ModelFitInfo > | fitBestModels (const PointCloudType &cloud, int numResults) |
Main fitting function; fits all meshes against cloud and sorts the fits. | |
void | loadDatabaseModels (std::string model_set) |
Loads all the models that are in the model database. | |
void | setNegateExclusions (bool value) |
~ExhaustiveFitDetector () | |
Deletes any loaded models. | |
Private Attributes | |
std::set< int > | model_exclusion_set_ |
Stores a list of model ids which may be in the list of templates, but which we should not look at. | |
bool | negate_exclusions_ |
ros::NodeHandle | nh_ |
Node handle in the roote namespace. | |
ros::NodeHandle | priv_nh_ |
Node handle in the private namespace. | |
std::vector< Fitter * > | templates |
Stores the individual model to cloud fitters, each initialized with a model. |
Given a point cloud, computes the fit against multiple meshes and chooses the best ones.
Is templated on the type of individual fitter to use; the individual fitter must be able to store a mesh or point cloud inside of it, then later compute the fit to an input cloud. The individual fitter is designed to inherit from ModelToCloudFitter, defined inside of model_fitter.h
This class just initializes a whole bunch of individual fitters, then, when given a new cloud, tries to fit all of them. It will then return the fits with the best scores.
Definition at line 64 of file exhaustive_fit_detector.h.
tabletop_object_detector::ExhaustiveFitDetector< Fitter >::ExhaustiveFitDetector | ( | ) | [inline] |
Just a stub; does not load models.
Definition at line 80 of file exhaustive_fit_detector.h.
tabletop_object_detector::ExhaustiveFitDetector< Fitter >::~ExhaustiveFitDetector | ( | ) |
Deletes any loaded models.
Definition at line 141 of file exhaustive_fit_detector.h.
void tabletop_object_detector::ExhaustiveFitDetector< Fitter >::addModelToExclusionList | ( | int | model_id | ) | [inline] |
Definition at line 84 of file exhaustive_fit_detector.h.
void tabletop_object_detector::ExhaustiveFitDetector< Fitter >::clearExclusionList | ( | ) | [inline] |
Definition at line 89 of file exhaustive_fit_detector.h.
std::vector<ModelFitInfo> tabletop_object_detector::ExhaustiveFitDetector< Fitter >::fitBestModels | ( | const PointCloudType & | cloud, |
int | numResults | ||
) | [inline] |
Main fitting function; fits all meshes against cloud and sorts the fits.
Fits the point cloud cloud against all the models in the internal list. It always stores the list with at most numResults best fits, sorted by their score. At the end, it returns this list.
rotate | true if we search for the optimal rotation as well |
Definition at line 109 of file exhaustive_fit_detector.h.
void tabletop_object_detector::ExhaustiveFitDetector< Fitter >::loadDatabaseModels | ( | std::string | model_set | ) |
Loads all the models that are in the model database.
Loads all the models in the Model Database. In order to do that, it asks the database for a list of models, then asks for the path to the geometry file for each model. Then it initializes a IterativeDistanceFitter for each of them, and also sets the database model id correctly for each model so that we later know what model each instance of IterativeDistanceFitter refers to.
WARNING: for the moment, it only uses the database models with the "orthographic" acquisition method. Those models are rotationally symmetric (which is what most fitters operating under this class are capable of handling) plus they do not have "filled insides" which makes them easier to grasp.
Definition at line 160 of file exhaustive_fit_detector.h.
void tabletop_object_detector::ExhaustiveFitDetector< Fitter >::setNegateExclusions | ( | bool | value | ) | [inline] |
Definition at line 94 of file exhaustive_fit_detector.h.
std::set<int> tabletop_object_detector::ExhaustiveFitDetector< Fitter >::model_exclusion_set_ [private] |
Stores a list of model ids which may be in the list of templates, but which we should not look at.
Definition at line 75 of file exhaustive_fit_detector.h.
bool tabletop_object_detector::ExhaustiveFitDetector< Fitter >::negate_exclusions_ [private] |
Definition at line 76 of file exhaustive_fit_detector.h.
ros::NodeHandle tabletop_object_detector::ExhaustiveFitDetector< Fitter >::nh_ [private] |
Node handle in the roote namespace.
Definition at line 70 of file exhaustive_fit_detector.h.
ros::NodeHandle tabletop_object_detector::ExhaustiveFitDetector< Fitter >::priv_nh_ [private] |
Node handle in the private namespace.
Definition at line 68 of file exhaustive_fit_detector.h.
std::vector<Fitter*> tabletop_object_detector::ExhaustiveFitDetector< Fitter >::templates [private] |
Stores the individual model to cloud fitters, each initialized with a model.
Definition at line 72 of file exhaustive_fit_detector.h.