recognition_result.cpp
Go to the documentation of this file.
1 
21 #include "recognition_result.h"
22 
24 
25 RecognitionResult::RecognitionResult(int view_index, double score_2D, HalconCpp::HHomMat2D &trans_matrix_2D, const Eigen::Vector2i &tex_point)
26  : model_found_(false), view_index(view_index), score_2D_(score_2D), trans_matrix_2D_(trans_matrix_2D), tex_point_(tex_point), adjusted_rotation_(HalconCpp::HQuaternion(0, 0, 0, 0)),
27  search_radius_(225), pose_valid_(true) { }
28 
29 
31 
32 void RecognitionResult::setSearchCloud(pcl::PointCloud<pcl::PointXYZ>::Ptr &search_cloud) { this->search_cloud_ = search_cloud; }
33 
34 void RecognitionResult::setPose(HalconCpp::HTuple pose) { this->pose_ = pose; }
35 
36 void RecognitionResult::setModelFound(bool model_found) { this->model_found_ = model_found; }
37 
38 void RecognitionResult::setTexPoint3D(pcl::PointXYZ tex_point_3D) { this->tex_point_3D_ = Eigen::Vector3d(tex_point_3D.x, tex_point_3D.y, tex_point_3D.z); }
39 
40 void RecognitionResult::setAdjustedRotation(HalconCpp::HQuaternion quaternion) { this->adjusted_rotation_ = quaternion; }
41 
42 void RecognitionResult::setScore3D(double score_3D) { this->score_3D_ = score_3D; }
43 
44 void RecognitionResult::setSearchRadius(int radius) { this->search_radius_ = radius; }
45 
46 void RecognitionResult::setPoseValid(bool pose_valid) { this->pose_valid_ = pose_valid; }
47 
48 
49 HalconCpp::HTuple RecognitionResult::getPose() const { return pose_; }
50 
51 double RecognitionResult::getScore2D() const { return score_2D_; }
52 
53 double RecognitionResult::getScore3D() const { return score_3D_; }
54 
56 
57 HalconCpp::HHomMat2D RecognitionResult::getTransMatrix2D() const { return trans_matrix_2D_; }
58 
59 Eigen::Vector2i RecognitionResult::getTexPoint() const { return tex_point_; }
60 
61 Eigen::Vector3d RecognitionResult::getTexPoint3D() const { return tex_point_3D_; }
62 
63 pcl::PointCloud<pcl::PointXYZ>::Ptr RecognitionResult::getSearchCloud() const { return search_cloud_; }
64 
65 HalconCpp::HQuaternion RecognitionResult::getAdjustedRotation() const { return adjusted_rotation_; }
66 
68 
70 
71 }
pcl::PointCloud< pcl::PointXYZ >::Ptr getSearchCloud() const
void setSearchCloud(pcl::PointCloud< pcl::PointXYZ >::Ptr &search_cloud)
bool checkModelFound()
Checks whether the model was correctly found.
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.


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