21 #ifndef POSE_RECOGNITION_H 22 #define POSE_RECOGNITION_H 24 #include <HalconCpp.h> 25 #include <pcl/point_cloud.h> 26 #include <pcl/point_types.h> 115 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);
130 std::vector<RecognitionResult*>
getResults()
const;
std::vector< RecognitionResult * > getResults() const
double keypoint_fraction_
HalconCpp::HRegion getInputImageDomain() const
int median_points_offset_
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.
ObjectDescriptor * obj_desc_
bool reducePointCloud(int result_index)
Prepares the 3D-recognition by reducing the point cloud depending on the 2D-recognition result...
pcl::PointCloud< pcl::PointXYZ >::Ptr point_cloud_with_guppy_
std::vector< RecognitionResult * > results_
void findPoses()
Recognizes the present object instances in the scene.
HalconCpp::HImage scene_image_
bool findModelInCloud(int result_index)
Recognizes the object in the reduced 3D-scene.
ObjectDescriptor * getObjectDescriptor() const
HalconCpp::HImage scene_image_mono_
void findTexture()
Recognizes the object in the 2D-scene.
double sampling_distance_
virtual ~PoseRecognition()
The destructor of this class.
void adjustRotation(int result_index)
Adjusts the rotation of the found object instance depending on its rotation-type. ...