Classes | Public Types | Public Member Functions | Protected Types | Protected Member Functions | Static Protected Member Functions | Protected Attributes | Friends
pcl::recognition::ObjRecRANSAC Class Reference

This is a RANSAC-based 3D object recognition method. Do the following to use it: (i) call addModel() k times with k different models representing the objects to be recognized and (ii) call recognize() with the 3D scene in which the objects should be recognized. Recognition means both object identification and pose (position + orientation) estimation. Check the method descriptions for more details. More...

#include <obj_rec_ransac.h>

List of all members.

Classes

class  HypothesisCreator
class  OrientedPointPair
class  Output
 This is an output item of the ObjRecRANSAC::recognize() method. It contains the recognized model, its name (the ones passed to ObjRecRANSAC::addModel()), the rigid transform which aligns the model with the input scene and the match confidence which is a number in the interval (0, 1] which gives the fraction of the model surface area matched to the scene. E.g., a match confidence of 0.3 means that 30% of the object surface area was matched to the scene points. If the scene is represented by a single range image, the match confidence can not be greater than 0.5 since the range scanner sees only one side of each object. More...

Public Types

typedef BVH< Hypothesis * > BVHH
typedef SimpleOctree
< Hypothesis,
HypothesisCreator, float > 
HypothesisOctree
typedef ModelLibrary::PointCloudIn PointCloudIn
typedef ModelLibrary::PointCloudN PointCloudN

Public Member Functions

bool addModel (const PointCloudIn &points, const PointCloudN &normals, const std::string &object_name, void *user_data=NULL)
 Add an object model to be recognized.
void clear ()
 Removes all models from the model library and releases some memory dynamically allocated by this instance.
void enterTestModeSampleOPP ()
void enterTestModeTestHypotheses ()
const std::vector< Hypothesis > & getAcceptedHypotheses () const
 This function is useful for testing purposes. It returns the accepted hypotheses generated during the recognition process. Makes sense only if some of the testing modes are active.
void getAcceptedHypotheses (std::vector< Hypothesis > &out) const
 This function is useful for testing purposes. It returns the accepted hypotheses generated during the recognition process. Makes sense only if some of the testing modes are active.
const
pcl::recognition::ModelLibrary::HashTable
getHashTable () const
 Returns the hash table in the model library.
const ModelLibrary::ModelgetModel (const std::string &name) const
const ModelLibrarygetModelLibrary () const
float getPairWidth () const
RigidTransformSpacegetRigidTransformSpace ()
const std::list
< ObjRecRANSAC::OrientedPointPair > & 
getSampledOrientedPointPairs () const
 This function is useful for testing purposes. It returns the oriented point pairs which were sampled from the scene during the recognition process. Makes sense only if some of the testing modes are active.
const ORROctreegetSceneOctree () const
void icpHypothesesRefinementOff ()
void icpHypothesesRefinementOn ()
void ignoreCoplanarPointPairsOff ()
 Default is on. This method calls the corresponding method of the model library.
void ignoreCoplanarPointPairsOn ()
 Default is on. This method calls the corresponding method of the model library.
void leaveTestMode ()
 ObjRecRANSAC (float pair_width, float voxel_size)
 Constructor with some important parameters which can not be changed once an instance of that class is created.
void recognize (const PointCloudIn &scene, const PointCloudN &normals, std::list< ObjRecRANSAC::Output > &recognized_objects, double success_probability=0.99)
 This method performs the recognition of the models loaded to the model library with the method addModel().
void setMaxCoplanarityAngleDegrees (float max_coplanarity_angle_degrees)
 This is a threshold. The larger the value the more point pairs will be considered as co-planar and will be ignored in the off-line model pre-processing and in the online recognition phases. This makes sense only if "ignore co-planar points" is on. Call this method before calling addModel. This method calls the corresponding method of the model library.
void setSceneBoundsEnlargementFactor (float value)
virtual ~ObjRecRANSAC ()

Protected Types

enum  Recognition_Mode { SAMPLE_OPP, TEST_HYPOTHESES, FULL_RECOGNITION }

Protected Member Functions

void buildGraphOfCloseHypotheses (HypothesisOctree &hypotheses, ORRGraph< Hypothesis > &graph) const
void buildGraphOfConflictingHypotheses (const BVHH &bvh, ORRGraph< Hypothesis * > &graph) const
void clearTestData ()
int computeNumberOfIterations (double success_probability) const
void computeRigidTransform (const float *a1, const float *a1_n, const float *b1, const float *b1_n, const float *a2, const float *a2_n, const float *b2, const float *b2_n, float *rigid_transform) const
 Computes the rigid transform that maps the line (a1, b1) to (a2, b2). The computation is based on the corresponding points 'a1' <-> 'a2' and 'b1' <-> 'b2' and the normals 'a1_n', 'b1_n', 'a2_n', and 'b2_n'. The result is saved in 'rigid_transform' which is an array of length 12. The first 9 elements are the rotational part (row major order) and the last 3 are the translation.
