42 const int nParallelityFactor = omp_get_num_procs();
43 m_pColorICPInstances =
new CColorICP*[nParallelityFactor];
45 for (
int i = 0; i < nParallelityFactor; i++)
47 m_pColorICPInstances[i] =
new CColorICP();
56 const int nParallelityFactor = omp_get_num_procs();
58 for (
int i = 0; i < nParallelityFactor; i++)
60 delete m_pColorICPInstances[i];
63 delete m_pColorICPInstances;
72 std::vector<CColorICP::CPointXYZRGBI> aScenePointsConverted;
73 aScenePointsConverted.resize(aScenePoints.size());
75 for (
size_t i = 0; i < aScenePoints.size(); i++)
81 const int nParallelityFactor = omp_get_num_procs();
83 for (
int i = 0; i < nParallelityFactor; i++)
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)
96 gettimeofday(&tStart, 0);
97 const int nParallelityFactor = omp_get_num_procs();
98 omp_set_num_threads(nParallelityFactor);
101 std::vector<Vec3d> aPossibleLocationOffsets;
102 aPossibleLocationOffsets.push_back(center);
104 if (pPossibleLocationOffsets)
106 for (
size_t i = 0; i < pPossibleLocationOffsets->size(); i++)
108 aPossibleLocationOffsets.push_back(pPossibleLocationOffsets->at(i));
112 const int nNumPossibleLocations = aPossibleLocationOffsets.size();
114 ARMARX_VERBOSE_S <<
"Trying to match object around " << nNumPossibleLocations <<
" different possible locations";
116 for (
size_t i = 0; i < aPossibleLocationOffsets.size(); i++)
123 int nNumSamplesPerDimensionTemp;
125 switch (nEffortLevel)
131 nNumSamplesPerDimensionTemp = 1;
136 nNumSamplesPerDimensionTemp = 2;
141 nNumSamplesPerDimensionTemp = 3;
146 nNumSamplesPerDimensionTemp = 4;
151 nNumSamplesPerDimensionTemp = 5;
156 nNumSamplesPerDimensionTemp = 6;
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);
167 const float fShift = fShiftTemp;
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];
176 for (
int n = 0; n < nNumPossibleLocations; n++)
178 const Vec3d vLocationOffset = aPossibleLocationOffsets.at(n);
180 for (
int i = 0; i < nNumSamplesPerDimension; i++)
182 for (
int j = 0; j < nNumSamplesPerDimension; j++)
184 for (
int k = 0; k < nNumSamplesPerDimension; k++)
186 for (
int l = 0; l < nNumOrientations; l++)
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]);
202 size_t maxNumPoints = 200 + nEffortLevel * 200;
203 std::vector<CHypothesisPoint*> aObjectPointsDownsampled;
205 if (aObjectPoints.size() > maxNumPoints)
207 const float ratio = (
float)maxNumPoints / (
float)aObjectPoints.size();
208 const int randomThreshold = 1000.0f * ratio;
210 for (
size_t i = 0; i < aObjectPoints.size(); i++)
212 if (rand() % 1000 <= randomThreshold)
214 aObjectPointsDownsampled.push_back(aObjectPoints.at(i));
218 ARMARX_VERBOSE_S <<
"Object pointcloud was downsampled from " << aObjectPoints.size() <<
" to " << aObjectPointsDownsampled.size() <<
" points";
222 aObjectPointsDownsampled = aObjectPoints;
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;
238 #pragma omp parallel for schedule(dynamic, 1)
239 for (
int k = 0; k < nNumSamples; k++)
241 const int nThreadNumber = omp_get_thread_num();
243 std::vector<CColorICP::CPointXYZRGBI> objectPointCloudPar;
244 objectPointCloudPar.resize(aObjectPointsDownsampled.size());
247 for (
size_t i = 0; i < aObjectPointsDownsampled.size(); i++)
250 vPointPar.
x -= center.x;
251 vPointPar.
y -= center.y;
252 vPointPar.
z -= center.z;
253 objectPointCloudPar.at(i) = vPointPar;
256 if (tryDifferentOrientations)
261 for (
size_t i = 0; i < objectPointCloudPar.size(); i++)
263 objectPointCloudPar.at(i).x += pShiftVectors[k].x;
264 objectPointCloudPar.at(i).y += pShiftVectors[k].y;
265 objectPointCloudPar.at(i).z += pShiftVectors[k].z;
268 Mat3d newRotation, newRotationGlobal;
269 Vec3d newTranslation, newTranslationGlobal;
270 float fNewObjectDistance = m_pColorICPInstances[nThreadNumber]->
SearchObject(objectPointCloudPar, newRotation, newTranslation,
std::min(fBestDistance, maxAcceptedDistance));
272 GetCompleteTransformation(newRotation, newTranslation, rotationMatrices[k], pShiftVectors[k], center, newRotationGlobal, newTranslationGlobal);
276 distances.push_back(fNewObjectDistance);
277 positions.push_back(newTranslationGlobal);
280 if (fNewObjectDistance < fBestDistance)
282 fSecondBestDistance = fBestDistance;
283 Math3d::SetMat(mSecondBestRotation, mBestRotation);
284 Math3d::SetVec(vSecondBestTranslation, vBestTranslation);
286 fBestDistance = fNewObjectDistance;
287 Math3d::SetMat(mBestRotation, newRotationGlobal);
288 Math3d::SetVec(vBestTranslation, newTranslationGlobal);
290 else if (fNewObjectDistance < fSecondBestDistance)
292 fSecondBestDistance = fNewObjectDistance;
293 Math3d::SetMat(mSecondBestRotation, newRotationGlobal);
294 Math3d::SetVec(vSecondBestTranslation, newTranslationGlobal);
297 numSamplesAlreadyDone++;
299 if (numSamplesAlreadyDone % (3 * nNumSamplesPerDimension3) == 0)
311 Vec3d vRefinementTranslation, vTemp;
312 Mat3d mRefinementRotation;
317 std::vector<CColorICP::CPointXYZRGBI> objectPointCloudConverted;
319 for (
size_t i = 0; i < aObjectPoints.size(); i++)
321 Math3d::MulMatVec(mBestRotation, aObjectPoints.at(i)->vPosition, vBestTranslation, vTemp);
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);
333 std::vector<float> aPointMatchDistances;
337 objectPointCloudConverted.clear();
339 for (
size_t i = 0; i < aObjectPoints.size(); i++)
343 Math3d::MulMatVec(mBestRotation, aObjectPoints.at(i)->vPosition, vBestTranslation, vTemp);
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);
355 m_pColorICPInstances[0]->
SearchObject(objectPointCloudConverted, mRefinementRotation, vRefinementTranslation, fBestDistance);
360 Math3d::SetMat(mOldBestRot, mBestRotation);
361 Math3d::MulMatMat(mRefinementRotation, mOldBestRot, mBestRotation);
363 Vec3d vOldBestTransl;
364 Math3d::SetVec(vOldBestTransl, vBestTranslation);
365 Math3d::MulMatVec(mRefinementRotation, vOldBestTransl, vRefinementTranslation, vBestTranslation);
370 if (pPointMatchDistances && pNearestNeighbors)
373 objectPointCloudConverted.clear();
375 for (
size_t i = 0; i < aObjectPoints.size(); i++)
377 Math3d::MulMatVec(mBestRotation, aObjectPoints.at(i)->vPosition, vBestTranslation, vTemp);
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);
388 if (pAdditionalPoints)
390 for (
size_t i = 0; i < pAdditionalPoints->size(); i++)
392 Math3d::MulMatVec(mBestRotation, pAdditionalPoints->at(i)->vPosition, vBestTranslation, vTemp);
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);
404 pNearestNeighbors->clear();
405 pPointMatchDistances->clear();
406 m_pColorICPInstances[0]->
GetNearestNeighbors(objectPointCloudConverted, *pNearestNeighbors, *pPointMatchDistances);
412 Math3d::SetMat(mRotation, mBestRotation);
413 Math3d::SetVec(vTranslation, vBestTranslation);
417 std::vector<float> badMatchDistances;
419 for (
size_t i = 0; i < distances.size(); i++)
421 float dist = Math3d::Distance(vBestTranslation, positions.at(i));
425 badMatchDistances.push_back(distances.at(i));
429 float averageBadMatchDistance = 0;
431 for (
size_t i = 0; i < badMatchDistances.size(); i++)
433 averageBadMatchDistance += badMatchDistances.at(i);
436 if (badMatchDistances.size() > 0)
438 averageBadMatchDistance /= badMatchDistances.size();
442 ARMARX_VERBOSE_S <<
"Distance: " << fBestDistance <<
" average bad match distance: " << averageBadMatchDistance;
446 delete[] pShiftVectors;
447 delete[] rotationMatrices;
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";
455 return fBestDistance;
463 std::vector<CHypothesisPoint*> aObjectPoints;
473 for (
size_t i = 0; i < pHypothesis->
aNewPoints.size() && i < nNewPointsLimit; i++)
475 aObjectPoints.push_back(pHypothesis->
aNewPoints.at(i));
479 size_t maxNumPoints = 200 + nEffortLevel * 200;
480 std::vector<CHypothesisPoint*> aObjectPointsDownsampled;
482 if (aObjectPoints.size() > maxNumPoints)
484 const float ratio = (
float)maxNumPoints / (
float)aObjectPoints.size();
485 const int randomThreshold = 1000.0f * ratio;
487 for (
size_t i = 0; i < aObjectPoints.size(); i++)
489 if (rand() % 1000 <= randomThreshold)
491 aObjectPointsDownsampled.push_back(aObjectPoints.at(i));
495 ARMARX_VERBOSE_S <<
"Object pointcloud was downsampled from " << aObjectPoints.size() <<
" to " << aObjectPointsDownsampled.size() <<
" points";
499 aObjectPointsDownsampled = aObjectPoints;
503 std::vector<CColorICP::CPointXYZRGBI> objectPointCloudConverted;
505 for (
size_t i = 0; i < aObjectPointsDownsampled.size(); i++)
512 distance = m_pColorICPInstances[0]->
SearchObject(objectPointCloudConverted, mRotation, vTranslation);
516 Vec3d vObjectCenter = {0, 0, 0};
518 for (
size_t i = 0; i < aObjectPointsDownsampled.size(); i++)
520 Math3d::AddToVec(vObjectCenter, aObjectPointsDownsampled.at(i)->vPosition);
523 Math3d::MulVecScalar(vObjectCenter, 1.0f / aObjectPointsDownsampled.size(), vObjectCenter);
525 Math3d::MulMatVec(mRotation, vObjectCenter, vTranslation, vTemp1);
526 float fTranslationLength = Math3d::Distance(vTemp1, vObjectCenter);
530 Math3d::GetAxisAndAngle(mRotation, vTemp1, fAngle);
535 ARMARX_VERBOSE_S <<
"Check at original position: Translation: " << fTranslationLength <<
" Rotation: " << 180 * fAngle /
M_PI <<
"deg";
615 const int nEffortLevel,
const std::vector<Vec3d>* pPossibleLocations, std::vector<CColorICP::CPointXYZRGBI>* pNearestNeighbors,
616 std::vector<float>* pPointMatchDistances,
const float maxAcceptedDistance)
618 #ifdef OLP_USE_DEPTH_MAP
621 std::vector<CHypothesisPoint*> aHypothesisPoints = pHypothesis->
aConfirmedPoints;
625 size_t maxNumPoints = 200 + nEffortLevel * 200;
626 size_t nNewPointsLimit;
628 if (aHypothesisPoints.size() >= maxNumPoints)
634 nNewPointsLimit = maxNumPoints - aHypothesisPoints.size();
642 for (
size_t i = 0; i < pHypothesis->
aNewPoints.size() && i < nNewPointsLimit; i++)
644 aHypothesisPoints.push_back(pHypothesis->
aNewPoints.at(i));
649 std::vector<CHypothesisPoint*> aAdditionalPoints;
651 for (
size_t i = nNewPointsLimit; i < pHypothesis->
aNewPoints.size(); i++)
653 aAdditionalPoints.push_back(pHypothesis->
aNewPoints.at(i));
663 pPossibleLocations, pNearestNeighbors, pPointMatchDistances, &aAdditionalPoints, maxAcceptedDistance);
682 Vec3d center = {0, 0, 0};
696 for (
size_t i = 0; i < points.size(); i++)
698 Vec3d point = {points.at(i).x - center.x, points.at(i).y - center.y, points.at(i).z - center.z};
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;
710 Math3d::MulMatMat(rotICP, rotShift, completeRotation);
713 Math3d::MulMatVec(completeRotation, center, temp1);
714 Math3d::MulMatVec(rotICP, transShift, temp2);
715 Math3d::SubtractVecVec(temp2, temp1, completeTranslation);
716 Math3d::AddToVec(completeTranslation, transICP);
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);