point_cloud_library / 1.12.1 / classpcl_1_1recognition_1_1_obj_rec_r_a_n_s_a_c.html /

This is a RANSAC-based 3D object recognition method. More...

#include <pcl/recognition/ransac_based/obj_rec_ransac.h>

Classes

class HypothesisCreator
class OrientedPointPair
class Output
This is an output item of the ObjRecRANSAC::recognize() method. More...

Public Types

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

Public Member Functions

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. More...
virtual ~ObjRecRANSAC ()
void clear ()
Removes all models from the model library and releases some memory dynamically allocated by this instance. More...
void setMaxCoplanarityAngleDegrees (float max_coplanarity_angle_degrees)
This is a threshold. More...
void setSceneBoundsEnlargementFactor (float value)
void ignoreCoplanarPointPairsOn ()
Default is on. More...
void ignoreCoplanarPointPairsOff ()
Default is on. More...
void icpHypothesesRefinementOn ()
void icpHypothesesRefinementOff ()
bool addModel (const PointCloudIn &points, const PointCloudN &normals, const std::string &object_name, void *user_data=nullptr)
Add an object model to be recognized. More...
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(). More...
void enterTestModeSampleOPP ()
void enterTestModeTestHypotheses ()
void leaveTestMode ()
const std::list< ObjRecRANSAC::OrientedPointPair > & getSampledOrientedPointPairs () const
This function is useful for testing purposes. More...
const std::vector< Hypothesis > & getAcceptedHypotheses () const
This function is useful for testing purposes. More...
void getAcceptedHypotheses (std::vector< Hypothesis > &out) const
This function is useful for testing purposes. More...
const pcl::recognition::ModelLibrary::HashTable & getHashTable () const
Returns the hash table in the model library. More...
const ModelLibrary & getModelLibrary () const
const ModelLibrary::Model * getModel (const std::string &name) const
const ORROctree & getSceneOctree () const
RigidTransformSpace & getRigidTransformSpace ()
float getPairWidth () const

Protected Types

enum Recognition_Mode { SAMPLE_OPP, TEST_HYPOTHESES, FULL_RECOGNITION }

Protected Member Functions

int computeNumberOfIterations (double success_probability) const
void clearTestData ()
void sampleOrientedPointPairs (int num_iterations, const std::vector< ORROctree::Node * > &full_scene_leaves, std::list< OrientedPointPair > &output) 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'. More...
void testHypothesis (Hypothesis *hypothesis, int &match, int &penalty) const
void testHypothesisNormalBased (Hypothesis *hypothesis, float &match) const
void buildGraphOfCloseHypotheses (HypothesisOctree &hypotheses, ORRGraph< Hypothesis > &graph) const
void filterGraphOfCloseHypotheses (ORRGraph< Hypothesis > &graph, std::vector< Hypothesis > &out) const
void buildGraphOfConflictingHypotheses (const BVHH &bvh, ORRGraph< Hypothesis * > &graph) const
void filterGraphOfConflictingHypotheses (ORRGraph< Hypothesis * > &graph, std::list< ObjRecRANSAC::Output > &recognized_objects) 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). More...

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. More...

Protected Attributes

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

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:
  • Chavdar Papazov, Sami Haddadin, Sven Parusel, Kai Krieger and Darius Burschka. Rigid 3D geometry matching for grasping of known objects in cluttered scenes. The International Journal of Robotics Research 2012. DOI: 10.1177/0278364911436019
  • Chavdar Papazov and Darius Burschka. An Efficient RANSAC for 3D Object Recognition in Noisy and Occluded Scenes. In Proceedings of the 10th Asian Conference on Computer Vision (ACCV'10), November 2010.
Author
Chavdar Papazov

Definition at line 83 of file obj_rec_ransac.h.

Member Typedef Documentation

BVHH

Definition at line 89 of file obj_rec_ransac.h.

HypothesisOctree

PointCloudIn

PointCloudN

Member Enumeration Documentation

Recognition_Mode

Enumerator
SAMPLE_OPP
TEST_HYPOTHESES
FULL_RECOGNITION

Definition at line 323 of file obj_rec_ransac.h.

Constructor & Destructor Documentation

ObjRecRANSAC()

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_width should 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_size is 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).

~ObjRecRANSAC()

virtual pcl::recognition::ObjRecRANSAC::~ObjRecRANSAC ( )
inlinevirtual

Definition at line 152 of file obj_rec_ransac.h.

Member Function Documentation

addModel()

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

Add an object model to be recognized.

Parameters
[in] points are the object points.
[in] normals at each point.
[in] object_name is 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_data is 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 227 of file obj_rec_ransac.h.

buildGraphOfCloseHypotheses()

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

buildGraphOfConflictingHypotheses()

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

clear()

void pcl::recognition::ObjRecRANSAC::clear ( )
inline

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

Definition at line 160 of file obj_rec_ransac.h.

clearTestData()