void filterGraphOfCloseHypotheses (ORRGraph< Hypothesis > &graph, std::vector< Hypothesis > &out) const
void filterGraphOfConflictingHypotheses (ORRGraph< Hypothesis * > &graph, std::list< ObjRecRANSAC::Output > &recognized_objects) const
int generateHypotheses (const std::list< OrientedPointPair > &pairs, std::list< HypothesisBase > &out) const
int groupHypotheses (std::list< HypothesisBase > &hypotheses, int num_hypotheses, RigidTransformSpace &transform_space, HypothesisOctree &grouped_hypotheses) const
 Groups close hypotheses in 'hypotheses'. Saves a representative for each group in 'out'. Returns the number of hypotheses after grouping.
void sampleOrientedPointPairs (int num_iterations, const std::vector< ORROctree::Node * > &full_scene_leaves, std::list< OrientedPointPair > &output) const
void testHypothesis (Hypothesis *hypothesis, int &match, int &penalty) const
void testHypothesisNormalBased (Hypothesis *hypothesis, float &match) const

Static Protected Member Functions

static void compute_oriented_point_pair_signature (const float *p1, const float *n1, const float *p2, const float *n2, float signature[3])
 Computes the signature of the oriented point pair ((p1, n1), (p2, n2)) consisting of the angles between n1 and (p2-p1), n2 and (p1-p2), n1 and n2.

Protected Attributes

float abs_zdist_thresh_
std::vector< Hypothesisaccepted_hypotheses_
bool do_icp_hypotheses_refinement_
float frac_of_points_for_icp_refinement_
bool ignore_coplanar_opps_
float intersection_fraction_
float max_coplanarity_angle_
ModelLibrary model_library_
float pair_width_
float position_discretization_
Recognition_Mode rec_mode_
float relative_num_of_illegal_pts_
float relative_obj_size_
float rotation_discretization_
std::list< OrientedPointPairsampled_oriented_point_pairs_
float scene_bounds_enlargement_factor_
ORROctree scene_octree_
PointCloudIn::Ptr scene_octree_points_
ORROctreeZProjection scene_octree_proj_
RigidTransformSpace transform_space_
TrimmedICP< pcl::PointXYZ, float > trimmed_icp_
float visibility_
float voxel_size_

Friends

class ModelLibrary

Detailed Description

This is a RANSAC-based 3D object recognition method. Do the following to use it: (i) call addModel() k times with k different models representing the objects to be recognized and (ii) call recognize() with the 3D scene in which the objects should be recognized. Recognition means both object identification and pose (position + orientation) estimation. Check the method descriptions for more details.

Note:
If you use this code in any academic work, please cite:
Author:
Chavdar Papazov

Definition at line 86 of file obj_rec_ransac.h.


Member Typedef Documentation

Definition at line 92 of file obj_rec_ransac.h.

Definition at line 142 of file obj_rec_ransac.h.

Definition at line 89 of file obj_rec_ransac.h.

Definition at line 90 of file obj_rec_ransac.h.


Member Enumeration Documentation

Enumerator:
SAMPLE_OPP 
TEST_HYPOTHESES 
FULL_RECOGNITION 

Definition at line 326 of file obj_rec_ransac.h.


Constructor & Destructor Documentation

pcl::recognition::ObjRecRANSAC::ObjRecRANSAC ( float  pair_width,
float  voxel_size 
)

Constructor with some important parameters which can not be changed once an instance of that class is created.

Parameters:
[in]pair_widthshould be roughly half the extent of the visible object part. This means, for each object point p there should be (at least) one point q (from the same object) such that ||p - q|| <= pair_width. Tradeoff: smaller values allow for detection in more occluded scenes but lead to more imprecise alignment. Bigger values lead to better alignment but require large visible object parts (i.e., less occlusion).
[in]voxel_sizeis the size of the leafs of the octree, i.e., the "size" of the discretization. Tradeoff: High values lead to less computation time but ignore object details. Small values allow to better distinguish between objects, but will introduce more holes in the resulting "voxel-surface" (especially for a sparsely sampled scene).

Definition at line 46 of file obj_rec_ransac.cpp.

virtual pcl::recognition::ObjRecRANSAC::~ObjRecRANSAC ( ) [inline, virtual]

Definition at line 155 of file obj_rec_ransac.h.


Member Function Documentation

