36 #define MAX_VARIANCE 500.0
37 #define DISTANCE_PENALTY_GAIN 0.2
38 #define ANGLE_PENALTY_GAIN 0.2
62 if (pScanManager != NULL)
64 return pScanManager->
GetScans().at(scanIndex);
94 scans.insert(scans.end(), rScans.begin(), rScans.end());
138 if (smearDeviation < 0)
142 if (rangeThreshold <= 0)
154 kt_int32u pointReadingMargin =
static_cast<kt_int32u>(ceil(rangeThreshold / resolution));
156 kt_int32s gridSize = searchSpaceSideSize + 2 * pointReadingMargin;
159 assert(gridSize % 2 == 1);
164 searchSpaceSideSize, resolution);
236 doPenalize, rMean, rCovariance,
false);
243 std::cout <<
"Mapper Info: Expanding response search space!" << std::endl;
251 bestResponse =
CorrelateScan(pScan, scanPose, coarseSearchOffset, coarseSearchResolution,
253 doPenalize, rMean, rCovariance,
false);
264 std::cout <<
"Mapper Warning: Unable to calculate response!" << std::endl;
274 bestResponse =
CorrelateScan(pScan, rMean, fineSearchOffset, fineSearchResolution,
277 doPenalize, rMean, rCovariance,
true);
281 std::cout <<
" BEST POSE = " << rMean <<
" BEST RESPONSE = " << bestResponse <<
", VARIANCE = "
282 << rCovariance(0, 0) <<
", " << rCovariance(1, 1) << std::endl;
311 assert(searchAngleResolution != 0.0);
328 std::vector<kt_double> xPoses;
330 2.0 / rSearchSpaceResolution.
GetX()) + 1);
332 for (
kt_int32u xIndex = 0; xIndex < nX; xIndex++)
334 xPoses.push_back(startX + xIndex * rSearchSpaceResolution.
GetX());
338 std::vector<kt_double> yPoses;
340 2.0 / rSearchSpaceResolution.
GetY()) + 1);
342 for (
kt_int32u yIndex = 0; yIndex < nY; yIndex++)
344 yPoses.push_back(startY + yIndex * rSearchSpaceResolution.
GetY());
351 kt_int32u poseResponseSize =
static_cast<kt_int32u>(xPoses.size() * yPoses.size() * nAngles);
354 std::pair<kt_double, Pose2>* pPoseResponse =
new std::pair<kt_double, Pose2>[poseResponseSize];
357 + startX, rSearchCenter.
GetY() + startY));
360 forEachAs(std::vector<kt_double>, &yPoses, yIter)
366 forEachAs(std::vector<kt_double>, &xPoses, xIter)
374 assert(gridIndex >= 0);
378 for (
kt_int32u angleIndex = 0; angleIndex < nAngles; angleIndex++)
380 angle = startAngle + angleIndex * searchAngleResolution;
387 kt_double squaredDistance = squareX + squareY;
397 response *= (distancePenalty * anglePenalty);
401 pPoseResponse[poseResponseCounter] = std::pair<kt_double, Pose2>(
response,
Pose2(newPositionX, newPositionY,
403 poseResponseCounter++;
410 assert(poseResponseSize == poseResponseCounter);
414 for (
kt_int32u i = 0; i < poseResponseSize; i++)
416 bestResponse =
math::Maximum(bestResponse, pPoseResponse[i].first);
421 const Pose2& rPose = pPoseResponse[i].second;
428 throw std::runtime_error(
"Mapper FATAL ERROR - Index out of range in probability search!");
440 for (
kt_int32u i = 0; i < poseResponseSize; i++)
444 averagePosition += pPoseResponse[i].second.GetPosition();
446 kt_double heading = pPoseResponse[i].second.GetHeading();
447 thetaX += cos(heading);
448 thetaY += sin(heading);
455 if (averagePoseCount > 0)
457 averagePosition /= averagePoseCount;
459 thetaX /= averagePoseCount;
460 thetaY /= averagePoseCount;
462 averagePose =
Pose2(averagePosition, atan2(thetaY, thetaX));
466 throw std::runtime_error(
"Mapper FATAL ERROR - Unable to find best position");
470 delete [] pPoseResponse;
473 std::cout <<
"bestPose: " << averagePose << std::endl;
474 std::cout <<
"bestResponse: " << bestResponse << std::endl;
480 rSearchSpaceResolution, searchAngleResolution, rCovariance);
485 searchAngleOffset, searchAngleResolution, rCovariance);
491 std::cout <<
"bestPose: " << averagePose << std::endl;
494 if (bestResponse > 1.0)
516 const Pose2& rSearchCenter,
529 rCovariance(2, 2) = 4 *
math::Square(searchAngleResolution);
553 for (
kt_int32u yIndex = 0; yIndex < nY; yIndex++)
555 kt_double y = startY + yIndex * rSearchSpaceResolution.
GetY();
557 for (
kt_int32u xIndex = 0; xIndex < nX; xIndex++)
559 kt_double x = startX + xIndex * rSearchSpaceResolution.
GetX();
562 rSearchCenter.
GetY() + y));
566 if (
response >= (bestResponse - 0.1))
570 accumulatedVarianceXY += ((x - dx) * (y - dy) *
response);
578 kt_double varianceXX = accumulatedVarianceXX / norm;
579 kt_double varianceXY = accumulatedVarianceXY / norm;
580 kt_double varianceYY = accumulatedVarianceYY / norm;
591 kt_double multiplier = 1.0 / bestResponse;
592 rCovariance(0, 0) = varianceXX * multiplier;
593 rCovariance(0, 1) = varianceXY * multiplier;
594 rCovariance(1, 0) = varianceXY * multiplier;
595 rCovariance(1, 1) = varianceYY * multiplier;
596 rCovariance(2, 2) = varianceTHTH;
623 const Pose2& rSearchCenter,
643 for (
kt_int32u angleIndex = 0; angleIndex < nAngles; angleIndex++)
645 angle = startAngle + angleIndex * searchAngleResolution;
649 if (
response >= (bestResponse - 0.1))
661 accumulatedVarianceThTh =
math::Square(searchAngleResolution);
664 accumulatedVarianceThTh /= norm;
668 accumulatedVarianceThTh = 1000 *
math::Square(searchAngleResolution);
671 rCovariance(2, 2) = accumulatedVarianceThTh;
745 PointVectorDouble::const_iterator trailingPointIter = rPointReadings.begin();
754 if (firstTime && !std::isnan(currentPoint.
GetX()) && !std::isnan(currentPoint.
GetY()))
756 firstPoint = currentPoint;
768 double a = rViewPoint.
GetY() - firstPoint.
GetY();
769 double b = firstPoint.
GetX() - rViewPoint.
GetX();
770 double c = firstPoint.
GetY() * rViewPoint.
GetX() - firstPoint.
GetX() * rViewPoint.
GetY();
771 double ss = currentPoint.GetX() * a + currentPoint.GetY() * b + c;
774 firstPoint = currentPoint;
778 trailingPointIter = iter;
782 for (; trailingPointIter != iter; ++trailingPointIter)
784 validPoints.push_back(*trailingPointIter);
807 assert(pOffsets != NULL);
821 kt_int32s pointGridIndex = gridPositionIndex + pAngleIndexPointer[i];
828 response += pByte[pAngleIndexPointer[i]];
886 if (pSensorManager->
GetLastScan(rSensorName) != NULL)
888 assert(previousScanNum >= 0);
893 std::vector<Matrix3> covariances;
896 if (pSensorManager->
GetLastScan(rSensorName) == NULL)
898 assert(pSensorManager->
GetScans(rSensorName).size() == 1);
901 forEach(std::vector<Name>, &deviceNames)
903 const Name& rCandidateSensorName = *iter;
906 if ((rCandidateSensorName == rSensorName) || (pSensorManager->
GetScans(rCandidateSensorName).empty()))
914 pSensorManager->
GetScans(rCandidateSensorName),
915 bestPose, covariance);
916 LinkScans(pSensorManager->
GetScan(rCandidateSensorName, 0), pScan, bestPose, covariance);
921 means.push_back(bestPose);
922 covariances.push_back(covariance);
930 means.push_back(scanPose);
931 covariances.push_back(rCovariance);
952 while (!candidateChain.empty())
957 bestPose, covariance,
false,
false);
959 std::stringstream stream;
960 stream <<
"COARSE RESPONSE: " << coarseResponse
963 stream <<
" var: " << covariance(0, 0) <<
", " << covariance(1, 1)
979 bestPose, covariance,
false);
981 std::stringstream stream1;
982 stream1 <<
"FINE RESPONSE: " << fineResponse <<
" (>"
986 if (fineResponse < m_pMapper->m_pLoopMatchMinimumResponseFine->GetValue())
1011 const Pose2& rPose)
const
1014 kt_double bestSquaredDistance = DBL_MAX;
1021 if (squaredDistance < bestSquaredDistance)
1023 bestSquaredDistance = squaredDistance;
1024 pClosestScan = *iter;
1028 return pClosestScan;
1066 if (isNewEdge ==
true)
1078 const std::vector<LocalizedRangeScanVector> nearChains =
FindNearChains(pScan);
1079 const_forEach(std::vector<LocalizedRangeScanVector>, &nearChains)
1092 rMeans.push_back(mean);
1093 rCovariances.push_back(covariance);
1105 assert(pClosestScan != NULL);
1112 LinkScans(pClosestScan, pScan, rMean, rCovariance);
1118 std::vector<LocalizedRangeScanVector> nearChains;
1131 if (pNearScan == pScan)
1137 if (find(processed.begin(), processed.end(), pNearScan) != processed.end())
1142 processed.push_back(pNearScan);
1146 std::list<LocalizedRangeScan*> chain;
1149 for (
kt_int32s candidateScanNum = pNearScan->
GetStateId() - 1; candidateScanNum >= 0; candidateScanNum--)
1155 if (pCandidateScan == pScan)
1157 isValidChain =
false;
1165 chain.push_front(pCandidateScan);
1166 processed.push_back(pCandidateScan);
1174 chain.push_back(pNearScan);
1178 for (
kt_int32u candidateScanNum = pNearScan->
GetStateId() + 1; candidateScanNum < end; candidateScanNum++)
1183 if (pCandidateScan == pScan)
1185 isValidChain =
false;
1193 chain.push_back(pCandidateScan);
1194 processed.push_back(pCandidateScan);
1206 std::copy(chain.begin(), chain.end(), std::inserter(tempChain, tempChain.begin()));
1208 nearChains.push_back(tempChain);
1221 return nearLinkedScans;
1226 assert(rMeans.size() == rCovariances.size());
1229 std::vector<Matrix3> inverses;
1230 inverses.reserve(rCovariances.size());
1236 inverses.push_back(inverse);
1238 sumOfInverses += inverse;
1243 Pose2 accumulatedPose;
1247 Pose2Vector::const_iterator meansIter = rMeans.begin();
1250 Pose2 pose = *meansIter;
1252 thetaX += cos(angle);
1253 thetaY += sin(angle);
1255 Matrix3 weight = inverseOfSumOfInverses * (*iter);
1256 accumulatedPose += weight * pose;
1261 thetaX /= rMeans.size();
1262 thetaY /= rMeans.size();
1263 accumulatedPose.
SetHeading(atan2(thetaY, thetaX));
1265 return accumulatedPose;
1269 const Name& rSensorName,
1282 for (; rStartNum < nScans; rStartNum++)
1292 if (find(nearLinkedScans.begin(), nearLinkedScans.end(), pCandidateScan) != nearLinkedScans.end())
1298 chain.push_back(pCandidateScan);
1322 if (pSolver != NULL)
1344 , m_Initialized(false)
1345 , m_pSequentialScanMatcher(NULL)
1346 , m_pMapperSensorManager(NULL)
1348 , m_pScanOptimizer(NULL)
1358 , m_Initialized(false)
1359 , m_pSequentialScanMatcher(NULL)
1360 , m_pMapperSensorManager(NULL)
1362 , m_pScanOptimizer(NULL)
1381 "When set to true, the mapper will use a scan matching algorithm. "
1382 "In most real-world situations this should be set to true so that the "
1383 "mapper algorithm can correct for noise and errors in odometry and "
1384 "scan data. In some simulator environments where the simulated scan "
1385 "and odometry data are very accurate, the scan matching algorithm can "
1386 "produce worse results. In those cases set this to false to improve "
1392 "UseScanBarycenter",
1393 "Use the barycenter of scan endpoints to define distances between "
1398 "MinimumTimeInterval",
1399 "Sets the minimum time between scans. If a new scan's time stamp is "
1400 "longer than MinimumTimeInterval from the previously processed scan, "
1401 "the mapper will use the data from the new scan. Otherwise, it will "
1402 "discard the new scan if it also does not meet the minimum travel "
1403 "distance and heading requirements. For performance reasons, it is "
1404 "generally it is a good idea to only process scans if a reasonable "
1405 "amount of time has passed. This parameter is particularly useful "
1406 "when there is a need to process scans while the robot is stationary.",
1410 "MinimumTravelDistance",
1411 "Sets the minimum travel between scans. If a new scan's position is "
1412 "more than minimumTravelDistance from the previous scan, the mapper "
1413 "will use the data from the new scan. Otherwise, it will discard the "
1414 "new scan if it also does not meet the minimum change in heading "
1415 "requirement. For performance reasons, generally it is a good idea to "
1416 "only process scans if the robot has moved a reasonable amount.",
1420 "MinimumTravelHeading",
1421 "Sets the minimum heading change between scans. If a new scan's "
1422 "heading is more than MinimumTravelHeading from the previous scan, the "
1423 "mapper will use the data from the new scan. Otherwise, it will "
1424 "discard the new scan if it also does not meet the minimum travel "
1425 "distance requirement. For performance reasons, generally it is a good "
1426 "idea to only process scans if the robot has moved a reasonable "
1432 "Scan buffer size is the length of the scan chain stored for scan "
1433 "matching. \"ScanBufferSize\" should be set to approximately "
1434 "\"ScanBufferMaximumScanDistance\" / \"MinimumTravelDistance\". The "
1435 "idea is to get an area approximately 20 meters long for scan "
1436 "matching. For example, if we add scans every MinimumTravelDistance == "
1437 "0.3 meters, then \"scanBufferSize\" should be 20 / 0.3 = 67.)",
1441 "ScanBufferMaximumScanDistance",
1442 "Scan buffer maximum scan distance is the maximum distance between the "
1443 "first and last scans in the scan chain stored for matching.",
1447 "LinkMatchMinimumResponseFine",
1448 "Scans are linked only if the correlation response value is greater "
1453 "LinkScanMaximumDistance",
1454 "Maximum distance between linked scans. Scans that are farther apart "
1455 "will not be linked regardless of the correlation response value.",
1459 "LoopSearchMaximumDistance",
1460 "Scans less than this distance from the current position will be "
1461 "considered for a match in loop closure.",
1466 "Enable/disable loop closure.",
1470 "LoopMatchMinimumChainSize",
1471 "When the loop closure detection finds a candidate it must be part of "
1472 "a large set of linked scans. If the chain of scans is less than this "
1473 "value we do not attempt to close the loop.",
1477 "LoopMatchMaximumVarianceCoarse",
1478 "The co-variance values for a possible loop closure have to be less "
1479 "than this value to consider a viable solution. This applies to the "
1484 "LoopMatchMinimumResponseCoarse",
1485 "If response is larger then this, then initiate loop closure search at "
1486 "the coarse resolution.",
1490 "LoopMatchMinimumResponseFine",
1491 "If response is larger then this, then initiate loop closure search at "
1492 "the fine resolution.",
1499 "CorrelationSearchSpaceDimension",
1500 "The size of the search grid used by the matcher. The search grid will "
1501 "have the size CorrelationSearchSpaceDimension * "
1502 "CorrelationSearchSpaceDimension",
1506 "CorrelationSearchSpaceResolution",
1507 "The resolution (size of a grid cell) of the correlation grid.",
1511 "CorrelationSearchSpaceSmearDeviation",
1512 "The point readings are smeared by this value in X and Y to create a "
1513 "smoother response.",
1521 "LoopSearchSpaceDimension",
1522 "The size of the search grid used by the matcher.",
1526 "LoopSearchSpaceResolution",
1527 "The resolution (size of a grid cell) of the correlation grid.",
1531 "LoopSearchSpaceSmearDeviation",
1532 "The point readings are smeared by this value in X and Y to create a "
1533 "smoother response.",
1540 "DistanceVariancePenalty",
1541 "Variance of penalty for deviating from odometry when scan-matching. "
1542 "The penalty is a multiplier (less than 1.0) is a function of the "
1543 "delta of the scan position being tested and the odometric pose.",
1547 "AngleVariancePenalty",
1548 "See DistanceVariancePenalty.",
1552 "FineSearchAngleOffset",
1553 "The range of angles to search during a fine search.",
1557 "CoarseSearchAngleOffset",
1558 "The range of angles to search during a coarse search.",
1562 "CoarseAngleResolution",
1563 "Resolution of angles to search during a coarse search.",
1567 "MinimumAnglePenalty",
1568 "Minimum value of the angle penalty multiplier so scores do not become "
1573 "MinimumDistancePenalty",
1574 "Minimum value of the distance penalty multiplier so scores do not "
1575 "become too small.",
1579 "UseResponseExpansion",
1580 "Whether to increase the search space if no good matches are initially "
1940 if (pLaserRangeFinder == NULL || pScan == NULL || pLaserRangeFinder->
Validate(pScan) ==
false)
1955 if (pLastScan != NULL)
2019 if (pLastScan == NULL)
2082 std::vector<MapperListener*>::iterator iter = std::find(
m_Listeners.begin(),
m_Listeners.end(), pListener);
2093 (*iter)->Info(rInfo);
2103 if (pListener != NULL)
2105 pListener->
Debug(rInfo);
2116 if (pListener != NULL)
2129 if (pListener != NULL)
2142 if (pListener != NULL)