PointCloudRegistration.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 "PointCloudRegistration.h"
25 #include "OLPTools.h"
26 
27 // OpenMP
28 #include <omp.h>
29 
30 // system
31 #include <sys/time.h>
32 
33 
35 
36 
37 
38 
40 {
41  // create parallel instances of CColorICP
42  const int nParallelityFactor = omp_get_num_procs();
43  m_pColorICPInstances = new CColorICP*[nParallelityFactor];
44 
45  for (int i = 0; i < nParallelityFactor; i++)
46  {
47  m_pColorICPInstances[i] = new CColorICP();
49  }
50 }
51 
52 
53 
55 {
56  const int nParallelityFactor = omp_get_num_procs();
57 
58  for (int i = 0; i < nParallelityFactor; i++)
59  {
60  delete m_pColorICPInstances[i];
61  }
62 
63  delete m_pColorICPInstances;
64 }
65 
66 
67 
68 // set the point cloud in which the object should be searched
69 void CPointCloudRegistration::SetScenePointcloud(const std::vector<CHypothesisPoint*>& aScenePoints)
70 {
71  // convert points to simple format for ICP
72  std::vector<CColorICP::CPointXYZRGBI> aScenePointsConverted;
73  aScenePointsConverted.resize(aScenePoints.size());
74 
75  for (size_t i = 0; i < aScenePoints.size(); i++)
76  {
77  aScenePointsConverted.at(i) = CColorICP::ConvertToXYZRGBI(aScenePoints.at(i));
78  }
79 
80  // update the parallel instances of CColorICP
81  const int nParallelityFactor = omp_get_num_procs();
82 
83  for (int i = 0; i < nParallelityFactor; i++)
84  {
85  m_pColorICPInstances[i]->SetScenePointcloud(aScenePointsConverted);
86  }
87 }
88 
89 
90 
91 float CPointCloudRegistration::EstimateTransformation(const std::vector<CHypothesisPoint*>& aObjectPoints, const Vec3d center, Mat3d& mRotation, Vec3d& vTranslation, const Vec3d upwardsVector,
92  const int nEffortLevel, const std::vector<Vec3d>* pPossibleLocationOffsets, std::vector<CColorICP::CPointXYZRGBI>* pNearestNeighbors,
93  std::vector<float>* pPointMatchDistances, const std::vector<CHypothesisPoint*>* pAdditionalPoints, const float maxAcceptedDistance)
94 {
95  timeval tStart, tEnd;
96  gettimeofday(&tStart, 0);
97  const int nParallelityFactor = omp_get_num_procs();
98  omp_set_num_threads(nParallelityFactor);
99 
100  // create grid of initial positions around the possible object locations
101  std::vector<Vec3d> aPossibleLocationOffsets;
102  aPossibleLocationOffsets.push_back(center); // original position
103 
104  if (pPossibleLocationOffsets)
105  {
106  for (size_t i = 0; i < pPossibleLocationOffsets->size(); i++)
107  {
108  aPossibleLocationOffsets.push_back(pPossibleLocationOffsets->at(i));
109  }
110  }
111 
112  const int nNumPossibleLocations = aPossibleLocationOffsets.size();
113 
114  ARMARX_VERBOSE_S << "Trying to match object around " << nNumPossibleLocations << " different possible locations";
115 
116  for (size_t i = 0; i < aPossibleLocationOffsets.size(); i++)
117  {
118  //ARMARX_VERBOSE_S << aPossibleLocationOffsets.at(i).x << " " << aPossibleLocationOffsets.at(i).y << " " << aPossibleLocationOffsets.at(i).z;
119  }
120 
121 
122  float fShiftTemp;
123  int nNumSamplesPerDimensionTemp;
124 
125  switch (nEffortLevel)
126  {
127  case 0:
128  case 1:
129  case 2:
130  fShiftTemp = 0;
131  nNumSamplesPerDimensionTemp = 1;
132  break;
133 
134  case 3:
135  fShiftTemp = 100;
136  nNumSamplesPerDimensionTemp = 2;
137  break;
138 
139  case 4:
140  fShiftTemp = 70;
141  nNumSamplesPerDimensionTemp = 3;
142  break;
143 
144  case 5:
145  fShiftTemp = 80;
146  nNumSamplesPerDimensionTemp = 4;
147  break;
148 
149  case 6:
150  fShiftTemp = 70;
151  nNumSamplesPerDimensionTemp = 5;
152  break;
153 
154  default:
155  fShiftTemp = 70;
156  nNumSamplesPerDimensionTemp = 6;
157  break;
158  }
159 
160  bool tryDifferentOrientations = (Math3d::Length(upwardsVector) > 0) && (nEffortLevel >= 2);
161  const int nNumOrientations = tryDifferentOrientations ? 3 : 1;
162  Mat3d baseRotationMatrices[3];
163  Math3d::SetMat(baseRotationMatrices[0], Math3d::unit_mat);
164  Math3d::SetRotationMat(baseRotationMatrices[1], upwardsVector, -20.0 * M_PI / 180.0);
165  Math3d::SetRotationMat(baseRotationMatrices[2], upwardsVector, 20.0 * M_PI / 180.0);
166 
167  const float fShift = fShiftTemp; // unit shift values for the sample points
168  const int nNumSamplesPerDimension = nNumSamplesPerDimensionTemp;
169  const int nNumSamplesPerDimension2 = nNumSamplesPerDimension * nNumSamplesPerDimension;
170  const int nNumSamplesPerDimension3 = nNumSamplesPerDimension * nNumSamplesPerDimension * nNumSamplesPerDimension;
171  const int nNumSamples = nNumOrientations * nNumSamplesPerDimension3 * nNumPossibleLocations;
172  const float fMiddle = 0.5f * (nNumSamplesPerDimension - 1);
173  Vec3d* pShiftVectors = new Vec3d[nNumSamples];
174  Mat3d* rotationMatrices = new Mat3d[nNumSamples];
175 
176  for (int n = 0; n < nNumPossibleLocations; n++)
177  {
178  const Vec3d vLocationOffset = aPossibleLocationOffsets.at(n);
179 
180  for (int i = 0; i < nNumSamplesPerDimension; i++)
181  {
182  for (int j = 0; j < nNumSamplesPerDimension; j++)
183  {
184  for (int k = 0; k < nNumSamplesPerDimension; k++)
185  {
186  for (int l = 0; l < nNumOrientations; l++)
187  {
188  const int nIndex = n * nNumSamplesPerDimension3 * nNumOrientations + i * nNumSamplesPerDimension2 * nNumOrientations
189  + j * nNumSamplesPerDimension * nNumOrientations + k * nNumOrientations + l;
190  pShiftVectors[nIndex].x = vLocationOffset.x + (i - fMiddle) * fShift;
191  pShiftVectors[nIndex].y = vLocationOffset.y + (j - fMiddle) * fShift;
192  pShiftVectors[nIndex].z = vLocationOffset.z + (k - fMiddle) * fShift;
193  Math3d::SetMat(rotationMatrices[nIndex], baseRotationMatrices[l]);
194  }
195  }
196  }
197  }
198  }
199 
200 
201  // downsample object cloud if necessary
202  size_t maxNumPoints = 200 + nEffortLevel * 200;
203  std::vector<CHypothesisPoint*> aObjectPointsDownsampled;
204 
205  if (aObjectPoints.size() > maxNumPoints)
206  {
207  const float ratio = (float)maxNumPoints / (float)aObjectPoints.size();
208  const int randomThreshold = 1000.0f * ratio;
209 
210  for (size_t i = 0; i < aObjectPoints.size(); i++)
211  {
212  if (rand() % 1000 <= randomThreshold)
213  {
214  aObjectPointsDownsampled.push_back(aObjectPoints.at(i));
215  }
216  }
217 
218  ARMARX_VERBOSE_S << "Object pointcloud was downsampled from " << aObjectPoints.size() << " to " << aObjectPointsDownsampled.size() << " points";
219  }
220  else
221  {
222  aObjectPointsDownsampled = aObjectPoints;
223  }
224 
225 
226  // try ICP with different start positions
227 
228  Mat3d mBestRotation = Math3d::unit_mat;
229  Mat3d mSecondBestRotation = Math3d::unit_mat;
230  Vec3d vBestTranslation = {0, 0, 0};
231  Vec3d vSecondBestTranslation = {0, 0, 0};
232  float fBestDistance = FLT_MAX;
233  float fSecondBestDistance = FLT_MAX;
234  std::vector<float> distances;
235  std::vector<Vec3d> positions;
236  int numSamplesAlreadyDone = 0;
237 
238  #pragma omp parallel for schedule(dynamic, 1)
239  for (int k = 0; k < nNumSamples; k++)
240  {
241  const int nThreadNumber = omp_get_thread_num();
242 
243  std::vector<CColorICP::CPointXYZRGBI> objectPointCloudPar;
244  objectPointCloudPar.resize(aObjectPointsDownsampled.size());
245  CColorICP::CPointXYZRGBI vPointPar;
246 
247  for (size_t i = 0; i < aObjectPointsDownsampled.size(); i++)
248  {
249  vPointPar = CColorICP::ConvertToXYZRGBI(aObjectPointsDownsampled.at(i));
250  vPointPar.x -= center.x;
251  vPointPar.y -= center.y;
252  vPointPar.z -= center.z;
253  objectPointCloudPar.at(i) = vPointPar;
254  }
255 
256  if (tryDifferentOrientations)
257  {
258  RotatePoints(objectPointCloudPar, rotationMatrices[k]);
259  }
260 
261  for (size_t i = 0; i < objectPointCloudPar.size(); i++)
262  {
263  objectPointCloudPar.at(i).x += pShiftVectors[k].x;
264  objectPointCloudPar.at(i).y += pShiftVectors[k].y;
265  objectPointCloudPar.at(i).z += pShiftVectors[k].z;
266  }
267 
268  Mat3d newRotation, newRotationGlobal;
269  Vec3d newTranslation, newTranslationGlobal;
270  float fNewObjectDistance = m_pColorICPInstances[nThreadNumber]->SearchObject(objectPointCloudPar, newRotation, newTranslation, std::min(fBestDistance, maxAcceptedDistance));
271 
272  GetCompleteTransformation(newRotation, newTranslation, rotationMatrices[k], pShiftVectors[k], center, newRotationGlobal, newTranslationGlobal);
273 
274  #pragma omp critical
275  {
276  distances.push_back(fNewObjectDistance);
277  positions.push_back(newTranslationGlobal);
278 
279  // if better solution found, save it
280  if (fNewObjectDistance < fBestDistance)
281  {
282  fSecondBestDistance = fBestDistance;
283  Math3d::SetMat(mSecondBestRotation, mBestRotation);
284  Math3d::SetVec(vSecondBestTranslation, vBestTranslation);
285 
286  fBestDistance = fNewObjectDistance;
287  Math3d::SetMat(mBestRotation, newRotationGlobal);
288  Math3d::SetVec(vBestTranslation, newTranslationGlobal);
289  }
290  else if (fNewObjectDistance < fSecondBestDistance)
291  {
292  fSecondBestDistance = fNewObjectDistance;
293  Math3d::SetMat(mSecondBestRotation, newRotationGlobal);
294  Math3d::SetVec(vSecondBestTranslation, newTranslationGlobal);
295  }
296 
297  numSamplesAlreadyDone++;
298 
299  if (numSamplesAlreadyDone % (3 * nNumSamplesPerDimension3) == 0)
300  {
301  ARMARX_VERBOSE_S << (int)((float)numSamplesAlreadyDone * 100 / (float)nNumSamples) << "% done";
302  }
303  }
304  }
305 
306 
307 
308 
309  // apply best found transformation, remove object points that do not match in the new scene, and do one more iteration of ICP
310 
311  Vec3d vRefinementTranslation, vTemp;
312  Mat3d mRefinementRotation;
313 
314 
315  // convert the points belonging to the object
317  std::vector<CColorICP::CPointXYZRGBI> objectPointCloudConverted;
318 
319  for (size_t i = 0; i < aObjectPoints.size(); i++)
320  {
321  Math3d::MulMatVec(mBestRotation, aObjectPoints.at(i)->vPosition, vBestTranslation, vTemp);
322  vPoint.x = vTemp.x;
323  vPoint.y = vTemp.y;
324  vPoint.z = vTemp.z;
325  vPoint.r = aObjectPoints.at(i)->fColorR;
326  vPoint.g = aObjectPoints.at(i)->fColorG;
327  vPoint.b = aObjectPoints.at(i)->fColorB;
328  vPoint.i = aObjectPoints.at(i)->fIntensity;
329  objectPointCloudConverted.push_back(vPoint);
330  }
331 
332  // determine "bad" points
333  std::vector<float> aPointMatchDistances;
334  m_pColorICPInstances[0]->GetPointMatchDistances(objectPointCloudConverted, aPointMatchDistances);
335 
336  // ICP using only the good points
337  objectPointCloudConverted.clear();
338 
339  for (size_t i = 0; i < aObjectPoints.size(); i++)
340  {
341  if (aPointMatchDistances.at(i) < OLP_TOLERANCE_CONCURRENT_MOTION)
342  {
343  Math3d::MulMatVec(mBestRotation, aObjectPoints.at(i)->vPosition, vBestTranslation, vTemp);
344  vPoint.x = vTemp.x;
345  vPoint.y = vTemp.y;
346  vPoint.z = vTemp.z;
347  vPoint.r = aObjectPoints.at(i)->fColorR;
348  vPoint.g = aObjectPoints.at(i)->fColorG;
349  vPoint.b = aObjectPoints.at(i)->fColorB;
350  vPoint.i = aObjectPoints.at(i)->fIntensity;
351  objectPointCloudConverted.push_back(vPoint);
352  }
353  }
354 
355  m_pColorICPInstances[0]->SearchObject(objectPointCloudConverted, mRefinementRotation, vRefinementTranslation, fBestDistance);
356 
357  // save the result
358  // rotation is Rot * initial rotation
359  Mat3d mOldBestRot;
360  Math3d::SetMat(mOldBestRot, mBestRotation);
361  Math3d::MulMatMat(mRefinementRotation, mOldBestRot, mBestRotation);
362  // translation is Rot*shift+trans
363  Vec3d vOldBestTransl;
364  Math3d::SetVec(vOldBestTransl, vBestTranslation);
365  Math3d::MulMatVec(mRefinementRotation, vOldBestTransl, vRefinementTranslation, vBestTranslation);
366 
367 
368 
369  // get the point match distances for the resulting transformation
370  if (pPointMatchDistances && pNearestNeighbors)
371  {
372  Vec3d vTemp;
373  objectPointCloudConverted.clear();
374 
375  for (size_t i = 0; i < aObjectPoints.size(); i++)
376  {
377  Math3d::MulMatVec(mBestRotation, aObjectPoints.at(i)->vPosition, vBestTranslation, vTemp);
378  vPoint.x = vTemp.x;
379  vPoint.y = vTemp.y;
380  vPoint.z = vTemp.z;
381  vPoint.r = aObjectPoints.at(i)->fColorR;
382  vPoint.g = aObjectPoints.at(i)->fColorG;
383  vPoint.b = aObjectPoints.at(i)->fColorB;
384  vPoint.i = aObjectPoints.at(i)->fIntensity;
385  objectPointCloudConverted.push_back(vPoint);
386  }
387 
388  if (pAdditionalPoints)
389  {
390  for (size_t i = 0; i < pAdditionalPoints->size(); i++)
391  {
392  Math3d::MulMatVec(mBestRotation, pAdditionalPoints->at(i)->vPosition, vBestTranslation, vTemp);
393  vPoint.x = vTemp.x;
394  vPoint.y = vTemp.y;
395  vPoint.z = vTemp.z;
396  vPoint.r = pAdditionalPoints->at(i)->fColorR;
397  vPoint.g = pAdditionalPoints->at(i)->fColorG;
398  vPoint.b = pAdditionalPoints->at(i)->fColorB;
399  vPoint.i = pAdditionalPoints->at(i)->fIntensity;
400  objectPointCloudConverted.push_back(vPoint);
401  }
402  }
403 
404  pNearestNeighbors->clear();
405  pPointMatchDistances->clear();
406  m_pColorICPInstances[0]->GetNearestNeighbors(objectPointCloudConverted, *pNearestNeighbors, *pPointMatchDistances);
407  }
408 
409 
410 
411  // set return values
412  Math3d::SetMat(mRotation, mBestRotation);
413  Math3d::SetVec(vTranslation, vBestTranslation);
414 
415 
416  // compare best distance to bad matches
417  std::vector<float> badMatchDistances;
418 
419  for (size_t i = 0; i < distances.size(); i++)
420  {
421  float dist = Math3d::Distance(vBestTranslation, positions.at(i));
422 
423  if (dist > 300)
424  {
425  badMatchDistances.push_back(distances.at(i));
426  }
427  }
428 
429  float averageBadMatchDistance = 0;
430 
431  for (size_t i = 0; i < badMatchDistances.size(); i++)
432  {
433  averageBadMatchDistance += badMatchDistances.at(i);
434  }
435 
436  if (badMatchDistances.size() > 0)
437  {
438  averageBadMatchDistance /= badMatchDistances.size();
439  }
440 
441 
442  ARMARX_VERBOSE_S << "Distance: " << fBestDistance << " average bad match distance: " << averageBadMatchDistance;
443 
444 
445  // clean up
446  delete[] pShiftVectors;
447  delete[] rotationMatrices;
448 
449 
450  gettimeofday(&tEnd, 0);
451  long tTimeDiff = (1000 * tEnd.tv_sec + tEnd.tv_usec / 1000) - (1000 * tStart.tv_sec + tStart.tv_usec / 1000);
452  ARMARX_VERBOSE_S << "Time for pointcloud registration: " << tTimeDiff << " ms";
453 
454 
455  return fBestDistance;
456 }
457 
458 
459 
460 bool CPointCloudRegistration::CheckObjectMatchAtOriginalPosition(const CObjectHypothesis* pHypothesis, float& distance, const int nEffortLevel)
461 {
462  // get the object points
463  std::vector<CHypothesisPoint*> aObjectPoints;
464 
465  for (size_t i = 0; i < pHypothesis->aConfirmedPoints.size(); i++)
466  {
467  aObjectPoints.push_back(pHypothesis->aConfirmedPoints.at(i));
468  }
469 
470  // dont use too many candidate points
471  const size_t nNewPointsLimit = (pHypothesis->aConfirmedPoints.size() > OLP_MIN_NUM_FEATURES) ? 3 * pHypothesis->aConfirmedPoints.size() / 2 : pHypothesis->aNewPoints.size();
472 
473  for (size_t i = 0; i < pHypothesis->aNewPoints.size() && i < nNewPointsLimit; i++)
474  {
475  aObjectPoints.push_back(pHypothesis->aNewPoints.at(i));
476  }
477 
478  // downsample object cloud if necessary
479  size_t maxNumPoints = 200 + nEffortLevel * 200;
480  std::vector<CHypothesisPoint*> aObjectPointsDownsampled;
481 
482  if (aObjectPoints.size() > maxNumPoints)
483  {
484  const float ratio = (float)maxNumPoints / (float)aObjectPoints.size();
485  const int randomThreshold = 1000.0f * ratio;
486 
487  for (size_t i = 0; i < aObjectPoints.size(); i++)
488  {
489  if (rand() % 1000 <= randomThreshold)
490  {
491  aObjectPointsDownsampled.push_back(aObjectPoints.at(i));
492  }
493  }
494 
495  ARMARX_VERBOSE_S << "Object pointcloud was downsampled from " << aObjectPoints.size() << " to " << aObjectPointsDownsampled.size() << " points";
496  }
497  else
498  {
499  aObjectPointsDownsampled = aObjectPoints;
500  }
501 
502  // convert the points belonging to the object
503  std::vector<CColorICP::CPointXYZRGBI> objectPointCloudConverted;
504 
505  for (size_t i = 0; i < aObjectPointsDownsampled.size(); i++)
506  {
507  objectPointCloudConverted.push_back(CColorICP::ConvertToXYZRGBI(aObjectPointsDownsampled.at(i)));
508  }
509 
510  Mat3d mRotation;
511  Vec3d vTranslation;
512  distance = m_pColorICPInstances[0]->SearchObject(objectPointCloudConverted, mRotation, vTranslation);
513 
514 
515  // check if the object seems to have moved
516  Vec3d vObjectCenter = {0, 0, 0};
517 
518  for (size_t i = 0; i < aObjectPointsDownsampled.size(); i++)
519  {
520  Math3d::AddToVec(vObjectCenter, aObjectPointsDownsampled.at(i)->vPosition);
521  }
522 
523  Math3d::MulVecScalar(vObjectCenter, 1.0f / aObjectPointsDownsampled.size(), vObjectCenter);
524  Vec3d vTemp1;
525  Math3d::MulMatVec(mRotation, vObjectCenter, vTranslation, vTemp1);
526  float fTranslationLength = Math3d::Distance(vTemp1, vObjectCenter);
527 
528  // check for rotation
529  float fAngle;
530  Math3d::GetAxisAndAngle(mRotation, vTemp1, fAngle);
531 
532 
533  bool bRet = (fTranslationLength < 0.33f * OLP_MINIMAL_MOTION_MEASURE) && (distance < 0.33f * OLP_TOLERANCE_CONCURRENT_MOTION) && (fAngle < 10 * M_PI / 180);
534 
535  ARMARX_VERBOSE_S << "Check at original position: Translation: " << fTranslationLength << " Rotation: " << 180 * fAngle / M_PI << "deg";
536 
537  return bRet;
538 }
539 
540 
541 /*
542 bool CPointCloudRegistration::EstimateTransformationPCL(const std::vector<CHypothesisPoint*>& aOldPoints, const std::vector<CHypothesisPoint*>& aNewPoints, Mat3d& mRotation, Vec3d& vTranslation)
543 {
544 #ifdef OLP_USE_PCL
545 
546  // copy points to PCL pointclouds
547  pcl::PointCloud<pcl::PointXYZRGBA>::Ptr aOldPointsPCL (new pcl::PointCloud<pcl::PointXYZRGBA>);
548  pcl::PointCloud<pcl::PointXYZRGBA>::Ptr aNewPointsPCL (new pcl::PointCloud<pcl::PointXYZRGBA>);
549 
550  aOldPointsPCL->resize(aOldPoints.size());
551  aNewPointsPCL->resize(aNewPoints.size());
552  for (int i=0; i<(int)aOldPoints.size(); i++)
553  {
554  aOldPointsPCL->points[i].x = aOldPoints.at(i)->vPosition.x/1000; // convert to meters
555  aOldPointsPCL->points[i].y = aOldPoints.at(i)->vPosition.y/1000;
556  aOldPointsPCL->points[i].z = aOldPoints.at(i)->vPosition.z/1000;
557  aOldPointsPCL->points[i].r = (int)(255*aOldPoints.at(i)->fIntensity*aOldPoints.at(i)->fColorR);
558  aOldPointsPCL->points[i].g = (int)(255*aOldPoints.at(i)->fIntensity*aOldPoints.at(i)->fColorG);
559  aOldPointsPCL->points[i].b = (int)(255*aOldPoints.at(i)->fIntensity*aOldPoints.at(i)->fColorB);
560  aOldPointsPCL->points[i].a = 1;
561  }
562  for (int i=0; i<(int)aNewPoints.size(); i++)
563  {
564  aNewPointsPCL->points[i].x = aNewPoints.at(i)->vPosition.x/1000;
565  aNewPointsPCL->points[i].y = aNewPoints.at(i)->vPosition.y/1000;
566  aNewPointsPCL->points[i].z = aNewPoints.at(i)->vPosition.z/1000;
567  aNewPointsPCL->points[i].r = (int)(255*aNewPoints.at(i)->fIntensity*aNewPoints.at(i)->fColorR);
568  aNewPointsPCL->points[i].g = (int)(255*aNewPoints.at(i)->fIntensity*aNewPoints.at(i)->fColorG);
569  aNewPointsPCL->points[i].b = (int)(255*aNewPoints.at(i)->fIntensity*aNewPoints.at(i)->fColorB);
570  aNewPointsPCL->points[i].a = 1;
571  }
572 
573  // i.e. this is an unorganized pointcloud
574  aOldPointsPCL->width = aOldPoints.size();
575  aOldPointsPCL->height = 1;
576  // set to false if points may contain inf or nan values
577  aOldPointsPCL->is_dense = true;
578 
579  // do ICP
580  pcl::IterativeClosestPoint<pcl::PointXYZRGBA, pcl::PointXYZRGBA> icp;
581  icp.setInputCloud(aOldPointsPCL);
582  icp.setInputTarget(aNewPointsPCL);
583  pcl::PointCloud<pcl::PointXYZRGBA> Final;
584  icp.align(Final);
585 
586  bool bSuccess = icp.hasConverged();
587  float fScore = icp.getFitnessScore();
588  Eigen::Matrix4f mTrafo = icp.getFinalTransformation();
589 
590  mRotation.r1 = mTrafo(0,0);
591  mRotation.r2 = mTrafo(0,1);
592  mRotation.r3 = mTrafo(0,2);
593  mRotation.r4 = mTrafo(1,0);
594  mRotation.r5 = mTrafo(1,1);
595  mRotation.r6 = mTrafo(1,2);
596  mRotation.r7 = mTrafo(2,0);
597  mRotation.r8 = mTrafo(2,1);
598  mRotation.r9 = mTrafo(2,2);
599 
600  vTranslation.x = mTrafo(0,3);
601  vTranslation.y = mTrafo(1,3);
602  vTranslation.z = mTrafo(2,3);
603 
604  cout << "Success: " << bSuccess << " Score: " << fScore << " "; // << " Transformation:" << endl << mTrafo << endl;
605 
606  return bSuccess;
607 #else
608  return false;
609 #endif
610 }
611 */
612 
613 
614 float CPointCloudRegistration::EstimateTransformation(const CObjectHypothesis* pHypothesis, Mat3d& mRotation, Vec3d& vTranslation, const Vec3d upwardsVector,
615  const int nEffortLevel, const std::vector<Vec3d>* pPossibleLocations, std::vector<CColorICP::CPointXYZRGBI>* pNearestNeighbors,
616  std::vector<float>* pPointMatchDistances, const float maxAcceptedDistance)
617 {
618 #ifdef OLP_USE_DEPTH_MAP
619 
620  // hypothesis points that will be used for matching
621  std::vector<CHypothesisPoint*> aHypothesisPoints = pHypothesis->aConfirmedPoints;
622 
623 
624  // fill up with candidate points, but dont use too many
625  size_t maxNumPoints = 200 + nEffortLevel * 200;
626  size_t nNewPointsLimit;
627 
628  if (aHypothesisPoints.size() >= maxNumPoints)
629  {
630  nNewPointsLimit = 0;
631  }
632  else
633  {
634  nNewPointsLimit = maxNumPoints - aHypothesisPoints.size();
635 
636  if ((pHypothesis->aConfirmedPoints.size() > OLP_MIN_NUM_FEATURES) && (pHypothesis->aConfirmedPoints.size() < nNewPointsLimit))
637  {
638  nNewPointsLimit = pHypothesis->aConfirmedPoints.size();
639  }
640  }
641 
642  for (size_t i = 0; i < pHypothesis->aNewPoints.size() && i < nNewPointsLimit; i++)
643  {
644  aHypothesisPoints.push_back(pHypothesis->aNewPoints.at(i));
645  }
646 
647 
648  // additional points that will not be used for matching
649  std::vector<CHypothesisPoint*> aAdditionalPoints;
650 
651  for (size_t i = nNewPointsLimit; i < pHypothesis->aNewPoints.size(); i++)
652  {
653  aAdditionalPoints.push_back(pHypothesis->aNewPoints.at(i));
654  }
655 
656  for (size_t i = 0; i < pHypothesis->aDoubtablePoints.size(); i++)
657  {
658  aAdditionalPoints.push_back(pHypothesis->aDoubtablePoints.at(i));
659  }
660 
661 
662  float fDistance = EstimateTransformation(aHypothesisPoints, pHypothesis->vCenter, mRotation, vTranslation, upwardsVector, nEffortLevel,
663  pPossibleLocations, pNearestNeighbors, pPointMatchDistances, &aAdditionalPoints, maxAcceptedDistance);
664 
665  //Vec3d vTemp1, vTemp2;
666  //Math3d::MulMatVec(mRotation, pHypothesis->vCenter, vTemp1);
667  //Math3d::MulVecScalar(vTranslation, 1, vTemp2);
668  //Math3d::AddToVec(vTemp1, vTemp2);
669  //float fDist = Math3d::Distance(vTemp1, pHypothesis->vCenter);
670  //ARMARX_VERBOSE_S << "Translation: (%.1f, %.1f, %.1f), length %.1f mm\n\n", (vTemp1.x-pHypothesis->vCenter.x), (vTemp1.y-pHypothesis->vCenter.y), (vTemp1.z-pHypothesis->vCenter.z), fDist);
671 
672  return fDistance;
673 #else
674  return FLT_MAX;
675 #endif
676 }
677 
678 
679 
680 void CPointCloudRegistration::RotatePoints(std::vector<CColorICP::CPointXYZRGBI>& points, const Mat3d rot)
681 {
682  Vec3d center = {0, 0, 0};
683  // for (size_t i=0; i<points.size(); i++)
684  // {
685  // center.x += points.at(i).x;
686  // center.y += points.at(i).y;
687  // center.z += points.at(i).z;
688  // }
689  // if (points.size()>0)
690  // {
691  // center.x /= points.size();
692  // center.y /= points.size();
693  // center.z /= points.size();
694  // }
695 
696  for (size_t i = 0; i < points.size(); i++)
697  {
698  Vec3d point = {points.at(i).x - center.x, points.at(i).y - center.y, points.at(i).z - center.z};
699  Vec3d pointRot;
700  Math3d::MulMatVec(rot, point, pointRot);
701  points.at(i).x = pointRot.x + center.x;
702  points.at(i).y = pointRot.y + center.y;
703  points.at(i).z = pointRot.z + center.z;
704  }
705 }
706 
707 
708 void CPointCloudRegistration::GetCompleteTransformation(Mat3d rotICP, Vec3d transICP, Mat3d rotShift, Vec3d transShift, Vec3d center, Mat3d& completeRotation, Vec3d& completeTranslation)
709 {
710  Math3d::MulMatMat(rotICP, rotShift, completeRotation);
711 
712  Vec3d temp1, temp2;
713  Math3d::MulMatVec(completeRotation, center, temp1);
714  Math3d::MulMatVec(rotICP, transShift, temp2);
715  Math3d::SubtractVecVec(temp2, temp1, completeTranslation);
716  Math3d::AddToVec(completeTranslation, transICP);
717 }
718 
719 
721 {
723  result.x = point.x;
724  result.y = point.y;
725  result.z = point.z;
726  float intensity = point.r + point.g + point.b + 3;
727  float intensityInverse = 1.0f / intensity;
728  result.r = intensityInverse * (point.r + 1);
729  result.g = intensityInverse * (point.g + 1);
730  result.b = intensityInverse * (point.b + 1);
731  result.i = intensity / (3.0f * 256.0f);
732  return result;
733 }
734 
OLP_ICP_COLOR_DISTANCE_WEIGHT
#define OLP_ICP_COLOR_DISTANCE_WEIGHT
Definition: ObjectLearningByPushingDefinitions.h:238
PointCloudRegistration.h
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
OLP_ICP_CUTOFF_DISTANCE
#define OLP_ICP_CUTOFF_DISTANCE
Definition: ObjectLearningByPushingDefinitions.h:240
CColorICP::CPointXYZRGBI::x
float x
Definition: ColorICP.h:42
CColorICP::CPointXYZRGBI::y
float y
Definition: ColorICP.h:42
CPointCloudRegistration::ConvertPclToXYZRGBI
static CColorICP::CPointXYZRGBI ConvertPclToXYZRGBI(pcl::PointXYZRGBA point)
Definition: PointCloudRegistration.cpp:720
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
CPointCloudRegistration::CPointCloudRegistration
CPointCloudRegistration()
Definition: PointCloudRegistration.cpp:39
CColorICP::CPointXYZRGBI::i
float i
Definition: ColorICP.h:42
CColorICP::CPointXYZRGBI::r
float r
Definition: ColorICP.h:42
OLPTools.h
OLP_MIN_NUM_FEATURES
#define OLP_MIN_NUM_FEATURES
Definition: ObjectLearningByPushingDefinitions.h:109
M_PI
#define M_PI
Definition: MathTools.h:17
OLP_TOLERANCE_CONCURRENT_MOTION
#define OLP_TOLERANCE_CONCURRENT_MOTION
Definition: ObjectLearningByPushingDefinitions.h:224
GfxTL::Vec3d
VectorXD< 3, double > Vec3d
Definition: VectorXD.h:695
CObjectHypothesis::vCenter
Vec3d vCenter
Definition: ObjectHypothesis.h:308
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
CPointCloudRegistration::GetCompleteTransformation
static void GetCompleteTransformation(Mat3d rotICP, Vec3d transICP, Mat3d rotShift, Vec3d transShift, Vec3d center, Mat3d &completeRotation, Vec3d &completeTranslation)
Definition: PointCloudRegistration.cpp:708
CColorICP::CPointXYZRGBI::b
float b
Definition: ColorICP.h:42
CObjectHypothesis
Definition: ObjectHypothesis.h:249
float
#define float
Definition: 16_Level.h:22
CObjectHypothesis::aNewPoints
std::vector< CHypothesisPoint * > aNewPoints
Definition: ObjectHypothesis.h:291
CColorICP::ConvertToXYZRGBI
static CPointXYZRGBI ConvertToXYZRGBI(CHypothesisPoint *pPoint)
Definition: ColorICP.cpp:335
CObjectHypothesis::aDoubtablePoints
std::vector< CHypothesisPoint * > aDoubtablePoints
Definition: ObjectHypothesis.h:293
CPointCloudRegistration::CheckObjectMatchAtOriginalPosition
bool CheckObjectMatchAtOriginalPosition(const CObjectHypothesis *pHypothesis, float &distance, const int nEffortLevel=OLP_EFFORT_POINTCLOUD_MATCHING)
Definition: PointCloudRegistration.cpp:460
CColorICP::CPointXYZRGBI::z
float z
Definition: ColorICP.h:42
CObjectHypothesis::aConfirmedPoints
std::vector< CHypothesisPoint * > aConfirmedPoints
Definition: ObjectHypothesis.h:292
ARMARX_VERBOSE_S
#define ARMARX_VERBOSE_S
Definition: Logging.h:200
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
Logging.h
OLP_MINIMAL_MOTION_MEASURE
#define OLP_MINIMAL_MOTION_MEASURE
Definition: ObjectLearningByPushingDefinitions.h:226
min
T min(T t1, T t2)
Definition: gdiam.h:42
CPointCloudRegistration::SetScenePointcloud
void SetScenePointcloud(const std::vector< CHypothesisPoint * > &aScenePoints)
Definition: PointCloudRegistration.cpp:69