ColorICP.cpp
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 #include "ColorICP.h"
26 
27 // IVT
28 #include <DataStructures/KdTree/KdTree.h>
29 #include <Tracking/ICP.h>
30 
31 #include <cmath>
32 
33 
35 
36 
37 
39 {
40  SetParameters();
41  m_pKdTree = new CKdTree();
42 
43  m_nNumScenePoints = 0;
44  m_pValues = new float*[1];
45 }
46 
47 
48 
50 {
51  delete m_pKdTree;
52 
53  for (int i = 0; i < m_nNumScenePoints; i++)
54  {
55  delete[] m_pValues[i];
56  }
57 
58  delete[] m_pValues;
59 }
60 
61 
62 
63 void CColorICP::SetScenePointcloud(std::vector<CColorICP::CPointXYZRGBI> aScenePoints)
64 {
65  // clean up
66  m_aScenePoints.clear();
67 
68  for (int i = 0; i < m_nNumScenePoints; i++)
69  {
70  delete[] m_pValues[i];
71  }
72 
73  delete[] m_pValues;
74  delete m_pKdTree;
75 
76  // copy points
77  const int nSize = aScenePoints.size();
78 
79  for (int i = 0; i < nSize; i++)
80  {
81  m_aScenePoints.push_back(aScenePoints.at(i));
82  }
83 
84  m_pKdTree = new CKdTree(nSize);
85 
86  m_pValues = new float*[nSize];
87  m_nNumScenePoints = nSize;
88 
89  for (int i = 0; i < nSize; i++)
90  {
91  m_pValues[i] = new float[7];
92  m_pValues[i][0] = aScenePoints.at(i).x;
93  m_pValues[i][1] = aScenePoints.at(i).y;
94  m_pValues[i][2] = aScenePoints.at(i).z;
95  m_pValues[i][3] = m_fColorWeight * aScenePoints.at(i).r;
96  m_pValues[i][4] = m_fColorWeight * aScenePoints.at(i).g;
97  m_pValues[i][5] = m_fColorWeight * aScenePoints.at(i).b;
98  m_pValues[i][6] = m_fColorWeight * aScenePoints.at(i).i;
99  }
100 
101  bool bUseIntensity = OLP_EFFORT_POINTCLOUD_MATCHING > 0;
102 
103  if (bUseIntensity)
104  {
105  m_pKdTree->Build(m_pValues, 0, nSize - 1, m_nKdTreeBucketSize, 7, 0);
106  }
107  else
108  {
109  m_pKdTree->Build(m_pValues, 0, nSize - 1, m_nKdTreeBucketSize, 6, 1);
110  }
111 
112 }
113 
114 
115 
116 float CColorICP::SearchObject(const std::vector<CPointXYZRGBI>& aObjectPoints, Mat3d& mRotation, Vec3d& vTranslation, const float fBestDistanceUntilNow)
117 {
118  Math3d::SetMat(mRotation, Math3d::unit_mat);
119  Math3d::SetVec(vTranslation, 0, 0, 0);
120 
121  if (aObjectPoints.size() < 3)
122  {
123  ARMARX_VERBOSE_S << "CColorICP::SearchObject: not enough object points!";
124  return FLT_MAX;
125  }
126 
127  if (m_aScenePoints.size() < 3)
128  {
129  ARMARX_WARNING_S << "CColorICP::SearchObject: not enough scene points!";
130  return FLT_MAX;
131  }
132 
133  float fLastDistance = FLT_MAX;
134  float fDistance = 0, fPointDistance;
135  Vec3d vPoint, vPointTransformed;
136  float* pPointData = new float[7];
137  float* pNearestNeighbor;
138  Vec3d* pPointPositions = new Vec3d[aObjectPoints.size()];
139  Vec3d* pCorrespondingPointPositions = new Vec3d[aObjectPoints.size()];
140  int nNumPointCorrespondences;
141 
142  // iterations of the ICP algorithm
143  for (int n = 0; n < m_nMaxIterations; n++)
144  {
145  fDistance = 0;
146  nNumPointCorrespondences = 0;
147 
148  // find nearest neighbor for each point in XYZRGB space
149  for (size_t i = 0; i < aObjectPoints.size(); i++)
150  {
151  Math3d::SetVec(vPoint, aObjectPoints.at(i).x, aObjectPoints.at(i).y, aObjectPoints.at(i).z);
152  Math3d::MulMatVec(mRotation, vPoint, vTranslation, vPointTransformed);
153 
154  pPointData[0] = vPointTransformed.x;
155  pPointData[1] = vPointTransformed.y;
156  pPointData[2] = vPointTransformed.z;
157  pPointData[3] = m_fColorWeight * aObjectPoints.at(i).r;
158  pPointData[4] = m_fColorWeight * aObjectPoints.at(i).g;
159  pPointData[5] = m_fColorWeight * aObjectPoints.at(i).b;
160  pPointData[6] = m_fColorWeight * aObjectPoints.at(i).i;
161 
162  m_pKdTree->NearestNeighborBBF(pPointData, fPointDistance, pNearestNeighbor);
163  //FindNNBruteForce(pPointData, fPointDistance, pNearestNeighbor);
164 
165  fPointDistance = sqrtf(fPointDistance);
166 
167  // if (i%10==0)
168  // {
169  // ARMARX_WARNING_S << "(%.1f %.1f %.1f %.1f %.1f %.1f) , (%.1f %.1f %.1f %.1f %.1f %.1f) : %.1f\n",
170  // pPointData[0], pPointData[1], pPointData[2], pPointData[3], pPointData[4], pPointData[5],
171  // pNearestNeighbor[0], pNearestNeighbor[1], pNearestNeighbor[2], pNearestNeighbor[3], pNearestNeighbor[4], pNearestNeighbor[5], fPointDistance);
172  // }
173 
174  // if the correspondence is too far away, we ignore it in the estimation of the transformation
175  if (fPointDistance > m_fCutoffDistance)
176  {
177  fDistance += m_fCutoffDistance;
178  }
179  else
180  {
181  fDistance += fPointDistance;
182  Math3d::SetVec(pPointPositions[nNumPointCorrespondences], vPoint);
183  Math3d::SetVec(pCorrespondingPointPositions[nNumPointCorrespondences], pNearestNeighbor[0], pNearestNeighbor[1], pNearestNeighbor[2]);
184  nNumPointCorrespondences++;
185  }
186  }
187 
188  if (nNumPointCorrespondences < 3)
189  {
190  ARMARX_IMPORTANT_S << "CColorICP::SearchObject: less than 3 correspondences found - no transformation determined";
191  return FLT_MAX;
192  }
193 
194  // re-estimate the transformation between the two pointclouds using the correspondences
195  CICP::CalculateOptimalTransformation(pPointPositions, pCorrespondingPointPositions, nNumPointCorrespondences, mRotation, vTranslation);
196 
197 
198  // if the improvement is very small, finish
199 
200  if (0.8f * fDistance < fBestDistanceUntilNow)
201  {
202  // if it seems we might get a new best result, quit only if improvement is very very small
203  if (1.0f - fDistance / fLastDistance < 0.01f * m_fConvergenceDelta)
204  {
205  break;
206  }
207  }
208  else if ((1.0f - fDistance / fLastDistance < m_fConvergenceDelta) || (2 * n > m_nMaxIterations))
209  {
210  // otherwise quit if improvement is below threshold or already many iterations
211  break;
212  }
213  else if ((0.5f * fDistance > fBestDistanceUntilNow) && (3 * n > m_nMaxIterations))
214  {
215  // if we dont seem to get close to the best result, quit earlier
216  break;
217  }
218 
219  fLastDistance = fDistance;
220 
221  //ARMARX_WARNING_S << "%.1f ", fDistance/aObjectPoints.size());
222  }
223 
224  delete[] pPointData;
225  delete[] pPointPositions;
226  delete[] pCorrespondingPointPositions;
227 
228  return fDistance / aObjectPoints.size();
229 }
230 
231 
232 
233 void CColorICP::SetParameters(float fColorWeight, float fCutoffDistance, float fConvergenceDelta, int nMaxIterations, int nKdTreeBucketSize)
234 {
235  m_fColorWeight = fColorWeight;
236  m_fCutoffDistance = fCutoffDistance;
237  m_fConvergenceDelta = fConvergenceDelta;
238  m_nMaxIterations = nMaxIterations;
239  m_nKdTreeBucketSize = nKdTreeBucketSize;
240 }
241 
242 
243 void CColorICP::FindNNBruteForce(const float* pPoint, float& fSquaredDistance, float*& pNeighbor)
244 {
245  float fMinDist = FLT_MAX;
246  float fDist;
247  int nBestIndex = -1;
248 
249  for (int i = 0; i < m_nNumScenePoints; i++)
250  {
251  fDist = 0;
252 
253  for (int j = 0; j < 6; j++)
254  {
255  fDist += (pPoint[j] - m_pValues[i][j]) * (pPoint[j] - m_pValues[i][j]);
256  }
257 
258  if (fDist < fMinDist)
259  {
260  fMinDist = fDist;
261  nBestIndex = i;
262  }
263  }
264 
265  fSquaredDistance = fMinDist;
266  pNeighbor = m_pValues[nBestIndex];
267 }
268 
269 
270 
271 
272 void CColorICP::GetPointMatchDistances(const std::vector<CPointXYZRGBI>& aObjectPoints, std::vector<float>& aPointMatchDistances)
273 {
274  float* pPointData = new float[7];
275  float* pNearestNeighbor;
276  float fDistance;
277 
278  for (size_t i = 0; i < aObjectPoints.size(); i++)
279  {
280  pPointData[0] = aObjectPoints.at(i).x;
281  pPointData[1] = aObjectPoints.at(i).y;
282  pPointData[2] = aObjectPoints.at(i).z;
283  pPointData[3] = m_fColorWeight * aObjectPoints.at(i).r;
284  pPointData[4] = m_fColorWeight * aObjectPoints.at(i).g;
285  pPointData[5] = m_fColorWeight * aObjectPoints.at(i).b;
286  pPointData[6] = m_fColorWeight * aObjectPoints.at(i).i;
287 
288  m_pKdTree->NearestNeighborBBF(pPointData, fDistance, pNearestNeighbor);
289 
290  aPointMatchDistances.push_back(fDistance);
291  }
292 
293  delete[] pPointData;
294 }
295 
296 
297 
298 
299 void CColorICP::GetNearestNeighbors(const std::vector<CPointXYZRGBI>& aObjectPoints, std::vector<CColorICP::CPointXYZRGBI>& aNeighbors, std::vector<float>& aPointMatchDistances)
300 {
301  float* pPointData = new float[7];
302  float* pNearestNeighbor;
303  CColorICP::CPointXYZRGBI pNearestNeighborPoint;
304  float fDistance;
305  const float fColorWeightFactor = 1.0f / m_fColorWeight;
306 
307  for (size_t i = 0; i < aObjectPoints.size(); i++)
308  {
309  pPointData[0] = aObjectPoints.at(i).x;
310  pPointData[1] = aObjectPoints.at(i).y;
311  pPointData[2] = aObjectPoints.at(i).z;
312  pPointData[3] = m_fColorWeight * aObjectPoints.at(i).r;
313  pPointData[4] = m_fColorWeight * aObjectPoints.at(i).g;
314  pPointData[5] = m_fColorWeight * aObjectPoints.at(i).b;
315  pPointData[6] = m_fColorWeight * aObjectPoints.at(i).i;
316 
317  m_pKdTree->NearestNeighborBBF(pPointData, fDistance, pNearestNeighbor);
318 
319  pNearestNeighborPoint.x = pNearestNeighbor[0];
320  pNearestNeighborPoint.y = pNearestNeighbor[1];
321  pNearestNeighborPoint.z = pNearestNeighbor[2];
322  pNearestNeighborPoint.r = fColorWeightFactor * pNearestNeighbor[3];
323  pNearestNeighborPoint.g = fColorWeightFactor * pNearestNeighbor[4];
324  pNearestNeighborPoint.b = fColorWeightFactor * pNearestNeighbor[5];
325  pNearestNeighborPoint.i = fColorWeightFactor * pNearestNeighbor[6];
326 
327  aNeighbors.push_back(pNearestNeighborPoint);
328  aPointMatchDistances.push_back(fDistance);
329  }
330 
331  delete[] pPointData;
332 }
333 
334 
336 {
338  ret.x = pPoint->vPosition.x;
339  ret.y = pPoint->vPosition.y;
340  ret.z = pPoint->vPosition.z;
341  ret.r = pPoint->fColorR;
342  ret.g = pPoint->fColorG;
343  ret.b = pPoint->fColorB;
344  ret.i = pPoint->fIntensity;
345 
346  return ret;
347 }
348 
349 
351 {
352  CHypothesisPoint* pRet = new CHypothesisPoint();
354  Math3d::SetVec(pRet->vPosition, pPoint.x, pPoint.y, pPoint.z);
355  pRet->fColorR = pPoint.r;
356  pRet->fColorG = pPoint.g;
357  pRet->fColorB = pPoint.b;
358  pRet->fIntensity = pPoint.i;
359  pRet->fMembershipProbability = 0.8f;
360  return pRet;
361 }
362 
363 
364 
365 void CColorICP::TransformPointXYZRGBI(CPointXYZRGBI& pPoint, Mat3d mRotation, Vec3d vTranslation)
366 {
367  const float x = pPoint.x;
368  const float y = pPoint.y;
369  const float z = pPoint.z;
370  pPoint.x = mRotation.r1 * x + mRotation.r2 * y + mRotation.r3 * z + vTranslation.x;
371  pPoint.y = mRotation.r4 * x + mRotation.r5 * y + mRotation.r6 * z + vTranslation.y;
372  pPoint.z = mRotation.r7 * x + mRotation.r8 * y + mRotation.r9 * z + vTranslation.z;
373 }
374 
375 
376 
ARMARX_IMPORTANT_S
#define ARMARX_IMPORTANT_S
Definition: Logging.h:203
armarx::aron::ret
ReaderT::InputType T & ret
Definition: rw.h:21
CColorICP::CColorICP
CColorICP()
Definition: ColorICP.cpp:38
CHypothesisPoint::fIntensity
float fIntensity
Definition: ObjectHypothesis.h:241
ColorICP.h
CColorICP::CPointXYZRGBI::x
float x
Definition: ColorICP.h:42
CColorICP::CPointXYZRGBI::y
float y
Definition: ColorICP.h:42
CHypothesisPoint::fColorG
float fColorG
Definition: ObjectHypothesis.h:241
CColorICP::GetPointMatchDistances
void GetPointMatchDistances(const std::vector< CPointXYZRGBI > &aObjectPoints, std::vector< float > &aPointMatchDistances)
Definition: ColorICP.cpp:272
CColorICP::SetScenePointcloud
void SetScenePointcloud(std::vector< CPointXYZRGBI > aScenePoints)
Definition: ColorICP.cpp:63
CColorICP::SetParameters
void SetParameters(float fColorWeight=OLP_ICP_COLOR_DISTANCE_WEIGHT, float fCutoffDistance=FLT_MAX, float fConvergenceDelta=0.01f, int nMaxIterations=30, int nKdTreeBucketSize=50)
Definition: ColorICP.cpp:233
CColorICP::SearchObject
float SearchObject(const std::vector< CPointXYZRGBI > &aObjectPoints, Mat3d &mRotation, Vec3d &vTranslation, const float fBestDistanceUntilNow=FLT_MAX)
Definition: ColorICP.cpp:116
CColorICP::CPointXYZRGBI::g
float g
Definition: ColorICP.h:42
CHypothesisPoint::vPosition
Vec3d vPosition
Definition: ObjectHypothesis.h:238
ObjectLearningByPushingDefinitions.h
CColorICP::CPointXYZRGBI::i
float i
Definition: ColorICP.h:42
CColorICP::CPointXYZRGBI::r
float r
Definition: ColorICP.h:42
CHypothesisPoint
Definition: ObjectHypothesis.h:171
OLP_EFFORT_POINTCLOUD_MATCHING
#define OLP_EFFORT_POINTCLOUD_MATCHING
Definition: ObjectLearningByPushingDefinitions.h:261
GfxTL::Vec3d
VectorXD< 3, double > Vec3d
Definition: VectorXD.h:695
CColorICP::GetNearestNeighbors
void GetNearestNeighbors(const std::vector< CPointXYZRGBI > &aObjectPoints, std::vector< CColorICP::CPointXYZRGBI > &aNeighbors, std::vector< float > &aPointMatchDistances)
Definition: ColorICP.cpp:299
CColorICP::CPointXYZRGBI
Definition: ColorICP.h:40
CColorICP::CPointXYZRGBI::b
float b
Definition: ColorICP.h:42
CColorICP::~CColorICP
~CColorICP()
Definition: ColorICP.cpp:49
CHypothesisPoint::eDepthMapPoint
@ eDepthMapPoint
Definition: ObjectHypothesis.h:235
ARMARX_WARNING_S
#define ARMARX_WARNING_S
Definition: Logging.h:206
CHypothesisPoint::fColorR
float fColorR
Definition: ObjectHypothesis.h:241
CColorICP::ConvertToXYZRGBI
static CPointXYZRGBI ConvertToXYZRGBI(CHypothesisPoint *pPoint)
Definition: ColorICP.cpp:335
CHypothesisPoint::ePointType
EPointType ePointType
Definition: ObjectHypothesis.h:240
CColorICP::CPointXYZRGBI::z
float z
Definition: ColorICP.h:42
ARMARX_VERBOSE_S
#define ARMARX_VERBOSE_S
Definition: Logging.h:200
Logging.h
CHypothesisPoint::fColorB
float fColorB
Definition: ObjectHypothesis.h:241
CHypothesisPoint::fMembershipProbability
float fMembershipProbability
Definition: ObjectHypothesis.h:242
CColorICP::TransformPointXYZRGBI
static void TransformPointXYZRGBI(CPointXYZRGBI &pPoint, Mat3d mRotation, Vec3d vTranslation)
Definition: ColorICP.cpp:365
CColorICP::ConvertFromXYZRGBI
static CHypothesisPoint * ConvertFromXYZRGBI(CPointXYZRGBI pPoint)
Definition: ColorICP.cpp:350