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 "ColorICP.h"
27#include "ObjectHypothesis.h"
28
29// PCL
30#include <pcl/point_cloud.h>
31#include <pcl/point_types.h>
32
34{
35public:
38
39 // set the scene point clound within which the object will be searched
40 void SetScenePointcloud(const std::vector<CHypothesisPoint*>& aScenePoints);
41
42 float EstimateTransformation(const std::vector<CHypothesisPoint*>& aObjectPoints,
43 const Vec3d center,
44 Mat3d& mRotation,
45 Vec3d& vTranslation,
46 const Vec3d upwardsVector,
47 const int nEffortLevel = OLP_EFFORT_POINTCLOUD_MATCHING,
48 const std::vector<Vec3d>* pPossibleLocationOffsets = NULL,
49 std::vector<CColorICP::CPointXYZRGBI>* pNearestNeighbors = NULL,
50 std::vector<float>* pPointMatchDistances = NULL,
51 const std::vector<CHypothesisPoint*>* pAdditionalPoints = NULL,
52 const float maxAcceptedDistance = FLT_MAX);
53
54 float EstimateTransformation(const CObjectHypothesis* pHypothesis,
55 Mat3d& mRotation,
56 Vec3d& vTranslation,
57 const Vec3d upwardsVector,
58 const int nEffortLevel = OLP_EFFORT_POINTCLOUD_MATCHING,
59 const std::vector<Vec3d>* pPossibleLocations = NULL,
60 std::vector<CColorICP::CPointXYZRGBI>* pNearestNeighbors = NULL,
61 std::vector<float>* pPointMatchDistances = NULL,
62 const float maxAcceptedDistance = FLT_MAX);
63 float EstimateTransformation(const pcl::PointCloud<pcl::PointXYZRGBA>::Ptr objectPointCloud,
64 const Vec3d center,
65 Mat3d& mRotation,
66 Vec3d& vTranslation,
67 const Vec3d upwardsVector,
68 const int nEffortLevel,
69 const std::vector<Vec3d>* pPossibleLocationOffsets = NULL,
70 std::vector<CColorICP::CPointXYZRGBI>* pNearestNeighbors = NULL,
71 std::vector<float>* pPointMatchDistances = NULL);
72
73 // returns true if the hypothesis is matched well at its current position
74 bool
76 float& distance,
77 const int nEffortLevel = OLP_EFFORT_POINTCLOUD_MATCHING);
78
79 static void RotatePoints(std::vector<CColorICP::CPointXYZRGBI>& points, const Mat3d rot);
80
81 static void GetCompleteTransformation(Mat3d rotICP,
82 Vec3d transICP,
83 Mat3d rotShift,
84 Vec3d transShift,
85 Vec3d center,
86 Mat3d& completeRotation,
87 Vec3d& completeTranslation);
88
89 static CColorICP::CPointXYZRGBI ConvertPclToXYZRGBI(pcl::PointXYZRGBA point);
90
91private:
92 CColorICP** m_pColorICPInstances;
93};
#define OLP_EFFORT_POINTCLOUD_MATCHING
void SetScenePointcloud(const std::vector< CHypothesisPoint * > &aScenePoints)
static void GetCompleteTransformation(Mat3d rotICP, Vec3d transICP, Mat3d rotShift, Vec3d transShift, Vec3d center, Mat3d &completeRotation, Vec3d &completeTranslation)
static CColorICP::CPointXYZRGBI ConvertPclToXYZRGBI(pcl::PointXYZRGBA point)
static void RotatePoints(std::vector< CColorICP::CPointXYZRGBI > &points, const Mat3d rot)
float EstimateTransformation(const pcl::PointCloud< pcl::PointXYZRGBA >::Ptr objectPointCloud, const Vec3d center, Mat3d &mRotation, Vec3d &vTranslation, const Vec3d upwardsVector, const int nEffortLevel, const std::vector< Vec3d > *pPossibleLocationOffsets=NULL, std::vector< CColorICP::CPointXYZRGBI > *pNearestNeighbors=NULL, std::vector< float > *pPointMatchDistances=NULL)
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)
bool CheckObjectMatchAtOriginalPosition(const CObjectHypothesis *pHypothesis, float &distance, const int nEffortLevel=OLP_EFFORT_POINTCLOUD_MATCHING)
double distance(const Point &a, const Point &b)
Definition point.hpp:95