void pcl::recognition::ObjRecRANSAC::clearTestData ( )
inlineprotected

Definition at line 343 of file obj_rec_ransac.h.

compute_oriented_point_pair_signature()

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]
)
inlinestaticprotected

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

Parameters
p1
n1
p2
n2
[out] signature is an array of three doubles saving the three angles in the order shown above.

Definition at line 439 of file obj_rec_ransac.h.

References pcl::recognition::aux::clamp(), pcl::recognition::aux::dot3(), and pcl::recognition::aux::normalize3().

computeNumberOfIterations()

int pcl::recognition::ObjRecRANSAC::computeNumberOfIterations ( double success_probability ) const
inlineprotected

Definition at line 328 of file obj_rec_ransac.h.

computeRigidTransform()

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
inlineprotected

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 386 of file obj_rec_ransac.h.

References pcl::recognition::aux::cross3(), pcl::recognition::aux::diff3(), pcl::recognition::aux::mult3x3(), pcl::recognition::aux::normalize3(), pcl::recognition::aux::projectOnPlane3(), and pcl::recognition::aux::sum3().

enterTestModeSampleOPP()

void pcl::recognition::ObjRecRANSAC::enterTestModeSampleOPP ( )
inline

Definition at line 244 of file obj_rec_ransac.h.

References SAMPLE_OPP.

enterTestModeTestHypotheses()

void pcl::recognition::ObjRecRANSAC::enterTestModeTestHypotheses ( )
inline

Definition at line 250 of file obj_rec_ransac.h.

References TEST_HYPOTHESES.

filterGraphOfCloseHypotheses()

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

filterGraphOfConflictingHypotheses()

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

generateHypotheses()

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

getAcceptedHypotheses() [1/2]

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 272 of file obj_rec_ransac.h.

getAcceptedHypotheses() [2/2]

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 280 of file obj_rec_ransac.h.

getHashTable()

const pcl::recognition::ModelLibrary::HashTable& pcl::recognition::ObjRecRANSAC::getHashTable ( ) const
inline

Returns the hash table in the model library.

Definition at line 287 of file obj_rec_ransac.h.

getModel()

const ModelLibrary::Model* pcl::recognition::ObjRecRANSAC::getModel ( const std::string & name ) const
inline

Definition at line 299 of file obj_rec_ransac.h.

getModelLibrary()

const ModelLibrary& pcl::recognition::ObjRecRANSAC::getModelLibrary ( ) const
inline

Definition at line 293 of file obj_rec_ransac.h.

getPairWidth()

float pcl::recognition::ObjRecRANSAC::getPairWidth ( ) const
inline

Definition at line 317 of file obj_rec_ransac.h.

getRigidTransformSpace()

RigidTransformSpace& pcl::recognition::ObjRecRANSAC::getRigidTransformSpace ( )
inline

Definition at line 311 of file obj_rec_ransac.h.

getSampledOrientedPointPairs()

const std::list<ObjRecRANSAC::OrientedPointPair>& pcl::recognition::ObjRecRANSAC::getSampledOrientedPointPairs ( ) const
inline

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 264 of file obj_rec_ransac.h.

getSceneOctree()

const ORROctree& pcl::recognition::ObjRecRANSAC::getSceneOctree ( ) const
inline

Definition at line 305 of file obj_rec_ransac.h.

groupHypotheses()

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.

icpHypothesesRefinementOff()

void pcl::recognition::ObjRecRANSAC::icpHypothesesRefinementOff ( )
inline

Definition at line 210 of file obj_rec_ransac.h.

icpHypothesesRefinementOn()

void pcl::recognition::ObjRecRANSAC::icpHypothesesRefinementOn ( )
inline

Definition at line 204 of file obj_rec_ransac.h.

ignoreCoplanarPointPairsOff()

void pcl::recognition::ObjRecRANSAC::ignoreCoplanarPointPairsOff ( )
inline

Default is on.

This method calls the corresponding method of the model library.

Definition at line 197 of file obj_rec_ransac.h.

ignoreCoplanarPointPairsOn()

void pcl::recognition::ObjRecRANSAC::ignoreCoplanarPointPairsOn ( )
inline

Default is on.

This method calls the corresponding method of the model library.

Definition at line 189 of file obj_rec_ransac.h.

leaveTestMode()

void pcl::recognition::ObjRecRANSAC::leaveTestMode ( )
inline

Definition at line 256 of file obj_rec_ransac.h.

References FULL_RECOGNITION.

recognize()

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] scene is the 3d scene in which the object should be recognized.
[in] normals are the scene normals.
[out] recognized_objects is 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_probability is the user-defined probability of detecting all objects in the scene.

sampleOrientedPointPairs()

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

setMaxCoplanarityAngleDegrees()

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 175 of file obj_rec_ransac.h.

setSceneBoundsEnlargementFactor()

void pcl::recognition::ObjRecRANSAC::setSceneBoundsEnlargementFactor ( float value )
inline

