recognition_result.cpp
Go to the documentation of this file.
00001 
00021 #include "recognition_result.h"
00022 
00023 namespace descriptor_surface_based_recognition {
00024 
00025 RecognitionResult::RecognitionResult(int view_index, double score_2D, HalconCpp::HHomMat2D &trans_matrix_2D, const Eigen::Vector2i &tex_point)
00026     : 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)),
00027       search_radius_(225), pose_valid_(true) { }
00028 
00029 
00030 bool RecognitionResult::checkModelFound() { return model_found_; }
00031 
00032 void RecognitionResult::setSearchCloud(pcl::PointCloud<pcl::PointXYZ>::Ptr &search_cloud) { this->search_cloud_ = search_cloud; }
00033 
00034 void RecognitionResult::setPose(HalconCpp::HTuple pose) { this->pose_ = pose; }
00035 
00036 void RecognitionResult::setModelFound(bool model_found) { this->model_found_ = model_found; }
00037 
00038 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); }
00039 
00040 void RecognitionResult::setAdjustedRotation(HalconCpp::HQuaternion quaternion) { this->adjusted_rotation_ = quaternion; }
00041 
00042 void RecognitionResult::setScore3D(double score_3D) { this->score_3D_ = score_3D; }
00043 
00044 void RecognitionResult::setSearchRadius(int radius) { this->search_radius_ = radius; }
00045 
00046 void RecognitionResult::setPoseValid(bool pose_valid) { this->pose_valid_ = pose_valid; }
00047 
00048 
00049 HalconCpp::HTuple RecognitionResult::getPose() const { return pose_; }
00050 
00051 double RecognitionResult::getScore2D() const { return score_2D_; }
00052 
00053 double RecognitionResult::getScore3D() const { return score_3D_; }
00054 
00055 int RecognitionResult::getViewIndex() const { return view_index; }
00056 
00057 HalconCpp::HHomMat2D RecognitionResult::getTransMatrix2D() const { return trans_matrix_2D_; }
00058 
00059 Eigen::Vector2i RecognitionResult::getTexPoint() const { return tex_point_; }
00060 
00061 Eigen::Vector3d RecognitionResult::getTexPoint3D() const { return tex_point_3D_; }
00062 
00063 pcl::PointCloud<pcl::PointXYZ>::Ptr RecognitionResult::getSearchCloud() const { return search_cloud_; }
00064 
00065 HalconCpp::HQuaternion RecognitionResult::getAdjustedRotation() const { return adjusted_rotation_; }
00066 
00067 int RecognitionResult::getSearchRadius() const { return search_radius_; }
00068 
00069 bool RecognitionResult::getPoseValid() const { return pose_valid_; }
00070 
00071 }


asr_descriptor_surface_based_recognition
Author(s): Allgeyer Tobias, Hutmacher Robin, Meißner Pascal
autogenerated on Thu Jun 6 2019 17:57:29