Public Member Functions | Private Member Functions | Private Attributes | List of all members
descriptor_surface_based_recognition::PoseRecognition Class Reference

#include <pose_recognition.h>

Public Member Functions

void findPoses ()
 Recognizes the present object instances in the scene. More...
 
HalconCpp::HRegion getInputImageDomain () const
 
ObjectDescriptorgetObjectDescriptor () const
 
std::vector< RecognitionResult * > getResults () const
 
 PoseRecognition (HalconCpp::HImage &scene_image, HalconCpp::HImage &scene_image_mono, pcl::PointCloud< pcl::PointXYZ >::Ptr &point_cloud_with_guppy, ObjectDescriptor *obj_desc, int median_points_offset, double samplingDistance, double keypointFraction, bool eval, int max_instances=1)
 The constructor of this class. More...
 
virtual ~PoseRecognition ()
 The destructor of this class. More...
 

Private Member Functions

void adjustRotation (int result_index)
 Adjusts the rotation of the found object instance depending on its rotation-type. More...
 
bool findModelInCloud (int result_index)
 Recognizes the object in the reduced 3D-scene. More...
 
void findTexture ()
 Recognizes the object in the 2D-scene. More...
 
bool reducePointCloud (int result_index)
 Prepares the 3D-recognition by reducing the point cloud depending on the 2D-recognition result. More...
 

Private Attributes

bool eval_
 
double keypoint_fraction_
 
int max_instances_
 
int median_points_offset_
 
ObjectDescriptorobj_desc_
 
pcl::PointCloud< pcl::PointXYZ >::Ptr point_cloud_with_guppy_
 
std::vector< RecognitionResult * > results_
 
double sampling_distance_
 
HalconCpp::HImage scene_image_
 
HalconCpp::HImage scene_image_mono_
 

Detailed Description

This class is used for the recognition of an object

Definition at line 40 of file pose_recognition.h.

Constructor & Destructor Documentation

descriptor_surface_based_recognition::PoseRecognition::PoseRecognition ( HalconCpp::HImage &  scene_image,
HalconCpp::HImage &  scene_image_mono,
pcl::PointCloud< pcl::PointXYZ >::Ptr &  point_cloud_with_guppy,
ObjectDescriptor obj_desc,
int  median_points_offset,
double  samplingDistance,
double  keypointFraction,
bool  eval,
int  max_instances = 1 
)

The constructor of this class.

Parameters
scene_image
scene_image_mono|
point_cloud_with_guppy|
obj_desc|– see above
median_points_offset|
samplingDistance|
keypointFraction|
max_instances

Definition at line 38 of file pose_recognition.cpp.

descriptor_surface_based_recognition::PoseRecognition::~PoseRecognition ( )
virtual

The destructor of this class.

Definition at line 44 of file pose_recognition.cpp.

Member Function Documentation

void descriptor_surface_based_recognition::PoseRecognition::adjustRotation ( int  result_index)
private

Adjusts the rotation of the found object instance depending on its rotation-type.

Parameters
result_indexThe index of the found instance in the list above

Definition at line 246 of file pose_recognition.cpp.

bool descriptor_surface_based_recognition::PoseRecognition::findModelInCloud ( int  result_index)
private

Recognizes the object in the reduced 3D-scene.

Parameters
result_indexThe index of the found instance in the list above

Definition at line 200 of file pose_recognition.cpp.

void descriptor_surface_based_recognition::PoseRecognition::findPoses ( )

Recognizes the present object instances in the scene.

Definition at line 51 of file pose_recognition.cpp.

void descriptor_surface_based_recognition::PoseRecognition::findTexture ( )
private

Recognizes the object in the 2D-scene.

Definition at line 105 of file pose_recognition.cpp.

HalconCpp::HRegion descriptor_surface_based_recognition::PoseRecognition::getInputImageDomain ( ) const

Definition at line 332 of file pose_recognition.cpp.

ObjectDescriptor * descriptor_surface_based_recognition::PoseRecognition::getObjectDescriptor ( ) const

Definition at line 330 of file pose_recognition.cpp.

std::vector< RecognitionResult * > descriptor_surface_based_recognition::PoseRecognition::getResults ( ) const

Getters for the class members

Definition at line 328 of file pose_recognition.cpp.

bool descriptor_surface_based_recognition::PoseRecognition::reducePointCloud ( int  result_index)
private

Prepares the 3D-recognition by reducing the point cloud depending on the 2D-recognition result.

Parameters
result_indexThe index of the found instance in the list above

Definition at line 136 of file pose_recognition.cpp.

Member Data Documentation

bool descriptor_surface_based_recognition::PoseRecognition::eval_
private

Indicates whether evaluation information are put out

Definition at line 72 of file pose_recognition.h.

double descriptor_surface_based_recognition::PoseRecognition::keypoint_fraction_
private

Fraction of sampled scene points used as key points in the 3D-recognition

Definition at line 66 of file pose_recognition.h.

int descriptor_surface_based_recognition::PoseRecognition::max_instances_
private

The maximum number of instances which can be found

Definition at line 57 of file pose_recognition.h.

int descriptor_surface_based_recognition::PoseRecognition::median_points_offset_
private

The pixel distance used to choose points for the lookup of the 3D point which is used for the reduction of the point cloud

Definition at line 60 of file pose_recognition.h.

ObjectDescriptor* descriptor_surface_based_recognition::PoseRecognition::obj_desc_
private

The descriptor of the object this class can recognize

Definition at line 54 of file pose_recognition.h.

pcl::PointCloud<pcl::PointXYZ>::Ptr descriptor_surface_based_recognition::PoseRecognition::point_cloud_with_guppy_
private

The point cloud of the scene used for the 3D-recognition

Definition at line 51 of file pose_recognition.h.

std::vector<RecognitionResult*> descriptor_surface_based_recognition::PoseRecognition::results_
private

The found object instances

Definition at line 69 of file pose_recognition.h.

double descriptor_surface_based_recognition::PoseRecognition::sampling_distance_
private

Scene sampling distance used for preparation of the scene the object will be recognized with (3D-recognition)

Definition at line 63 of file pose_recognition.h.

HalconCpp::HImage descriptor_surface_based_recognition::PoseRecognition::scene_image_
private

The colored image of the scene used for the 2D-recognition

Definition at line 45 of file pose_recognition.h.

HalconCpp::HImage descriptor_surface_based_recognition::PoseRecognition::scene_image_mono_
private

The greyscale image of the scene used for the 2D-recognition

Definition at line 48 of file pose_recognition.h.


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


asr_descriptor_surface_based_recognition
Author(s): Allgeyer Tobias, Hutmacher Robin, Meißner Pascal
autogenerated on Mon Dec 16 2019 03:31:16