bool pcl::recognition::ObjRecRANSAC::addModel ( const PointCloudIn points,
const PointCloudN normals,
const std::string object_name,
void *  user_data = NULL 
) [inline]

Add an object model to be recognized.

Parameters:
[in]pointsare the object points.
[in]normalsat each point.
[in]object_nameis an identifier for the object. If that object is detected in the scene 'object_name' is returned by the recognition method and you know which object has been detected. Note that 'object_name' has to be unique!
[in]user_datais a pointer to some data (can be NULL)

The method returns true if the model was successfully added to the model library and false otherwise (e.g., if 'object_name' is already in use).

Definition at line 230 of file obj_rec_ransac.h.

void pcl::recognition::ObjRecRANSAC::buildGraphOfCloseHypotheses ( HypothesisOctree hypotheses,
ORRGraph< Hypothesis > &  graph 
) const [protected]

Definition at line 416 of file obj_rec_ransac.cpp.

void pcl::recognition::ObjRecRANSAC::buildGraphOfConflictingHypotheses ( const BVHH bvh,
ORRGraph< Hypothesis * > &  graph 
) const [protected]

Definition at line 475 of file obj_rec_ransac.cpp.

Removes all models from the model library and releases some memory dynamically allocated by this instance.

Definition at line 163 of file obj_rec_ransac.h.

void pcl::recognition::ObjRecRANSAC::clearTestData ( ) [inline, protected]

Definition at line 346 of file obj_rec_ransac.h.

static void pcl::recognition::ObjRecRANSAC::compute_oriented_point_pair_signature ( const float *  p1,
const float *  n1,
const float *  p2,
const float *  n2,
float  signature[3] 
) [inline, static, protected]

Computes the signature of the oriented point pair ((p1, n1), (p2, n2)) consisting of the angles between n1 and (p2-p1), n2 and (p1-p2), n1 and n2.

Parameters:
[out]signatureis an array of three doubles saving the three angles in the order shown above.

Definition at line 442 of file obj_rec_ransac.h.

int pcl::recognition::ObjRecRANSAC::computeNumberOfIterations ( double  success_probability) const [inline, protected]

Definition at line 331 of file obj_rec_ransac.h.

void pcl::recognition::ObjRecRANSAC::computeRigidTransform ( const float *  a1,
const float *  a1_n,
const float *  b1,
const float *  b1_n,
const float *  a2,
const float *  a2_n,
const float *  b2,
const float *  b2_n,
float *  rigid_transform 
) const [inline, protected]

Computes the rigid transform that maps the line (a1, b1) to (a2, b2). The computation is based on the corresponding points 'a1' <-> 'a2' and 'b1' <-> 'b2' and the normals 'a1_n', 'b1_n', 'a2_n', and 'b2_n'. The result is saved in 'rigid_transform' which is an array of length 12. The first 9 elements are the rotational part (row major order) and the last 3 are the translation.

Definition at line 389 of file obj_rec_ransac.h.

Definition at line 247 of file obj_rec_ransac.h.

Definition at line 253 of file obj_rec_ransac.h.

void pcl::recognition::ObjRecRANSAC::filterGraphOfCloseHypotheses ( ORRGraph< Hypothesis > &  graph,
std::vector< Hypothesis > &  out 
) const [protected]

Definition at line 454 of file obj_rec_ransac.cpp.

void pcl::recognition::ObjRecRANSAC::filterGraphOfConflictingHypotheses ( ORRGraph< Hypothesis * > &  graph,
std::list< ObjRecRANSAC::Output > &  recognized_objects 
) const [protected]

Definition at line 573 of file obj_rec_ransac.cpp.

int pcl::recognition::ObjRecRANSAC::generateHypotheses ( const std::list< OrientedPointPair > &  pairs,
std::list< HypothesisBase > &  out 
) const [protected]

Definition at line 239 of file obj_rec_ransac.cpp.

const std::vector<Hypothesis>& pcl::recognition::ObjRecRANSAC::getAcceptedHypotheses ( ) const [inline]

This function is useful for testing purposes. It returns the accepted hypotheses generated during the recognition process. Makes sense only if some of the testing modes are active.

Definition at line 275 of file obj_rec_ransac.h.

void pcl::recognition::ObjRecRANSAC::getAcceptedHypotheses ( std::vector< Hypothesis > &  out) const [inline]

This function is useful for testing purposes. It returns the accepted hypotheses generated during the recognition process. Makes sense only if some of the testing modes are active.

Definition at line 283 of file obj_rec_ransac.h.

Returns the hash table in the model library.

Definition at line 290 of file obj_rec_ransac.h.

Definition at line 302 of file obj_rec_ransac.h.

Definition at line 296 of file obj_rec_ransac.h.