Definition at line 182 of file obj_rec_ransac.h.

testHypothesis()

void pcl::recognition::ObjRecRANSAC::testHypothesis ( Hypothesis * hypothesis,
int & match,
int & penalty
) const
inlineprotected

testHypothesisNormalBased()

void pcl::recognition::ObjRecRANSAC::testHypothesisNormalBased ( Hypothesis * hypothesis,
float & match
) const
inlineprotected

Friends And Related Function Documentation

ModelLibrary

friend class ModelLibrary
friend

Definition at line 325 of file obj_rec_ransac.h.

Member Data Documentation

abs_zdist_thresh_

float pcl::recognition::ObjRecRANSAC::abs_zdist_thresh_
protected

Definition at line 456 of file obj_rec_ransac.h.

accepted_hypotheses_

std::vector<Hypothesis> pcl::recognition::ObjRecRANSAC::accepted_hypotheses_
protected

Definition at line 475 of file obj_rec_ransac.h.

do_icp_hypotheses_refinement_

bool pcl::recognition::ObjRecRANSAC::do_icp_hypotheses_refinement_
protected

Definition at line 465 of file obj_rec_ransac.h.

frac_of_points_for_icp_refinement_

float pcl::recognition::ObjRecRANSAC::frac_of_points_for_icp_refinement_
protected

Definition at line 464 of file obj_rec_ransac.h.

ignore_coplanar_opps_

bool pcl::recognition::ObjRecRANSAC::ignore_coplanar_opps_
protected

Definition at line 463 of file obj_rec_ransac.h.

intersection_fraction_

float pcl::recognition::ObjRecRANSAC::intersection_fraction_
protected

Definition at line 460 of file obj_rec_ransac.h.

max_coplanarity_angle_

float pcl::recognition::ObjRecRANSAC::max_coplanarity_angle_
protected

Definition at line 461 of file obj_rec_ransac.h.

model_library_

ModelLibrary pcl::recognition::ObjRecRANSAC::model_library_
protected

Definition at line 467 of file obj_rec_ransac.h.

pair_width_

float pcl::recognition::ObjRecRANSAC::pair_width_
protected

Definition at line 452 of file obj_rec_ransac.h.

position_discretization_

float pcl::recognition::ObjRecRANSAC::position_discretization_
protected

Definition at line 454 of file obj_rec_ransac.h.

rec_mode_

Recognition_Mode pcl::recognition::ObjRecRANSAC::rec_mode_
protected

Definition at line 476 of file obj_rec_ransac.h.

relative_num_of_illegal_pts_

float pcl::recognition::ObjRecRANSAC::relative_num_of_illegal_pts_
protected

Definition at line 459 of file obj_rec_ransac.h.

relative_obj_size_

float pcl::recognition::ObjRecRANSAC::relative_obj_size_
protected

Definition at line 457 of file obj_rec_ransac.h.

rotation_discretization_

float pcl::recognition::ObjRecRANSAC::rotation_discretization_
protected

Definition at line 455 of file obj_rec_ransac.h.

sampled_oriented_point_pairs_

std::list<OrientedPointPair> pcl::recognition::ObjRecRANSAC::sampled_oriented_point_pairs_
protected

Definition at line 474 of file obj_rec_ransac.h.

scene_bounds_enlargement_factor_

float pcl::recognition::ObjRecRANSAC::scene_bounds_enlargement_factor_
protected

Definition at line 462 of file obj_rec_ransac.h.

scene_octree_

ORROctree pcl::recognition::ObjRecRANSAC::scene_octree_
protected

Definition at line 468 of file obj_rec_ransac.h.

scene_octree_points_

PointCloudIn::Ptr pcl::recognition::ObjRecRANSAC::scene_octree_points_
protected

Definition at line 472 of file obj_rec_ransac.h.

scene_octree_proj_

ORROctreeZProjection pcl::recognition::ObjRecRANSAC::scene_octree_proj_
protected

Definition at line 469 of file obj_rec_ransac.h.

transform_space_

RigidTransformSpace pcl::recognition::ObjRecRANSAC::transform_space_
protected

Definition at line 470 of file obj_rec_ransac.h.

trimmed_icp_

TrimmedICP<pcl::PointXYZ, float> pcl::recognition::ObjRecRANSAC::trimmed_icp_
protected

Definition at line 471 of file obj_rec_ransac.h.

visibility_

float pcl::recognition::ObjRecRANSAC::visibility_
protected

Definition at line 458 of file obj_rec_ransac.h.

voxel_size_

float pcl::recognition::ObjRecRANSAC::voxel_size_
protected

Definition at line 453 of file obj_rec_ransac.h.


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

© 2009–2012, Willow Garage, Inc.
© 2012–, Open Perception, Inc.
Licensed under the BSD License.
https://pointclouds.org/documentation/classpcl_1_1recognition_1_1_obj_rec_r_a_n_s_a_c.html