PointCloudRegistration.h
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * Copyright (C) 2011-2016, High Performance Humanoid Technologies (H2T), Karlsruhe Institute of Technology (KIT), all rights reserved.
5  *
6  * ArmarX is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License version 2 as
8  * published by the Free Software Foundation.
9  *
10  * ArmarX is distributed in the hope that it will be useful, but
11  * WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program. If not, see <http://www.gnu.org/licenses/>.
17  *
18  * @package
19  * @author
20  * @date
21  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
22  * GNU General Public License
23  */
24 #pragma once
25 
26 #include "ObjectHypothesis.h"
27 #include "ColorICP.h"
28 
29 // PCL
30 #include <pcl/point_types.h>
31 #include <pcl/point_cloud.h>
32 
33 
35 {
36 public:
37 
40 
41  // set the scene point clound within which the object will be searched
42  void SetScenePointcloud(const std::vector<CHypothesisPoint*>& aScenePoints);
43 
44  float EstimateTransformation(const std::vector<CHypothesisPoint*>& aObjectPoints, const Vec3d center, Mat3d& mRotation, Vec3d& vTranslation, const Vec3d upwardsVector,
45  const int nEffortLevel = OLP_EFFORT_POINTCLOUD_MATCHING, const std::vector<Vec3d>* pPossibleLocationOffsets = NULL,
46  std::vector<CColorICP::CPointXYZRGBI>* pNearestNeighbors = NULL, std::vector<float>* pPointMatchDistances = NULL,
47  const std::vector<CHypothesisPoint*>* pAdditionalPoints = NULL, const float maxAcceptedDistance = FLT_MAX);
48 
49  float EstimateTransformation(const CObjectHypothesis* pHypothesis, Mat3d& mRotation, Vec3d& vTranslation, const Vec3d upwardsVector,
50  const int nEffortLevel = OLP_EFFORT_POINTCLOUD_MATCHING, const std::vector<Vec3d>* pPossibleLocations = NULL,
51  std::vector<CColorICP::CPointXYZRGBI>* pNearestNeighbors = NULL, std::vector<float>* pPointMatchDistances = NULL, const float maxAcceptedDistance = FLT_MAX);
52  float EstimateTransformation(const pcl::PointCloud<pcl::PointXYZRGBA>::Ptr objectPointCloud, const Vec3d center, Mat3d& mRotation, Vec3d& vTranslation, const Vec3d upwardsVector,
53  const int nEffortLevel, const std::vector<Vec3d>* pPossibleLocationOffsets = NULL,
54  std::vector<CColorICP::CPointXYZRGBI>* pNearestNeighbors = NULL, std::vector<float>* pPointMatchDistances = NULL);
55 
56  // returns true if the hypothesis is matched well at its current position
57  bool CheckObjectMatchAtOriginalPosition(const CObjectHypothesis* pHypothesis, float& distance, const int nEffortLevel = OLP_EFFORT_POINTCLOUD_MATCHING);
58 
59  static void RotatePoints(std::vector<CColorICP::CPointXYZRGBI>& points, const Mat3d rot);
60 
61  static void GetCompleteTransformation(Mat3d rotICP, Vec3d transICP, Mat3d rotShift, Vec3d transShift, Vec3d center, Mat3d& completeRotation, Vec3d& completeTranslation);
62 
63  static CColorICP::CPointXYZRGBI ConvertPclToXYZRGBI(pcl::PointXYZRGBA point);
64 
65 private:
66  CColorICP** m_pColorICPInstances;
67 };
68 
69 
CPointCloudRegistration::EstimateTransformation
float EstimateTransformation(const std::vector< CHypothesisPoint * > &aObjectPoints, const Vec3d center, Mat3d &mRotation, Vec3d &vTranslation, const Vec3d upwardsVector, const int nEffortLevel=OLP_EFFORT_POINTCLOUD_MATCHING, const std::vector< Vec3d > *pPossibleLocationOffsets=NULL, std::vector< CColorICP::CPointXYZRGBI > *pNearestNeighbors=NULL, std::vector< float > *pPointMatchDistances=NULL, const std::vector< CHypothesisPoint * > *pAdditionalPoints=NULL, const float maxAcceptedDistance=FLT_MAX)
Definition: PointCloudRegistration.cpp:91
CPointCloudRegistration::RotatePoints
static void RotatePoints(std::vector< CColorICP::CPointXYZRGBI > &points, const Mat3d rot)
Definition: PointCloudRegistration.cpp:680
ObjectHypothesis.h
ColorICP.h
CPointCloudRegistration::ConvertPclToXYZRGBI
static CColorICP::CPointXYZRGBI ConvertPclToXYZRGBI(pcl::PointXYZRGBA point)
Definition: PointCloudRegistration.cpp:720
CPointCloudRegistration::CPointCloudRegistration
CPointCloudRegistration()
Definition: PointCloudRegistration.cpp:39
OLP_EFFORT_POINTCLOUD_MATCHING
#define OLP_EFFORT_POINTCLOUD_MATCHING
Definition: ObjectLearningByPushingDefinitions.h:261
GfxTL::Vec3d
VectorXD< 3, double > Vec3d
Definition: VectorXD.h:695
CPointCloudRegistration
Definition: PointCloudRegistration.h:34
CColorICP::CPointXYZRGBI
Definition: ColorICP.h:40
CPointCloudRegistration::GetCompleteTransformation
static void GetCompleteTransformation(Mat3d rotICP, Vec3d transICP, Mat3d rotShift, Vec3d transShift, Vec3d center, Mat3d &completeRotation, Vec3d &completeTranslation)
Definition: PointCloudRegistration.cpp:708
CObjectHypothesis
Definition: ObjectHypothesis.h:249
CPointCloudRegistration::CheckObjectMatchAtOriginalPosition
bool CheckObjectMatchAtOriginalPosition(const CObjectHypothesis *pHypothesis, float &distance, const int nEffortLevel=OLP_EFFORT_POINTCLOUD_MATCHING)
Definition: PointCloudRegistration.cpp:460
distance
double distance(const Point &a, const Point &b)
Definition: point.hpp:88
CPointCloudRegistration::~CPointCloudRegistration
~CPointCloudRegistration()
Definition: PointCloudRegistration.cpp:54
CColorICP
Definition: ColorICP.h:36
CPointCloudRegistration::SetScenePointcloud
void SetScenePointcloud(const std::vector< CHypothesisPoint * > &aScenePoints)
Definition: PointCloudRegistration.cpp:69