00001 00021 #ifndef POSE_RECOGNITION_H 00022 #define POSE_RECOGNITION_H 00023 00024 #include <HalconCpp.h> 00025 #include <pcl/point_cloud.h> 00026 #include <pcl/point_types.h> 00027 00028 00029 #include "object_descriptor.h" 00030 #include "recognition_result.h" 00031 00032 00033 00034 00035 namespace descriptor_surface_based_recognition { 00036 00040 class PoseRecognition { 00041 00042 private: 00043 00045 HalconCpp::HImage scene_image_; 00046 00048 HalconCpp::HImage scene_image_mono_; 00049 00051 pcl::PointCloud<pcl::PointXYZ>::Ptr point_cloud_with_guppy_; 00052 00054 ObjectDescriptor *obj_desc_; 00055 00057 int max_instances_; 00058 00060 int median_points_offset_; 00061 00063 double sampling_distance_; 00064 00066 double keypoint_fraction_; 00067 00069 std::vector<RecognitionResult*> results_; 00070 00072 bool eval_; 00073 00074 00078 void findTexture(); 00079 00085 bool reducePointCloud(int result_index); 00086 00092 bool findModelInCloud(int result_index); 00093 00099 void adjustRotation(int result_index); 00100 00101 public: 00102 00115 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); 00116 00120 virtual ~PoseRecognition(); 00121 00125 void findPoses(); 00126 00130 std::vector<RecognitionResult*> getResults() const; 00131 ObjectDescriptor* getObjectDescriptor() const; 00132 HalconCpp::HRegion getInputImageDomain() const; 00133 }; 00134 00135 00136 } 00137 00138 #endif