Definition at line 320 of file obj_rec_ransac.h.

Definition at line 314 of file obj_rec_ransac.h.

This function is useful for testing purposes. It returns the oriented point pairs which were sampled from the scene during the recognition process. Makes sense only if some of the testing modes are active.

Definition at line 267 of file obj_rec_ransac.h.

Definition at line 308 of file obj_rec_ransac.h.

int pcl::recognition::ObjRecRANSAC::groupHypotheses ( std::list< HypothesisBase > &  hypotheses,
int  num_hypotheses,
RigidTransformSpace transform_space,
HypothesisOctree grouped_hypotheses 
) const [protected]

Groups close hypotheses in 'hypotheses'. Saves a representative for each group in 'out'. Returns the number of hypotheses after grouping.

Definition at line 301 of file obj_rec_ransac.cpp.

Definition at line 213 of file obj_rec_ransac.h.

Definition at line 207 of file obj_rec_ransac.h.

Default is on. This method calls the corresponding method of the model library.

Definition at line 200 of file obj_rec_ransac.h.

Default is on. This method calls the corresponding method of the model library.

Definition at line 192 of file obj_rec_ransac.h.

Definition at line 259 of file obj_rec_ransac.h.

void pcl::recognition::ObjRecRANSAC::recognize ( const PointCloudIn scene,
const PointCloudN normals,
std::list< ObjRecRANSAC::Output > &  recognized_objects,
double  success_probability = 0.99 
)

This method performs the recognition of the models loaded to the model library with the method addModel().

Parameters:
[in]sceneis the 3d scene in which the object should be recognized.
[in]normalsare the scene normals.
[out]recognized_objectsis the list of output items each one containing the recognized model instance, its name, the aligning rigid transform and the match confidence (see ObjRecRANSAC::Output for further explanations).
[in]success_probabilityis the user-defined probability of detecting all objects in the scene.

Definition at line 69 of file obj_rec_ransac.cpp.

void pcl::recognition::ObjRecRANSAC::sampleOrientedPointPairs ( int  num_iterations,
const std::vector< ORROctree::Node * > &  full_scene_leaves,
std::list< OrientedPointPair > &  output 
) const [protected]

Definition at line 165 of file obj_rec_ransac.cpp.

void pcl::recognition::ObjRecRANSAC::setMaxCoplanarityAngleDegrees ( float  max_coplanarity_angle_degrees) [inline]

This is a threshold. The larger the value the more point pairs will be considered as co-planar and will be ignored in the off-line model pre-processing and in the online recognition phases. This makes sense only if "ignore co-planar points" is on. Call this method before calling addModel. This method calls the corresponding method of the model library.

Definition at line 178 of file obj_rec_ransac.h.

Definition at line 185 of file obj_rec_ransac.h.

void pcl::recognition::ObjRecRANSAC::testHypothesis ( Hypothesis hypothesis,
int &  match,
int &  penalty 
) const [inline, protected]

Definition at line 617 of file obj_rec_ransac.cpp.

void pcl::recognition::ObjRecRANSAC::testHypothesisNormalBased ( Hypothesis hypothesis,
float &  match 
) const [inline, protected]

Definition at line 656 of file obj_rec_ransac.cpp.


Friends And Related Function Documentation

friend class ModelLibrary [friend]

Definition at line 328 of file obj_rec_ransac.h.


Member Data Documentation

Definition at line 459 of file obj_rec_ransac.h.

Definition at line 478 of file obj_rec_ransac.h.

Definition at line 468 of file obj_rec_ransac.h.

Definition at line 467 of file obj_rec_ransac.h.

Definition at line 466 of file obj_rec_ransac.h.

Definition at line 463 of file obj_rec_ransac.h.

Definition at line 464 of file obj_rec_ransac.h.

Definition at line 470 of file obj_rec_ransac.h.

Definition at line 455 of file obj_rec_ransac.h.

Definition at line 457 of file obj_rec_ransac.h.

Definition at line 479 of file obj_rec_ransac.h.

Definition at line 462 of file obj_rec_ransac.h.

Definition at line 460 of file obj_rec_ransac.h.

Definition at line 458 of file obj_rec_ransac.h.

Definition at line 477 of file obj_rec_ransac.h.

Definition at line 465 of file obj_rec_ransac.h.

Definition at line 471 of file obj_rec_ransac.h.

Definition at line 475 of file obj_rec_ransac.h.

Definition at line 472 of file obj_rec_ransac.h.

Definition at line 473 of file obj_rec_ransac.h.

Definition at line 474 of file obj_rec_ransac.h.

Definition at line 461 of file obj_rec_ransac.h.

Definition at line 456 of file obj_rec_ransac.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:44:35