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());
121 delete m_pCorrelationGrid;
122 delete m_pSearchSpaceProbs;
123 delete m_pGridLookup;
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);
202 rCovariance(2, 2) = 4 *
math::Square(m_pMapper->m_pCoarseAngleResolution->GetValue());
212 offset.
SetX(scanPose.
GetX() - (0.5 * (roi.
GetWidth() - 1) * m_pCorrelationGrid->GetResolution()));
213 offset.
SetY(scanPose.
GetY() - (0.5 * (roi.
GetHeight() - 1) * m_pCorrelationGrid->GetResolution()));
216 m_pCorrelationGrid->GetCoordinateConverter()->SetOffset(offset);
224 Vector2<kt_double> searchDimensions(m_pSearchSpaceProbs->GetWidth(), m_pSearchSpaceProbs->GetHeight());
225 Vector2<kt_double> coarseSearchOffset(0.5 * (searchDimensions.GetX() - 1) * m_pCorrelationGrid->GetResolution(),
226 0.5 * (searchDimensions.GetY() - 1) * m_pCorrelationGrid->GetResolution());
230 2 * m_pCorrelationGrid->GetResolution());
233 kt_double bestResponse = CorrelateScan(pScan, scanPose, coarseSearchOffset, coarseSearchResolution,
234 m_pMapper->m_pCoarseSearchAngleOffset->GetValue(),
235 m_pMapper->m_pCoarseAngleResolution->GetValue(),
236 doPenalize, rMean, rCovariance,
false);
238 if (m_pMapper->m_pUseResponseExpansion->GetValue() ==
true)
243 std::cout <<
"Mapper Info: Expanding response search space!" << std::endl;
246 kt_double newSearchAngleOffset = m_pMapper->m_pCoarseSearchAngleOffset->GetValue();
251 bestResponse = CorrelateScan(pScan, scanPose, coarseSearchOffset, coarseSearchResolution,
252 newSearchAngleOffset, m_pMapper->m_pCoarseAngleResolution->GetValue(),
253 doPenalize, rMean, rCovariance,
false);
264 std::cout <<
"Mapper Warning: Unable to calculate response!" << std::endl;
273 Vector2<kt_double> fineSearchResolution(m_pCorrelationGrid->GetResolution(), m_pCorrelationGrid->GetResolution());
274 bestResponse = CorrelateScan(pScan, rMean, fineSearchOffset, fineSearchResolution,
275 0.5 * m_pMapper->m_pCoarseAngleResolution->GetValue(),
276 m_pMapper->m_pFineSearchAngleOffset->GetValue(),
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);
314 m_pGridLookup->ComputeOffsets(pScan, rSearchCenter.
GetHeading(), searchAngleOffset, searchAngleResolution);
319 m_pSearchSpaceProbs->Clear();
323 m_pSearchSpaceProbs->GetCoordinateConverter()->SetOffset(offset);
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)
373 kt_int32s gridIndex = m_pCorrelationGrid->GridIndex(gridPoint);
374 assert(gridIndex >= 0);
378 for (
kt_int32u angleIndex = 0; angleIndex < nAngles; angleIndex++)
380 angle = startAngle + angleIndex * searchAngleResolution;
387 kt_double squaredDistance = squareX + squareY;
389 squaredDistance / m_pMapper->m_pDistanceVariancePenalty->GetValue());
390 distancePenalty =
math::Maximum(distancePenalty, m_pMapper->m_pMinimumDistancePenalty->GetValue());
394 squaredAngleDistance / m_pMapper->m_pAngleVariancePenalty->GetValue());
395 anglePenalty =
math::Maximum(anglePenalty, m_pMapper->m_pMinimumAnglePenalty->GetValue());
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;
425 kt_double* ptr =
reinterpret_cast<kt_double*
>(m_pSearchSpaceProbs->GetDataPointer(grid));
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;
479 ComputePositionalCovariance(averagePose, bestResponse, rSearchCenter, rSearchSpaceOffset,
480 rSearchSpaceResolution, searchAngleResolution, rCovariance);
484 ComputeAngularCovariance(averagePose, bestResponse, rSearchCenter,
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))
569 accumulatedVarianceXX += (
math::Square(x - dx) * response);
570 accumulatedVarianceXY += ((x - dx) * (y - dy) * response);
571 accumulatedVarianceYY += (
math::Square(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,
634 kt_int32s gridIndex = m_pCorrelationGrid->GridIndex(gridPoint);
643 for (
kt_int32u angleIndex = 0; angleIndex < nAngles; angleIndex++)
645 angle = startAngle + angleIndex * searchAngleResolution;
649 if (response >= (bestResponse - 0.1))
652 accumulatedVarianceThTh += (
math::Square(angle - bestAngle) * response);
661 accumulatedVarianceThTh =
math::Square(searchAngleResolution);
664 accumulatedVarianceThTh /= norm;
668 accumulatedVarianceThTh = 1000 *
math::Square(searchAngleResolution);
671 rCovariance(2, 2) = accumulatedVarianceThTh;
681 m_pCorrelationGrid->Clear();
704 if (!
math::IsUpTo(gridPoint.
GetX(), m_pCorrelationGrid->GetROI().GetWidth()) ||
711 int gridIndex = m_pCorrelationGrid->GridIndex(gridPoint);
725 m_pCorrelationGrid->SmearPoint(gridPoint);
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);
804 kt_int8u* pByte = m_pCorrelationGrid->GetDataPointer() + gridPositionIndex;
806 const LookupArray* pOffsets = m_pGridLookup->GetLookupArray(angleIndex);
807 assert(pOffsets != NULL);
821 kt_int32s pointGridIndex = gridPositionIndex + pAngleIndexPointer[i];
828 response += pByte[pAngleIndexPointer[i]];
833 assert(fabs(response) <= 1.0);
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)
974 tmpScan.SetTime(pScan->
GetTime());
977 tmpScan.SetSensorPose(bestPose);
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)
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)
1957 Transform lastTransform(pLastScan->GetOdometricPose(), pLastScan->GetCorrectedPose());
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)
std::vector< LocalizedRangeScanVector > FindNearChains(LocalizedRangeScan *pScan)
virtual kt_bool Process(LocalizedRangeScan *pScan)
std::map< Name, ScanManager * > ScanManagerMap
void InitializeParameters()
LaserRangeFinder * GetLaserRangeFinder() const
ScanMatcher * m_pSequentialScanMatcher
void RemoveListener(MapperListener *pListener)
double getParamMinimumAnglePenalty()
double getParamLinkScanMaximumDistance()
#define DISTANCE_PENALTY_GAIN
bool getParamDoLoopClosing()
virtual kt_bool Validate()
void setParamCorrelationSearchSpaceResolution(double d)
void FireEndLoopClosure(const std::string &rInfo) const
void setParamLoopMatchMinimumChainSize(int i)
const kt_int32s INVALID_SCAN
Parameter< kt_double > * m_pLinkScanMaximumDistance
kt_double Round(kt_double value)
void LinkNearChains(LocalizedRangeScan *pScan, Pose2Vector &rMeans, std::vector< Matrix3 > &rCovariances)
virtual void AddNode(Vertex< LocalizedRangeScan > *)
void SetUniqueId(kt_int32u uniqueId)
Parameter< kt_double > * m_pCoarseAngleResolution
Pose2 GetSensorPose() const
kt_int32s GetStateId() const
virtual ScanMatcher * GetLoopScanMatcher() const
const Pose2 & GetOdometricPose() const
Parameter< kt_double > * m_pLoopMatchMaximumVarianceCoarse
std::vector< Vector2< kt_double > > PointVectorDouble
Parameter< kt_double > * m_pMinimumTravelHeading
virtual void EndLoopClosure(const std::string &)
void SetValue(const T &rValue)
void setParamUseScanMatching(bool b)
#define forEachAs(listtype, list, iter)
void AddEdge(Edge< T > *pEdge)
int getParamLoopMatchMinimumChainSize()
void ComputeAngularCovariance(const Pose2 &rBestPose, kt_double bestResponse, const Pose2 &rSearchCenter, kt_double searchAngleOffset, kt_double searchAngleResolution, Matrix3 &rCovariance)
Parameter< kt_double > * m_pMinimumAnglePenalty
std::vector< MapperListener * > m_Listeners
LocalizedRangeScanVector & GetScans()
double getParamCoarseSearchAngleOffset()
void FireBeginLoopClosure(const std::string &rInfo) const
kt_int32s * GetArrayPointer()
const Pose2 & GetCorrectedPose() const
kt_int32u GetNumberOfRangeReadings() const
const Vector2< kt_double > & GetPosition() const
const T & Maximum(const T &value1, const T &value2)
kt_double DegreesToRadians(kt_double degrees)
double getParamCoarseAngleResolution()
std::vector< Name > GetSensorNames()
double getParamMinimumDistancePenalty()
virtual void LoopClosureCheck(const std::string &)
Parameter< kt_double > * m_pLoopSearchSpaceSmearDeviation
kt_int32u GetSize() const
void setParamDoLoopClosing(bool b)
const PointVectorDouble & GetPointReadings(kt_bool wantFiltered=false) const
void AddVertex(LocalizedRangeScan *pScan)
Parameter< kt_int32u > * m_pLoopMatchMinimumChainSize
void setParamCorrelationSearchSpaceSmearDeviation(double d)
Parameter< kt_double > * m_pCorrelationSearchSpaceResolution
void Initialize(kt_double rangeThreshold)
double getParamMinimumTimeInterval()
Parameter< kt_double > * m_pMinimumDistancePenalty
void setParamDistanceVariancePenalty(double d)
void AddVertex(const Name &rName, Vertex< T > *pVertex)
void ComputePositionalCovariance(const Pose2 &rBestPose, kt_double bestResponse, const Pose2 &rSearchCenter, const Vector2< kt_double > &rSearchSpaceOffset, const Vector2< kt_double > &rSearchSpaceResolution, kt_double searchAngleResolution, Matrix3 &rCovariance)
virtual void AddConstraint(Edge< LocalizedRangeScan > *)
Parameter< kt_double > * m_pDistanceVariancePenalty
Parameter< kt_bool > * m_pUseScanMatching
Vertex< T > * GetTarget() const
Pose2 ComputeWeightedMean(const Pose2Vector &rMeans, const std::vector< Matrix3 > &rCovariances) const
#define forEach(listtype, list)
void setParamScanBufferSize(int i)
void AddScan(LocalizedRangeScan *pScan)
void setParamCorrelationSearchSpaceDimension(double d)
void SetSensorPose(const Pose2 &rScanPose)
Pose2 GetSensorAt(const Pose2 &rPose) const
void setParamMinimumTimeInterval(double d)
kt_double GetResponse(kt_int32u angleIndex, kt_int32s gridPositionIndex) const
void SetLastScan(LocalizedRangeScan *pScan)
kt_int32s GetUniqueId() const
#define ANGLE_PENALTY_GAIN
void LinkChainToScan(const LocalizedRangeScanVector &rChain, LocalizedRangeScan *pScan, const Pose2 &rMean, const Matrix3 &rCovariance)
LocalizedRangeScanVector & GetScans(const Name &rSensorName)
double getParamLoopMatchMinimumResponseCoarse()
void LinkScans(LocalizedRangeScan *pFromScan, LocalizedRangeScan *pToScan, const Pose2 &rMean, const Matrix3 &rCovariance)
MapperSensorManager * m_pMapperSensorManager
kt_int32u m_RunningBufferMaximumSize
GraphTraversal< LocalizedRangeScan > * m_pTraversal
double getParamLoopMatchMinimumResponseFine()
Parameter< kt_bool > * m_pDoLoopClosing
virtual ScanMatcher * GetSequentialScanMatcher() const
void setParamAngleVariancePenalty(double d)
Parameter< kt_double > * m_pFineSearchAngleOffset
LocalizedRangeScan * GetClosestScanToPose(const LocalizedRangeScanVector &rScans, const Pose2 &rPose) const
kt_double SquaredLength() const
kt_double RadiansToDegrees(kt_double radians)
Parameter< kt_double > * m_pScanBufferMaximumScanDistance
ScanSolver * m_pScanOptimizer
void setParamLoopMatchMaximumVarianceCoarse(double d)
virtual void Debug(const std::string &)
void AddListener(MapperListener *pListener)
Parameter< kt_double > * m_pLoopSearchSpaceDimension
void setParamLinkScanMaximumDistance(double d)
kt_double SquaredDistance(const Vector2 &rOther) const
void setParamMinimumAnglePenalty(double d)
kt_double MatchScan(LocalizedRangeScan *pScan, const LocalizedRangeScanVector &rBaseScans, Pose2 &rMean, Matrix3 &rCovariance, kt_bool doPenalize=true, kt_bool doRefineMatch=true)
kt_double GetRangeThreshold() const
virtual MapperGraph * GetGraph() const
virtual ParameterManager * GetParameterManager()
const Name & GetSensorName() const
virtual const IdPoseVector & GetCorrections() const =0
LocalizedRangeScan * GetLastScan(const Name &rSensorName)
double getParamCorrelationSearchSpaceSmearDeviation()
Parameter< kt_double > * m_pMinimumTravelDistance
void AddRunningScan(LocalizedRangeScan *pScan)
RangeReadingsVector GetRangeReadingsVector() const
double getParamMinimumTravelHeading()
void setParamLoopSearchSpaceDimension(double d)
void setParamLoopSearchSpaceResolution(double d)
static Grid * CreateGrid(kt_int32s width, kt_int32s height, kt_double resolution)
void setParamScanBufferMaximumScanDistance(double d)
void setParamMinimumDistancePenalty(double d)
double getParamMinimumTravelDistance()
std::vector< Pose2 > Pose2Vector
double getParamLoopSearchSpaceSmearDeviation()
ScanMatcher * GetLoopScanMatcher() const
double getParamFineSearchAngleOffset()
void setParamLoopSearchMaximumDistance(double d)
const T & GetValue() const
void setParamLoopMatchMinimumResponseCoarse(double d)
kt_bool HasMovedEnough(LocalizedRangeScan *pScan, LocalizedRangeScan *pLastScan) const
PointVectorDouble FindValidPoints(LocalizedRangeScan *pScan, const Vector2< kt_double > &rViewPoint) const
bool getParamUseScanBarycenter()
void FireDebug(const std::string &rInfo) const
kt_bool InRange(const T &value, const T &a, const T &b)
void AddScan(LocalizedRangeScan *pScan, kt_int32s uniqueId)
kt_double m_RunningBufferMaximumDistance
void setParamMinimumTravelDistance(double d)
const kt_double KT_TOLERANCE
kt_double NormalizeAngle(kt_double angle)
LocalizedRangeScan * GetScan(const Name &rSensorName, kt_int32s scanIndex)
bool getParamUseScanMatching()
#define const_forEach(listtype, list)
double getParamScanBufferMaximumScanDistance()
void SetScanSolver(ScanSolver *pSolver)
virtual void BeginLoopClosure(const std::string &)
LocalizedRangeScanVector FindPossibleLoopClosure(LocalizedRangeScan *pScan, const Name &rSensorName, kt_int32u &rStartNum)
int getParamScanBufferSize()
bool getParamUseResponseExpansion()
double getParamCorrelationSearchSpaceDimension()
GridIndexLookup< kt_int8u > * m_pGridLookup
Pose2 GetReferencePose(kt_bool useBarycenter) const
static CorrelationGrid * CreateGrid(kt_int32s width, kt_int32s height, kt_double resolution, kt_double smearDeviation)
kt_double GetTime() const
void AddScans(const LocalizedRangeScanVector &rScans, Vector2< kt_double > viewPoint)
kt_double NormalizeAngleDifference(kt_double minuend, kt_double subtrahend)
void AddScan(LocalizedRangeScan *pScan, const Vector2< kt_double > &rViewPoint, kt_bool doSmear=true)
void setParamLinkMatchMinimumResponseFine(double d)
CorrelationGrid * m_pCorrelationGrid
kt_double CorrelateScan(LocalizedRangeScan *pScan, const Pose2 &rSearchCenter, const Vector2< kt_double > &rSearchSpaceOffset, const Vector2< kt_double > &rSearchSpaceResolution, kt_double searchAngleOffset, kt_double searchAngleResolution, kt_bool doPenalize, Pose2 &rMean, Matrix3 &rCovariance, kt_bool doingFineMatch)
Parameter< kt_double > * m_pLoopSearchSpaceResolution
Parameter< kt_double > * m_pCorrelationSearchSpaceDimension
void setParamCoarseSearchAngleOffset(double d)
double getParamDistanceVariancePenalty()
double getParamCorrelationSearchSpaceResolution()
void RegisterSensor(const Name &rSensorName)
std::vector< std::pair< kt_int32s, Pose2 > > IdPoseVector
void SetCorrectedPose(const Pose2 &rPose)
LocalizedRangeScanVector GetAllScans()
void setParamFineSearchAngleOffset(double d)
LocalizedRangeScanVector & GetRunningScans(const Name &rSensorName)
Parameter< kt_double > * m_pLinkMatchMinimumResponseFine
Vertex< LocalizedRangeScan > * GetVertex(LocalizedRangeScan *pScan)
void FireInfo(const std::string &rInfo) const
double getParamAngleVariancePenalty()
static ScanMatcher * Create(Mapper *pMapper, kt_double searchSize, kt_double resolution, kt_double smearDeviation, kt_double rangeThreshold)
ScanMatcher * m_pLoopScanMatcher
void SetLabel(EdgeLabel *pLabel)
ScanManagerMap m_ScanManagers
Grid< kt_double > * m_pSearchSpaceProbs
kt_bool DoubleEqual(kt_double a, kt_double b)
Edge< LocalizedRangeScan > * AddEdge(LocalizedRangeScan *pSourceScan, LocalizedRangeScan *pTargetScan, kt_bool &rIsNewEdge)
void SetHeading(kt_double heading)
LocalizedRangeScanVector FindNearLinkedScans(LocalizedRangeScan *pScan, kt_double maxDistance)
double getParamLoopSearchSpaceResolution()
Parameter< kt_double > * m_pCorrelationSearchSpaceSmearDeviation
void setParamMinimumTravelHeading(double d)
void AddEdges(LocalizedRangeScan *pScan, const Matrix3 &rCovariance)
double getParamLoopSearchMaximumDistance()
void setParamUseResponseExpansion(bool b)
Parameter< kt_double > * m_pLoopMatchMinimumResponseCoarse
void FireLoopClosureCheck(const std::string &rInfo) const
double getParamLoopMatchMaximumVarianceCoarse()
kt_bool TryCloseLoop(LocalizedRangeScan *pScan, const Name &rSensorName)
double getParamLinkMatchMinimumResponseFine()
std::vector< LocalizedRangeScan * > m_Scans
Parameter< kt_double > * m_pCoarseSearchAngleOffset
void setParamLoopMatchMinimumResponseFine(double d)
Parameter< kt_double > * m_pLoopSearchMaximumDistance
void setParamUseScanBarycenter(bool b)
Parameter< kt_double > * m_pAngleVariancePenalty
MapperGraph(Mapper *pMapper, kt_double rangeThreshold)
double getParamLoopSearchSpaceDimension()
Parameter< kt_double > * m_pMinimumTimeInterval
Parameter< kt_bool > * m_pUseResponseExpansion
Parameter< kt_int32u > * m_pScanBufferSize
virtual const LocalizedRangeScanVector GetAllProcessedScans() const
kt_bool IsUpTo(const T &value, const T &maximum)
const std::string response
void setParamLoopSearchSpaceSmearDeviation(double d)
ScanManager * GetScanManager(LocalizedRangeScan *pScan)
std::vector< LocalizedRangeScan * > LocalizedRangeScanVector
Parameter< kt_bool > * m_pUseScanBarycenter
Parameter< kt_double > * m_pLoopMatchMinimumResponseFine
void setParamCoarseAngleResolution(double d)
kt_double GetHeading() const