21 #ifndef RECOGNITION_RESULT_H 22 #define RECOGNITION_RESULT_H 24 #include <HalconCpp.h> 25 #include <pcl/point_cloud.h> 26 #include <pcl/point_types.h> 75 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
85 RecognitionResult(
int view_index,
double score_2D, HalconCpp::HHomMat2D &trans_matrix_2D,
const Eigen::Vector2i &tex_point);
97 void setSearchCloud(pcl::PointCloud<pcl::PointXYZ>::Ptr &search_cloud);
98 void setPose(HalconCpp::HTuple pose);
109 HalconCpp::HTuple
getPose()
const;
HalconCpp::HHomMat2D trans_matrix_2D_
HalconCpp::HTuple getPose() const
void setTexPoint3D(pcl::PointXYZ tex_point_3D)
int getSearchRadius() const
pcl::PointCloud< pcl::PointXYZ >::Ptr getSearchCloud() const
Eigen::Vector2i getTexPoint() const
void setSearchRadius(int radius)
double getScore3D() const
Eigen::Vector3d tex_point_3D_
HalconCpp::HHomMat2D getTransMatrix2D() const
HalconCpp::HQuaternion getAdjustedRotation() const
bool getPoseValid() const
HalconCpp::HQuaternion adjusted_rotation_
void setSearchCloud(pcl::PointCloud< pcl::PointXYZ >::Ptr &search_cloud)
bool checkModelFound()
Checks whether the model was correctly found.
Eigen::Vector2i tex_point_
void setPoseValid(bool pose_valid)
void setModelFound(bool model_found=true)
void setAdjustedRotation(HalconCpp::HQuaternion quaternion)
pcl::PointCloud< pcl::PointXYZ >::Ptr search_cloud_
EIGEN_MAKE_ALIGNED_OPERATOR_NEW RecognitionResult(int view_index, double score_2D, HalconCpp::HHomMat2D &trans_matrix_2D, const Eigen::Vector2i &tex_point)
The constructor of this class.
double getScore2D() const
void setPose(HalconCpp::HTuple pose)
void setScore3D(double score_3D)
Eigen::Vector3d getTexPoint3D() const