SegmentedPointCloudFusion.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  */
25 #include "ColorICP.h"
26 #include "OLPTools.h"
27 
28 #include <omp.h>
29 
30 // system
31 #include <sys/time.h>
32 
34 
35 
37 {
38  void FusePointClouds(std::vector<CObjectHypothesis*> aHypotheses, CObjectHypothesis*& pFusedHypothesis)
39  {
40  Transformation3d tTrafo;
41  tTrafo.rotation = Math3d::unit_mat;
42  tTrafo.translation = Math3d::zero_vec;
43  std::vector<Transformation3d> aTransformations;
44  aTransformations.resize(aHypotheses.size());
45 
46  for (size_t i = 0; i < aTransformations.size(); i++)
47  {
48  aTransformations.at(i) = tTrafo;
49  }
50 
51  FusePointClouds(aHypotheses, aTransformations, pFusedHypothesis);
52  }
53 
54 
55  void FusePointClouds(std::vector<CObjectHypothesis*> aHypotheses, std::vector<Transformation3d> aEstimatedTransformations, CObjectHypothesis*& pFusedHypothesis)
56  {
57  std::vector<std::vector<CHypothesisPoint*> > aPointClouds;
58  aPointClouds.resize(aHypotheses.size());
59 
60  for (size_t i = 0; i < aHypotheses.size(); i++)
61  {
62  aPointClouds.at(i).resize(aHypotheses.at(i)->aConfirmedPoints.size());
63 
64  for (size_t j = 0; j < aHypotheses.at(i)->aConfirmedPoints.size(); j++)
65  {
66  aPointClouds.at(i).at(j) = aHypotheses.at(i)->aConfirmedPoints.at(j);
67  }
68  }
69 
70  FusePointClouds(aPointClouds, aEstimatedTransformations, pFusedHypothesis);
71  }
72 
73 
74  void FusePointClouds(std::vector<std::vector<CHypothesisPoint*> > aHypothesisPoints, CObjectHypothesis*& pFusedHypothesis)
75  {
76  Transformation3d tTrafo;
77  tTrafo.rotation = Math3d::unit_mat;
78  tTrafo.translation = Math3d::zero_vec;
79  std::vector<Transformation3d> aTransformations;
80  aTransformations.resize(aHypothesisPoints.size());
81 
82  for (size_t i = 0; i < aTransformations.size(); i++)
83  {
84  aTransformations.at(i) = tTrafo;
85  }
86 
87  FusePointClouds(aHypothesisPoints, aTransformations, pFusedHypothesis);
88  }
89 
90  // this one does the real work
91  void FusePointClouds(std::vector<std::vector<CHypothesisPoint*> > aHypothesisPoints, std::vector<Transformation3d> aEstimatedTransformations, CObjectHypothesis*& pFusedHypothesis)
92  {
93  bool bPairwiseFusion = true;
94 
95  if (aHypothesisPoints.size() < 2)
96  {
97  ARMARX_WARNING_S << "FusePointClouds: At least two point clouds required!";
98  return;
99  }
100 
101  timeval tStart, tEnd;
102  gettimeofday(&tStart, 0);
103 
104  // transform points with estimated transformations
105  Transformation3d tAccumulatedTransform, tInverseTransform;
106  tAccumulatedTransform.rotation = Math3d::unit_mat;
107  tAccumulatedTransform.translation = Math3d::zero_vec;
108 
109  for (size_t i = 0; i < aHypothesisPoints.size() - 1; i++)
110  {
111  Math3d::MulMatMat(aEstimatedTransformations.at(i).rotation, tAccumulatedTransform.rotation, tAccumulatedTransform.rotation);
112  Math3d::MulMatVec(aEstimatedTransformations.at(i).rotation, tAccumulatedTransform.translation, aEstimatedTransformations.at(i).translation, tAccumulatedTransform.translation);
113  Math3d::Transpose(tAccumulatedTransform.rotation, tInverseTransform.rotation);
114  Math3d::MulMatVec(tInverseTransform.rotation, tAccumulatedTransform.translation, tInverseTransform.translation);
115  Math3d::MulVecScalar(tInverseTransform.translation, -1, tInverseTransform.translation);
116 
117  for (size_t j = 0; j < aHypothesisPoints.at(i).size(); j++)
118  {
119  Math3d::MulMatVec(tInverseTransform.rotation, aHypothesisPoints.at(i).at(j)->vPosition, tInverseTransform.translation, aHypothesisPoints.at(i).at(j)->vPosition);
120  }
121  }
122 
123  // convert the points to simple format for ICP
124  std::vector<std::vector<CColorICP::CPointXYZRGBI> > aPointClouds;
125  aPointClouds.resize(aHypothesisPoints.size());
126 
127  for (size_t i = 0; i < aHypothesisPoints.size(); i++)
128  {
129  aPointClouds.at(i).resize(aHypothesisPoints.at(i).size());
130 
131  for (size_t j = 0; j < aHypothesisPoints.at(i).size(); j++)
132  {
133  aPointClouds.at(i).at(j) = CColorICP::ConvertToXYZRGBI(aHypothesisPoints.at(i).at(j));
134  }
135  }
136 
137  // different orientations
138  const int nNumDifferentInitializations = 7;
139  std::vector<Mat3d> aRotations;
140  aRotations.resize(nNumDifferentInitializations);
141  const float fAngle = M_PI / 6.0f;
142  Math3d::SetMat(aRotations.at(0), Math3d::unit_mat);
143  Math3d::SetRotationMatX(aRotations.at(1), fAngle);
144  Math3d::SetRotationMatX(aRotations.at(2), -fAngle);
145  Math3d::SetRotationMatY(aRotations.at(3), fAngle);
146  Math3d::SetRotationMatY(aRotations.at(4), -fAngle);
147  Math3d::SetRotationMatZ(aRotations.at(5), fAngle);
148  Math3d::SetRotationMatZ(aRotations.at(6), -fAngle);
149 
150 
151 
152  // create parallel ICP instances
153  const int nParallelityFactor = omp_get_num_procs();
154  omp_set_num_threads(nParallelityFactor);
155  CColorICP** pColorICPInstances = new CColorICP*[nParallelityFactor];
156 
157  for (int i = 0; i < nParallelityFactor; i++)
158  {
159  pColorICPInstances[i] = new CColorICP();
161  }
162 
163 
164  int nFusionResultIndex = -1;
165 
166  ARMARX_VERBOSE_S << "Fusing " << aPointClouds.size() << " segmentations";
167 
168  if (bPairwiseFusion)
169  {
170  nFusionResultIndex = 0;
171  std::vector<Transformation3d> aPairwiseTransformations;
172  aPairwiseTransformations.resize(aPointClouds.size() - 1);
173  std::vector<float> aMinDistances;
174  aMinDistances.resize(aPointClouds.size() - 1);
175 
176  for (size_t i = 0; i < aPointClouds.size() - 1; i++)
177  {
178  aPairwiseTransformations.at(i).rotation = Math3d::unit_mat;
179  aPairwiseTransformations.at(i).translation = Math3d::zero_vec;
180  aMinDistances.at(i) = FLT_MAX;
181  }
182 
183 
184  // determine the best transformation, starting from different initial transformations
185  #pragma omp parallel for schedule(static, 1)
186  for (int k = 0; k < nNumDifferentInitializations * ((int)aPointClouds.size() - 1); k++)
187  {
188  const int n = k / nNumDifferentInitializations;
189  const int i = k % nNumDifferentInitializations;
190  const int nThreadNumber = omp_get_thread_num();
191 
192  // set second point cloud as scene point cloud (because it is probably bigger than the one before)
193  pColorICPInstances[nThreadNumber]->SetScenePointcloud(aPointClouds.at(n + 1));
194 
195  // rotate points
196  std::vector<CColorICP::CPointXYZRGBI> aRotatedPointCloud;
197  aRotatedPointCloud.resize(aPointClouds.at(n).size());
198 
199  for (size_t j = 0; j < aPointClouds.at(n).size(); j++)
200  {
201  aRotatedPointCloud.at(j) = aPointClouds.at(n).at(j);
202  CColorICP::TransformPointXYZRGBI(aRotatedPointCloud.at(j), aRotations.at(i), Math3d::zero_vec);
203  }
204 
205  Mat3d mRotation;
206  Vec3d vTranslation;
207  float fDist = pColorICPInstances[nThreadNumber]->SearchObject(aRotatedPointCloud, mRotation, vTranslation);
208 
209  #pragma omp critical
210  if (fDist < aMinDistances.at(n))
211  {
212  Math3d::MulMatMat(mRotation, aRotations.at(i), aPairwiseTransformations.at(n).rotation);
213  Math3d::SetVec(aPairwiseTransformations.at(n).translation, vTranslation);
214  aMinDistances.at(n) = fDist;
215  }
216  }
217 
218  // combine all transformed point clouds
219  int nOverallNumberOfPoints = 0;
220  int nIndexOffset = aPointClouds.at(0).size();
221 
222  for (size_t i = 0; i < aPointClouds.size(); i++)
223  {
224  nOverallNumberOfPoints += aPointClouds.at(i).size();
225  }
226 
227  aPointClouds.at(nFusionResultIndex).resize(nOverallNumberOfPoints);
228  tAccumulatedTransform.rotation = Math3d::unit_mat;
229  tAccumulatedTransform.translation = Math3d::zero_vec;
230 
231  for (size_t i = 0; i < aPointClouds.size() - 1; i++)
232  {
233  Math3d::MulMatMat(aPairwiseTransformations.at(i).rotation, tAccumulatedTransform.rotation, tAccumulatedTransform.rotation);
234  Math3d::MulMatVec(aPairwiseTransformations.at(i).rotation, tAccumulatedTransform.translation, aPairwiseTransformations.at(i).translation, tAccumulatedTransform.translation);
235  Math3d::Transpose(tAccumulatedTransform.rotation, tInverseTransform.rotation);
236  Math3d::MulMatVec(tInverseTransform.rotation, tAccumulatedTransform.translation, tInverseTransform.translation);
237  Math3d::MulVecScalar(tInverseTransform.translation, -1, tInverseTransform.translation);
238 
239  #pragma omp parallel for schedule(static, 100)
240  for (size_t j = 0; j < aPointClouds.at(i + 1).size(); j++)
241  {
242  CColorICP::TransformPointXYZRGBI(aPointClouds.at(i + 1).at(j), tInverseTransform.rotation, tInverseTransform.translation);
243  aPointClouds.at(nFusionResultIndex).at(nIndexOffset + j) = aPointClouds.at(i + 1).at(j);
244  }
245 
246  if (i > 0)
247  {
248  nIndexOffset += aPointClouds.at(i).size();
249  }
250  }
251 
252  }
253  else
254  {
255  const int nStartIndex = aHypothesisPoints.size() / 2;
256  nFusionResultIndex = nStartIndex;
257  int nLowIndex = nStartIndex - 1;
258  int nHighIndex = nStartIndex + 1;
259 
260  // match and add earlier and later segmentations alternately
261  while (nLowIndex >= 0 || nHighIndex < (int)aHypothesisPoints.size())
262  {
263  // update fused point cloud into ICP after adding both an earlier and later segmentation
264  for (int i = 0; i < nParallelityFactor; i++)
265  {
266  pColorICPInstances[i]->SetScenePointcloud(aPointClouds.at(nStartIndex));
267  }
268 
269  // match the next earlier segmentation
270  if (nLowIndex >= 0)
271  {
272  Mat3d mBestRotation = Math3d::unit_mat;
273  Vec3d vBestTranslation = Math3d::zero_vec;
274  float fMinDist = FLT_MAX;
275 
276  #pragma omp parallel for schedule(static, 1)
277  for (int i = 0; i < nNumDifferentInitializations; i++)
278  {
279  const int nThreadNumber = omp_get_thread_num();
280 
281  // rotate points
282  std::vector<CColorICP::CPointXYZRGBI> aRotatedPointCloud;
283  aRotatedPointCloud.resize(aPointClouds.at(nLowIndex).size());
284 
285  for (size_t j = 0; j < aPointClouds.at(nLowIndex).size(); j++)
286  {
287  aRotatedPointCloud.at(j) = aPointClouds.at(nLowIndex).at(j);
288  CColorICP::TransformPointXYZRGBI(aRotatedPointCloud.at(j), aRotations.at(i), Math3d::zero_vec);
289  }
290 
291  Mat3d mRotation;
292  Vec3d vTranslation;
293  float fDist = pColorICPInstances[nThreadNumber]->SearchObject(aRotatedPointCloud, mRotation, vTranslation);
294 
295  #pragma omp critical
296  if (fDist < fMinDist)
297  {
298  Math3d::MulMatMat(mRotation, aRotations.at(i), mBestRotation);
299  Math3d::SetVec(vBestTranslation, vTranslation);
300  fMinDist = fDist;
301  }
302  }
303 
304  ARMARX_VERBOSE_S << "Index " << nLowIndex << ": dist " << fMinDist;
305 
306  for (size_t i = 0; i < aPointClouds.at(nLowIndex).size(); i++)
307  {
308  CColorICP::TransformPointXYZRGBI(aPointClouds.at(nLowIndex).at(i), mBestRotation, vBestTranslation);
309  aPointClouds.at(nStartIndex).push_back(aPointClouds.at(nLowIndex).at(i));
310  }
311 
312  nLowIndex--;
313  }
314 
315  // match the next later segmentation
316  if (nHighIndex < (int)aHypothesisPoints.size())
317  {
318  Mat3d mBestRotation = Math3d::unit_mat;
319  Vec3d vBestTranslation = Math3d::zero_vec;
320  float fMinDist = FLT_MAX;
321 
322  #pragma omp parallel for schedule(static, 1)
323  for (int i = 0; i < nNumDifferentInitializations; i++)
324  {
325  const int nThreadNumber = omp_get_thread_num();
326 
327  // rotate points
328  std::vector<CColorICP::CPointXYZRGBI> aRotatedPointCloud;
329  aRotatedPointCloud.resize(aPointClouds.at(nHighIndex).size());
330 
331  for (size_t j = 0; j < aPointClouds.at(nHighIndex).size(); j++)
332  {
333  aRotatedPointCloud.at(j) = aPointClouds.at(nHighIndex).at(j);
334  CColorICP::TransformPointXYZRGBI(aRotatedPointCloud.at(j), aRotations.at(i), Math3d::zero_vec);
335  }
336 
337  Mat3d mRotation;
338  Vec3d vTranslation;
339  float fDist = pColorICPInstances[nThreadNumber]->SearchObject(aRotatedPointCloud, mRotation, vTranslation);
340 
341  #pragma omp critical
342  if (fDist < fMinDist)
343  {
344  Math3d::MulMatMat(mRotation, aRotations.at(i), mBestRotation);
345  Math3d::SetVec(vBestTranslation, vTranslation);
346  fMinDist = fDist;
347  }
348  }
349 
350  ARMARX_VERBOSE_S << "Index " << nHighIndex << ": dist" << fMinDist;
351 
352  for (size_t i = 0; i < aPointClouds.at(nHighIndex).size(); i++)
353  {
354  CColorICP::TransformPointXYZRGBI(aPointClouds.at(nHighIndex).at(i), mBestRotation, vBestTranslation);
355  aPointClouds.at(nStartIndex).push_back(aPointClouds.at(nHighIndex).at(i));
356  }
357 
358  nHighIndex++;
359  }
360  }
361  }
362 
363  ARMARX_VERBOSE_S << "Done";
364 
365 
366  // return result
367  if (!pFusedHypothesis)
368  {
369  pFusedHypothesis = new CObjectHypothesis();
370  }
371 
372  pFusedHypothesis->eType = CObjectHypothesis::eRGBD;
373  pFusedHypothesis->aConfirmedPoints.clear();
374  pFusedHypothesis->aConfirmedPoints.resize(aPointClouds.at(nFusionResultIndex).size());
375  pFusedHypothesis->aVisibleConfirmedPoints.clear();
376  pFusedHypothesis->aVisibleConfirmedPoints.resize(aPointClouds.at(nFusionResultIndex).size());
377 
378  for (size_t i = 0; i < aPointClouds.at(nFusionResultIndex).size(); i++)
379  {
380  pFusedHypothesis->aConfirmedPoints.at(i) = CColorICP::ConvertFromXYZRGBI(aPointClouds.at(nFusionResultIndex).at(i));
381  pFusedHypothesis->aVisibleConfirmedPoints.at(i) = CColorICP::ConvertFromXYZRGBI(aPointClouds.at(nFusionResultIndex).at(i));
382  }
383 
384  COLPTools::GetMeanAndVariance(pFusedHypothesis->aConfirmedPoints, pFusedHypothesis->vCenter, pFusedHypothesis->fMaxExtent);
385  pFusedHypothesis->fMaxExtent = 2 * sqrtf(pFusedHypothesis->fMaxExtent);
386 
387  for (int i = 0; i < nParallelityFactor; i++)
388  {
389  delete pColorICPInstances[i];
390  }
391 
392  gettimeofday(&tEnd, 0);
393  long tTimeDiff = (1000 * tEnd.tv_sec + tEnd.tv_usec / 1000) - (1000 * tStart.tv_sec + tStart.tv_usec / 1000);
394  ARMARX_VERBOSE_S << "Time for pointcloud fusion: " << tTimeDiff << " ms";
395  }
396 
397 }
OLP_ICP_COLOR_DISTANCE_WEIGHT
#define OLP_ICP_COLOR_DISTANCE_WEIGHT
Definition: ObjectLearningByPushingDefinitions.h:238
COLPTools::GetMeanAndVariance
void GetMeanAndVariance(const std::vector< CHypothesisPoint * > &pHypothesisPoints, Vec3d &vMean, float &fVariance)
Definition: OLPTools.cpp:699
CSegmentedPointCloudFusion::FusePointClouds
void FusePointClouds(std::vector< CObjectHypothesis * > aHypotheses, CObjectHypothesis *&pFusedHypothesis)
Definition: SegmentedPointCloudFusion.cpp:38
ColorICP.h
OLP_ICP_CUTOFF_DISTANCE
#define OLP_ICP_CUTOFF_DISTANCE
Definition: ObjectLearningByPushingDefinitions.h:240
CObjectHypothesis::eType
eObjectType eType
Definition: ObjectHypothesis.h:289
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
CObjectHypothesis::eRGBD
@ eRGBD
Definition: ObjectHypothesis.h:285
OLPTools.h
CSegmentedPointCloudFusion
Definition: SegmentedPointCloudFusion.cpp:36
M_PI
#define M_PI
Definition: MathTools.h:17
GfxTL::Vec3d
VectorXD< 3, double > Vec3d
Definition: VectorXD.h:695
CObjectHypothesis::vCenter
Vec3d vCenter
Definition: ObjectHypothesis.h:308
CObjectHypothesis::aVisibleConfirmedPoints
std::vector< CHypothesisPoint * > aVisibleConfirmedPoints
Definition: ObjectHypothesis.h:294
SegmentedPointCloudFusion.h
ARMARX_WARNING_S
#define ARMARX_WARNING_S
Definition: Logging.h:206
CObjectHypothesis
Definition: ObjectHypothesis.h:249
CObjectHypothesis::fMaxExtent
float fMaxExtent
Definition: ObjectHypothesis.h:315
CColorICP::ConvertToXYZRGBI
static CPointXYZRGBI ConvertToXYZRGBI(CHypothesisPoint *pPoint)
Definition: ColorICP.cpp:335
CObjectHypothesis::aConfirmedPoints
std::vector< CHypothesisPoint * > aConfirmedPoints
Definition: ObjectHypothesis.h:292
ARMARX_VERBOSE_S
#define ARMARX_VERBOSE_S
Definition: Logging.h:200
CColorICP
Definition: ColorICP.h:36
Logging.h
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