19 #include <tbb/tbb_thread.h>
20 #include <tbb/concurrent_queue.h>
40 #define MAX_VARIANCE 500.0
41 #define DISTANCE_PENALTY_GAIN 0.2
42 #define ANGLE_PENALTY_GAIN 0.2
252 if (pSensorDataManager != NULL)
273 sensorNames.
Add(iter->first);
341 objects.
Add(rObjects);
388 GridIndexLookup<kt_int8u>* pGridLookup =
new GridIndexLookup<kt_int8u>(pCorrelationGrid);
390 m_ScanMatcherGridSets.push(
new ScanMatcherGridSet(pCorrelationGrid, pSearchSpaceProbs, pGridLookup));
394 virtual ~ScanMatcherGridSetBank()
397 m_ScanMatcherGridSets.push(NULL);
399 m_ScanMatcherGridSets.clear();
406 SmartPointer<ScanMatcherGridSet> CheckOut()
408 SmartPointer<ScanMatcherGridSet> pScanMatcherGridSet = NULL;
410 m_ScanMatcherGridSets.pop(pScanMatcherGridSet);
412 return pScanMatcherGridSet;
418 void Return(SmartPointer<ScanMatcherGridSet> pScanMatcherGridSet)
420 m_ScanMatcherGridSets.push(pScanMatcherGridSet);
424 tbb::concurrent_bounded_queue<SmartPointer<ScanMatcherGridSet> > m_ScanMatcherGridSets;
452 if (smearDeviation < 0)
456 if (rangeThreshold <= 0)
468 kt_int32u pointReadingMargin =
static_cast<kt_int32u>(ceil(rangeThreshold / resolution));
470 kt_int32s gridSize = searchSpaceSideSize + 2 * pointReadingMargin;
473 assert(gridSize % 2 == 1);
513 CorrelationGrid* pCorrelationGrid = pScanMatcherGridSet->m_pCorrelationGrid;
514 Grid<kt_double>* pSearchSpaceProbs = pScanMatcherGridSet->m_pSearchSpaceProbs;
567 kt_double bestResponse =
CorrelateScan(pScanMatcherGridSet, pScan, scanPose, coarseSearchOffset, coarseSearchResolution,
m_pOpenMapper->
m_pCoarseSearchAngleOffset->
GetValue(),
m_pOpenMapper->
m_pCoarseAngleResolution->
GetValue(), doPenalize, rMean, rCovariance,
false);
574 std::cout <<
"Mapper Info: Expanding response search space!" << std::endl;
582 bestResponse =
CorrelateScan(pScanMatcherGridSet, pScan, scanPose, coarseSearchOffset, coarseSearchResolution, newSearchAngleOffset,
m_pOpenMapper->
m_pCoarseAngleResolution->
GetValue(), doPenalize, rMean, rCovariance,
false);
593 std::cout <<
"Mapper Warning: Unable to calculate response!" << std::endl;
601 Vector2d fineSearchOffset(coarseSearchResolution * 0.5);
603 bestResponse =
CorrelateScan(pScanMatcherGridSet, pScan, rMean, fineSearchOffset, fineSearchResolution, 0.5 *
m_pOpenMapper->
m_pCoarseAngleResolution->
GetValue(),
m_pOpenMapper->
m_pFineSearchAngleOffset->
GetValue(), doPenalize, rMean, rCovariance,
true);
607 std::cout <<
" BEST POSE = " << rMean <<
" BEST RESPONSE = " << bestResponse <<
", VARIANCE = " << rCovariance(0, 0) <<
", " << rCovariance(1, 1) << std::endl;
623 class Parallel_CorrelateScan
626 Parallel_CorrelateScan(std::vector<kt_double>* pNewPositionsY, std::vector<kt_double>* pSquaresY,
627 std::vector<kt_double>* pNewPositionsX, std::vector<kt_double>* pSquaresX,
628 std::vector<kt_double>* pAngles,
629 std::vector<std::pair<kt_double, Pose2> >* pPoseResponses,
634 : m_pNewPositionsY(pNewPositionsY)
635 , m_pSquaresY(pSquaresY)
636 , m_pNewPositionsX(pNewPositionsX)
637 , m_pSquaresX(pSquaresX)
639 , m_pPoseResponses(pPoseResponses)
640 , m_pScanMatcher(pScanMatcher)
641 , m_DoPenalize(doPenalize)
642 , m_DistanceVariancePenalty(distanceVariancePenalty)
643 , m_MinimumDistancePenalty(minimumDistancePenalty)
644 , m_AngleVariancePenalty(angleVariancePenalty)
645 , m_MinimumAnglePenalty(minimumAnglePenalty)
646 , m_SearchCenterHeading(searchCenterHeading)
647 , m_pScanMatcherGridSet(pScanMatcherGridSet)
649 m_nX = pNewPositionsX->size();
650 m_nAngles = pAngles->size();
653 void operator()(
const tbb::blocked_range3d<kt_int32s, kt_int32s, kt_int32s>& rRange)
const
655 CorrelationGrid* pCorrelationGrid = m_pScanMatcherGridSet->m_pCorrelationGrid;
657 for (tbb::blocked_range<kt_int32s>::const_iterator yIndex = rRange.pages().begin(); yIndex != rRange.pages().end(); yIndex++)
659 kt_double newPositionY = m_pNewPositionsY->at(yIndex);
660 kt_double squareY = m_pSquaresY->at(yIndex);
662 for (tbb::blocked_range<kt_int32s>::const_iterator xIndex = rRange.rows().begin(); xIndex != rRange.rows().end(); xIndex++)
664 kt_double newPositionX = m_pNewPositionsX->at(xIndex);
665 kt_double squareX = m_pSquaresX->at(xIndex);
667 Vector2i gridPoint = pCorrelationGrid->WorldToGrid(
Vector2d(newPositionX, newPositionY));
668 kt_int32s gridIndex = pCorrelationGrid->GridIndex(gridPoint);
669 assert(gridIndex >= 0);
671 kt_double squaredDistance = squareX + squareY;
673 for (tbb::blocked_range<kt_int32s>::const_iterator angleIndex = rRange.cols().begin(); angleIndex != rRange.cols().end(); angleIndex++)
675 kt_int32u poseResponseIndex = (m_nX * m_nAngles) * yIndex + m_nAngles * xIndex + angleIndex;
679 kt_double response = m_pScanMatcher->GetResponse(m_pScanMatcherGridSet, angleIndex, gridIndex);
685 distancePenalty =
math::Maximum(distancePenalty, m_MinimumDistancePenalty);
689 anglePenalty =
math::Maximum(anglePenalty, m_MinimumAnglePenalty);
691 response *= (distancePenalty * anglePenalty);
695 m_pPoseResponses->at(poseResponseIndex) = std::pair<kt_double, Pose2>(response, Pose2(newPositionX, newPositionY,
math::NormalizeAngle(angle)));
702 std::vector<kt_double>* m_pNewPositionsY;
703 std::vector<kt_double>* m_pSquaresY;
704 std::vector<kt_double>* m_pNewPositionsX;
705 std::vector<kt_double>* m_pSquaresX;
706 std::vector<kt_double>* m_pAngles;
707 std::vector<std::pair<kt_double, Pose2> >* m_pPoseResponses;
708 ScanMatcher* m_pScanMatcher;
710 kt_double m_DistanceVariancePenalty, m_MinimumDistancePenalty;
711 kt_double m_AngleVariancePenalty, m_MinimumAnglePenalty;
714 ScanMatcherGridSet* m_pScanMatcherGridSet;
721 assert(searchAngleResolution != 0.0);
733 pSearchSpaceProbs->
Clear();
743 std::vector<kt_double> xPoses(nX), newPositionsX(nX), squaresX(nX);
745 for (
kt_int32u xIndex = 0; xIndex < nX; xIndex++)
747 kt_double x = startX + xIndex * rSearchSpaceResolution.
GetX();
749 newPositionsX[xIndex] = rSearchCenter.
GetX() + x;
755 std::vector<kt_double> yPoses(nY), newPositionsY(nY), squaresY(nY);
757 for (
kt_int32u yIndex = 0; yIndex < nY; yIndex++)
759 kt_double y = startY + yIndex * rSearchSpaceResolution.
GetY();
761 newPositionsY[yIndex] = rSearchCenter.
GetY() + y;
768 std::vector<kt_double>
angles(nAngles);
771 for (
kt_int32u angleIndex = 0; angleIndex < nAngles; angleIndex++)
773 angle = startAngle + angleIndex * searchAngleResolution;
779 kt_int32u poseResponseSize = nX * nY * nAngles;
780 std::vector<std::pair<kt_double, Pose2> > poseResponses = std::vector<std::pair<kt_double, Pose2> >(poseResponseSize);
790 Parallel_CorrelateScan myTask(&newPositionsY, &squaresY, &newPositionsX, &squaresX, &
angles,
791 &poseResponses,
this, doPenalize,
796 rSearchCenter.
GetHeading(), pScanMatcherGridSet);
799 int grainSizeAngle = 10;
800 tbb::parallel_for(tbb::blocked_range3d<kt_int32s>(0,
static_cast<kt_int32s>(nY), grainSizeY, 0,
static_cast<kt_int32s>(nX), grainSizeX, 0, nAngles, grainSizeAngle), myTask);
808 for (
kt_int32u yIndex = 0; yIndex < nY; yIndex++)
810 kt_double newPositionY = newPositionsY[yIndex];
813 for (
kt_int32u xIndex = 0; xIndex < nX; xIndex++)
815 kt_double newPositionX = newPositionsX[xIndex];
820 assert(gridIndex >= 0);
822 kt_double squaredDistance = squareX + squareY;
823 for (
kt_int32u angleIndex = 0; angleIndex < nAngles; angleIndex++)
839 response *= (distancePenalty * anglePenalty);
844 poseResponseCounter++;
849 assert(poseResponseSize == poseResponseCounter);
854 for (
kt_int32u i = 0; i < poseResponseSize; i++)
856 bestResponse =
math::Maximum(bestResponse, poseResponses[i].first);
861 const Pose2& rPose = poseResponses[i].second;
867 throw Exception(
"Mapper FATAL ERROR - Index out of range in probability search!");
879 for (
kt_int32u i = 0; i < poseResponseSize; i++)
883 averagePosition += poseResponses[i].second.GetPosition();
885 kt_double heading = poseResponses[i].second.GetHeading();
886 thetaX += cos(heading);
887 thetaY += sin(heading);
894 if (averagePoseCount > 0)
896 averagePosition /= averagePoseCount;
898 thetaX /= averagePoseCount;
899 thetaY /= averagePoseCount;
901 averagePose =
Pose2(averagePosition, atan2(thetaY, thetaX));
905 throw Exception(
"Mapper FATAL ERROR - Unable to find best position");
909 std::cout <<
"bestPose: " << averagePose << std::endl;
910 std::cout <<
"bestResponse: " << bestResponse << std::endl;
915 ComputePositionalCovariance(pSearchSpaceProbs, averagePose, bestResponse, rSearchCenter, rSearchSpaceOffset, rSearchSpaceResolution, searchAngleResolution, rCovariance);
919 ComputeAngularCovariance(pScanMatcherGridSet, averagePose, bestResponse, rSearchCenter, searchAngleOffset, searchAngleResolution, rCovariance);
925 std::cout <<
"bestPose: " << averagePose << std::endl;
928 if (bestResponse > 1.0)
940 const Pose2& rSearchCenter,
const Vector2d& rSearchSpaceOffset,
951 rCovariance(2, 2) = 4 *
math::Square(searchAngleResolution);
975 for (
kt_int32u yIndex = 0; yIndex < nY; yIndex++)
977 kt_double y = startY + yIndex * rSearchSpaceResolution.
GetY();
979 for (
kt_int32u xIndex = 0; xIndex < nX; xIndex++)
981 kt_double x = startX + xIndex * rSearchSpaceResolution.
GetX();
987 if (
response >= (bestResponse - 0.1))
991 accumulatedVarianceXY += ((x - dx) * (y - dy) *
response);
999 kt_double varianceXX = accumulatedVarianceXX / norm;
1000 kt_double varianceXY = accumulatedVarianceXY / norm;
1001 kt_double varianceYY = accumulatedVarianceYY / norm;
1012 kt_double multiplier = 1.0 / bestResponse;
1013 rCovariance(0, 0) = varianceXX * multiplier;
1014 rCovariance(0, 1) = varianceXY * multiplier;
1015 rCovariance(1, 0) = varianceXY * multiplier;
1016 rCovariance(1, 1) = varianceYY * multiplier;
1017 rCovariance(2, 2) = varianceTHTH;
1052 kt_double accumulatedVarianceThTh = 0.0;
1053 for (
kt_int32u angleIndex = 0; angleIndex < nAngles; angleIndex++)
1055 angle = startAngle + angleIndex * searchAngleResolution;
1059 if (
response >= (bestResponse - 0.1))
1071 accumulatedVarianceThTh =
math::Square(searchAngleResolution);
1074 accumulatedVarianceThTh /= norm;
1078 accumulatedVarianceThTh = 1000 *
math::Square(searchAngleResolution);
1081 rCovariance(2, 2) = accumulatedVarianceThTh;
1086 pCorrelationGrid->
Clear();
1091 AddScan(pCorrelationGrid, *iter, rViewPoint);
1097 pCorrelationGrid->
Clear();
1118 AddScanNew(pCorrelationGrid, pValidPoints[i]);
1121 delete[] pValidPoints;
1138 int gridIndex = pCorrelationGrid->
GridIndex(gridPoint);
1150 if (doSmear ==
true)
1169 int gridIndex = pCorrelationGrid->
GridIndex(gridPoint);
1181 if (doSmear ==
true)
1208 firstPoint = currentPoint;
1212 Vector2d delta = firstPoint - currentPoint;
1220 double a = rViewPoint.
GetY() - firstPoint.
GetY();
1221 double b = firstPoint.
GetX() - rViewPoint.
GetX();
1222 double c = firstPoint.
GetY() * rViewPoint.
GetX() - firstPoint.
GetX() * rViewPoint.
GetY();
1223 double ss = currentPoint.GetX() * a + currentPoint.GetY() * b + c;
1226 firstPoint = currentPoint;
1230 trailingPointIter = iter;
1234 for (; trailingPointIter != iter; trailingPointIter++)
1236 validPoints.
Add(*trailingPointIter);
1256 assert(pOffsets != NULL);
1270 kt_int32s pointGridIndex = gridPositionIndex + pAngleIndexPointer[i];
1277 response += pByte[pAngleIndexPointer[i]];
1291 throw Exception(
"Correlation grid only available in single-threaded mode");
1303 throw Exception(
"Search grid only available in single-threaded mode");
1315 template<
typename T>
1343 std::queue<Vertex<T>*> toVisit;
1344 std::set<Vertex<T>*> seenVertices;
1345 std::vector<Vertex<T>*> validVertices;
1347 toVisit.push(pStartVertex);
1348 seenVertices.insert(pStartVertex);
1355 if (pVisitor->
Visit(pNext))
1358 validVertices.push_back(pNext);
1366 if (seenVertices.find(pAdjacent) == seenVertices.end())
1368 toVisit.push(pAdjacent);
1369 seenVertices.insert(pAdjacent);
1373 }
while (toVisit.empty() ==
false);
1378 objects.
Add((*iter)->GetVertexObject());
1430 : m_pOpenMapper(pOpenMapper)
1451 if (pObject == NULL)
1483 if (pLastScan != NULL)
1500 if (pLastScan == NULL)
1504 assert(pSensorManager->
GetScans(rSensorName).
Size() == 1);
1509 const Identifier& rCandidateSensorName = *iter;
1512 if ((rCandidateSensorName == rSensorName) || (pSensorManager->
GetScans(rCandidateSensorName).
IsEmpty()))
1520 LinkObjects(pSensorManager->
GetScans(rCandidateSensorName)[0], pScan, bestPose, covariance);
1525 means.
Add(bestPose);
1526 covariances.
Add(covariance);
1537 means.
Add(scanPose);
1538 covariances.
Add(rCovariance);
1559 while (!candidateChain.
IsEmpty())
1562 std::cout <<
"Candidate chain for " << pScan->
GetStateId() <<
": [ ";
1565 std::cout << (*iter)->GetStateId() <<
" ";
1567 std::cout <<
"]" << std::endl;
1601 if (fineResponse < m_pOpenMapper->m_pLoopMatchMinimumResponseFine->GetValue())
1636 kt_double bestSquaredDistance = DBL_MAX;
1643 if (squaredDistance < bestSquaredDistance)
1645 bestSquaredDistance = squaredDistance;
1646 pClosestScan = *iter;
1650 return pClosestScan;
1686 if (isNewEdge ==
true)
1705 class Parallel_LinkNearChains
1711 : m_pOpenMapper(pMapper)
1713 , m_pChains(pChains)
1714 , m_pWasChainLinked(pWasChainLinked)
1716 , m_pCovariances(pCovariances)
1717 , m_MinChainSize(minChainSize)
1718 , m_MinResponse(minResponse)
1722 void operator()(
const tbb::blocked_range<kt_int32s>& rRange)
const
1724 for (
kt_int32s i = rRange.begin(); i != rRange.end(); i++)
1726 m_pWasChainLinked[i] =
false;
1730 if (rChain.Size() < m_MinChainSize)
1739 kt_double response = m_pOpenMapper->GetSequentialScanMatcher()->MatchScan(m_pScan, rChain, mean, covariance,
false);
1742 m_pWasChainLinked[i] =
true;
1743 m_pMeans->Set(i, mean);
1744 m_pCovariances->Set(i, covariance);
1750 OpenMapper* m_pOpenMapper;
1751 LocalizedLaserScan* m_pScan;
1752 const List<LocalizedLaserScanList>* m_pChains;
1755 List<Matrix3>* m_pCovariances;
1778 int grainSize = 100;
1779 Parallel_LinkNearChains myTask(
m_pOpenMapper, pScan, &nearChains, pWasChainLinked, &means, &covariances,
1782 tbb::parallel_for(tbb::blocked_range<kt_int32s>(0,
static_cast<kt_int32s>(nearChains.
Size()), grainSize), myTask);
1786 if (pWasChainLinked[i] ==
true)
1788 rMeans.
Add(means[i]);
1789 rCovariances.
Add(covariances[i]);
1794 delete [] pWasChainLinked;
1798 if (gotTbb ==
false)
1803 std::cout <<
"Near chain for " << pScan->
GetStateId() <<
": [ ";
1806 std::cout << (*iter2)->GetStateId() <<
" ";
1826 std::cout <<
" ACCEPTED" << std::endl;
1829 rCovariances.
Add(covariance);
1847 assert(pClosestScan != NULL);
1854 LinkObjects(pClosestScan, pScan, rMean, rCovariance);
1856 std::cout <<
"Linking scan " << pScan->
GetStateId() <<
" to chain scan " << pClosestScan->
GetStateId() << std::endl;
1875 if (pNearScan == pScan)
1881 if (processed.
Contains(pNearScan) ==
true)
1890 processed.
Add(pNearScan);
1899 assert(nearScanIndex >= 0);
1902 for (
kt_int32s candidateScanIndex = nearScanIndex - 1; candidateScanIndex >= 0; candidateScanIndex--)
1907 if (pCandidateScan == pScan)
1910 std::cout <<
"INVALID CHAIN: Scan " << pScan->
GetStateId() <<
" is not allowed in chain." << std::endl;
1912 isValidChain =
false;
1920 chain.
Add(pCandidateScan);
1921 processed.
Add(pCandidateScan);
1924 std::cout <<
"Building chain for " << pScan->
GetStateId() <<
": [ ";
1927 std::cout << (*iter2)->GetStateId() <<
" ";
1929 std::cout <<
"]" << std::endl;
1938 chain.
Add(pNearScan);
1942 for (
kt_size_t candidateScanIndex = nearScanIndex + 1; candidateScanIndex < end; candidateScanIndex++)
1946 if (pCandidateScan == pScan)
1949 std::cout <<
"INVALID CHAIN: Scan " << pScan->
GetStateId() <<
" is not allowed in chain." << std::endl;
1951 isValidChain =
false;
1959 chain.
Add(pCandidateScan);
1960 processed.
Add(pCandidateScan);
1963 std::cout <<
"Building chain for " << pScan->
GetStateId() <<
": [ ";
1966 std::cout << (*iter2)->GetStateId() <<
" ";
1968 std::cout <<
"]" << std::endl;
1980 nearChains.
Add(chain);
2000 nearLinkedScans.
Add(pScan);
2004 return nearLinkedScans;
2018 if (pCandidateScan == NULL)
2025 nearScans.
Add(pCandidateScan);
2035 assert(rMeans.
Size() == rCovariances.
Size());
2052 Pose2 accumulatedPose;
2059 Pose2 pose = *meansIter;
2061 thetaX += cos(
angle);
2062 thetaY += sin(
angle);
2064 Matrix3 weight = inverseOfSumOfInverses * (*iter);
2065 accumulatedPose += weight * pose;
2070 thetaX /= rMeans.
Size();
2071 thetaY /= rMeans.
Size();
2072 accumulatedPose.
SetHeading(atan2(thetaY, thetaX));
2074 return accumulatedPose;
2089 for (; rStartScanIndex < nScans; rStartScanIndex++)
2099 if (nearLinkedScans.
Contains(pCandidateScan) ==
true)
2105 chain.
Add(pCandidateScan);
2129 if (pSolver != NULL)
2161 , m_pScanSolver(NULL)
2162 , m_Initialized(false)
2163 , m_MultiThreaded(multiThreaded)
2164 , m_pSequentialScanMatcher(NULL)
2165 , m_pMapperSensorManager(NULL)
2176 , m_pScanSolver(NULL)
2177 , m_Initialized(false)
2178 , m_MultiThreaded(multiThreaded)
2179 , m_pSequentialScanMatcher(NULL)
2180 , m_pMapperSensorManager(NULL)
2189 OpenMapper::~OpenMapper()
2271 if (pObject == NULL)
2278 if (IsLaserRangeFinder(pObject))
2295 if (pLocalizedObject != NULL)
2303 if (pLaserRangeFinder == NULL)
2309 pLaserRangeFinder->
Validate(pScan);
2325 if (pLastScan != NULL)
2387 isObjectProcessed =
true;
2390 return isObjectProcessed;
2396 if (pLastScan == NULL)