00001 00021 #ifndef RECOGNITION_RESULT_H 00022 #define RECOGNITION_RESULT_H 00023 00024 #include <HalconCpp.h> 00025 #include <pcl/point_cloud.h> 00026 #include <pcl/point_types.h> 00027 00028 00029 namespace descriptor_surface_based_recognition { 00030 00034 class RecognitionResult { 00035 00036 private: 00038 bool model_found_; 00039 00041 int view_index; 00042 00044 double score_2D_; 00045 00047 HalconCpp::HHomMat2D trans_matrix_2D_; 00048 00050 Eigen::Vector2i tex_point_; 00051 00053 HalconCpp::HQuaternion adjusted_rotation_; 00054 00056 int search_radius_; 00057 00059 bool pose_valid_; 00060 00062 double score_3D_; 00063 00065 Eigen::Vector3d tex_point_3D_; 00066 00068 pcl::PointCloud<pcl::PointXYZ>::Ptr search_cloud_; 00069 00071 HalconCpp::HTuple pose_; 00072 00073 public: 00075 EIGEN_MAKE_ALIGNED_OPERATOR_NEW 00076 00085 RecognitionResult(int view_index, double score_2D, HalconCpp::HHomMat2D &trans_matrix_2D, const Eigen::Vector2i &tex_point); 00086 00092 bool checkModelFound(); 00093 00097 void setSearchCloud(pcl::PointCloud<pcl::PointXYZ>::Ptr &search_cloud); 00098 void setPose(HalconCpp::HTuple pose); 00099 void setModelFound(bool model_found = true); 00100 void setTexPoint3D(pcl::PointXYZ tex_point_3D); 00101 void setAdjustedRotation(HalconCpp::HQuaternion quaternion); 00102 void setScore3D(double score_3D); 00103 void setSearchRadius(int radius); 00104 void setPoseValid(bool pose_valid); 00105 00109 HalconCpp::HTuple getPose() const; 00110 int getViewIndex() const; 00111 double getScore2D() const; 00112 double getScore3D() const; 00113 HalconCpp::HHomMat2D getTransMatrix2D() const; 00114 Eigen::Vector2i getTexPoint() const; 00115 Eigen::Vector3d getTexPoint3D() const; 00116 pcl::PointCloud<pcl::PointXYZ>::Ptr getSearchCloud() const; 00117 HalconCpp::HQuaternion getAdjustedRotation() const; 00118 int getSearchRadius() const; 00119 bool getPoseValid() const; 00120 00121 }; 00122 00123 00124 } 00125 00126 #endif