37 #define MAX_VARIANCE 500.0 38 #define DISTANCE_PENALTY_GAIN 0.2 39 #define ANGLE_PENALTY_GAIN 0.2 174 if (GetScanManager(rSensorName) == NULL)
189 ScanManager* pScanManager = GetScanManager(rSensorName);
190 if (pScanManager != NULL)
192 return pScanManager->
GetScans().at(scanIndex);
206 RegisterSensor(rSensorName);
208 return GetScanManager(rSensorName)->GetLastScan();
217 GetScanManager(pScan)->SetLastScan(pScan);
226 GetScanManager(pScan)->AddScan(pScan, m_NextScanId);
237 GetScanManager(pScan)->AddRunningScan(pScan);
247 return GetScanManager(rSensorName)->GetScans();
257 return GetScanManager(rSensorName)->GetRunningScans();
272 scans.insert(scans.end(), rScans.begin(), rScans.end());
290 m_ScanManagers.clear();
299 delete m_pCorrelationGrid;
300 delete m_pSearchSpaceProbs;
301 delete m_pGridLookup;
316 if (smearDeviation < 0)
320 if (rangeThreshold <= 0)
332 kt_int32u pointReadingMargin =
static_cast<kt_int32u>(ceil(rangeThreshold / resolution));
334 kt_int32s gridSize = searchSpaceSideSize + 2 * pointReadingMargin;
337 assert(gridSize % 2 == 1);
342 searchSpaceSideSize, resolution);
380 rCovariance(2, 2) = 4 *
math::Square(m_pMapper->m_pCoarseAngleResolution->GetValue());
390 offset.
SetX(scanPose.
GetX() - (0.5 * (roi.
GetWidth() - 1) * m_pCorrelationGrid->GetResolution()));
391 offset.
SetY(scanPose.
GetY() - (0.5 * (roi.
GetHeight() - 1) * m_pCorrelationGrid->GetResolution()));
394 m_pCorrelationGrid->GetCoordinateConverter()->SetOffset(offset);
402 Vector2<kt_double> searchDimensions(m_pSearchSpaceProbs->GetWidth(), m_pSearchSpaceProbs->GetHeight());
403 Vector2<kt_double> coarseSearchOffset(0.5 * (searchDimensions.GetX() - 1) * m_pCorrelationGrid->GetResolution(),
404 0.5 * (searchDimensions.GetY() - 1) * m_pCorrelationGrid->GetResolution());
408 2 * m_pCorrelationGrid->GetResolution());
411 kt_double bestResponse = CorrelateScan(pScan, scanPose, coarseSearchOffset, coarseSearchResolution,
412 m_pMapper->m_pCoarseSearchAngleOffset->GetValue(),
413 m_pMapper->m_pCoarseAngleResolution->GetValue(),
414 doPenalize, rMean, rCovariance,
false);
416 if (m_pMapper->m_pUseResponseExpansion->GetValue() ==
true)
421 std::cout <<
"Mapper Info: Expanding response search space!" << std::endl;
424 kt_double newSearchAngleOffset = m_pMapper->m_pCoarseSearchAngleOffset->GetValue();
429 bestResponse = CorrelateScan(pScan, scanPose, coarseSearchOffset, coarseSearchResolution,
430 newSearchAngleOffset, m_pMapper->m_pCoarseAngleResolution->GetValue(),
431 doPenalize, rMean, rCovariance,
false);
442 std::cout <<
"Mapper Warning: Unable to calculate response!" << std::endl;
451 Vector2<kt_double> fineSearchResolution(m_pCorrelationGrid->GetResolution(), m_pCorrelationGrid->GetResolution());
452 bestResponse = CorrelateScan(pScan, rMean, fineSearchOffset, fineSearchResolution,
453 0.5 * m_pMapper->m_pCoarseAngleResolution->GetValue(),
454 m_pMapper->m_pFineSearchAngleOffset->GetValue(),
455 doPenalize, rMean, rCovariance,
true);
459 std::cout <<
" BEST POSE = " << rMean <<
" BEST RESPONSE = " << bestResponse <<
", VARIANCE = " 460 << rCovariance(0, 0) <<
", " << rCovariance(1, 1) << std::endl;
489 assert(searchAngleResolution != 0.0);
492 m_pGridLookup->ComputeOffsets(pScan, rSearchCenter.
GetHeading(), searchAngleOffset, searchAngleResolution);
497 m_pSearchSpaceProbs->Clear();
501 m_pSearchSpaceProbs->GetCoordinateConverter()->SetOffset(offset);
506 std::vector<kt_double> xPoses;
508 2.0 / rSearchSpaceResolution.
GetX()) + 1);
510 for (
kt_int32u xIndex = 0; xIndex < nX; xIndex++)
512 xPoses.push_back(startX + xIndex * rSearchSpaceResolution.
GetX());
516 std::vector<kt_double> yPoses;
518 2.0 / rSearchSpaceResolution.
GetY()) + 1);
520 for (
kt_int32u yIndex = 0; yIndex < nY; yIndex++)
522 yPoses.push_back(startY + yIndex * rSearchSpaceResolution.
GetY());
529 kt_int32u poseResponseSize =
static_cast<kt_int32u>(xPoses.size() * yPoses.size() * nAngles);
532 std::pair<kt_double, Pose2>* pPoseResponse =
new std::pair<kt_double, Pose2>[poseResponseSize];
535 + startX, rSearchCenter.
GetY() + startY));
538 forEachAs(std::vector<kt_double>, &yPoses, yIter)
544 forEachAs(std::vector<kt_double>, &xPoses, xIter)
551 kt_int32s gridIndex = m_pCorrelationGrid->GridIndex(gridPoint);
552 assert(gridIndex >= 0);
556 for (
kt_int32u angleIndex = 0; angleIndex < nAngles; angleIndex++)
558 angle = startAngle + angleIndex * searchAngleResolution;
560 kt_double response = GetResponse(angleIndex, gridIndex);
565 kt_double squaredDistance = squareX + squareY;
567 squaredDistance / m_pMapper->m_pDistanceVariancePenalty->GetValue());
568 distancePenalty =
math::Maximum(distancePenalty, m_pMapper->m_pMinimumDistancePenalty->GetValue());
572 squaredAngleDistance / m_pMapper->m_pAngleVariancePenalty->GetValue());
573 anglePenalty =
math::Maximum(anglePenalty, m_pMapper->m_pMinimumAnglePenalty->GetValue());
575 response *= (distancePenalty * anglePenalty);
579 pPoseResponse[poseResponseCounter] = std::pair<kt_double, Pose2>(response,
Pose2(newPositionX, newPositionY,
581 poseResponseCounter++;
588 assert(poseResponseSize == poseResponseCounter);
592 for (
kt_int32u i = 0; i < poseResponseSize; i++)
594 bestResponse =
math::Maximum(bestResponse, pPoseResponse[i].first);
599 const Pose2& rPose = pPoseResponse[i].second;
603 kt_double* ptr =
reinterpret_cast<kt_double*
>(m_pSearchSpaceProbs->GetDataPointer(grid));
606 throw std::runtime_error(
"Mapper FATAL ERROR - Index out of range in probability search!");
618 for (
kt_int32u i = 0; i < poseResponseSize; i++)
622 averagePosition += pPoseResponse[i].second.GetPosition();
624 kt_double heading = pPoseResponse[i].second.GetHeading();
625 thetaX += cos(heading);
626 thetaY += sin(heading);
633 if (averagePoseCount > 0)
635 averagePosition /= averagePoseCount;
637 thetaX /= averagePoseCount;
638 thetaY /= averagePoseCount;
640 averagePose =
Pose2(averagePosition, atan2(thetaY, thetaX));
644 throw std::runtime_error(
"Mapper FATAL ERROR - Unable to find best position");
648 delete [] pPoseResponse;
651 std::cout <<
"bestPose: " << averagePose << std::endl;
652 std::cout <<
"bestResponse: " << bestResponse << std::endl;
657 ComputePositionalCovariance(averagePose, bestResponse, rSearchCenter, rSearchSpaceOffset,
658 rSearchSpaceResolution, searchAngleResolution, rCovariance);
662 ComputeAngularCovariance(averagePose, bestResponse, rSearchCenter,
663 searchAngleOffset, searchAngleResolution, rCovariance);
669 std::cout <<
"bestPose: " << averagePose << std::endl;
672 if (bestResponse > 1.0)
694 const Pose2& rSearchCenter,
707 rCovariance(2, 2) = 4 *
math::Square(searchAngleResolution);
731 for (
kt_int32u yIndex = 0; yIndex < nY; yIndex++)
733 kt_double y = startY + yIndex * rSearchSpaceResolution.
GetY();
735 for (
kt_int32u xIndex = 0; xIndex < nX; xIndex++)
737 kt_double x = startX + xIndex * rSearchSpaceResolution.
GetX();
740 rSearchCenter.
GetY() + y));
741 kt_double response = *(m_pSearchSpaceProbs->GetDataPointer(gridPoint));
744 if (response >= (bestResponse - 0.1))
747 accumulatedVarianceXX += (
math::Square(x - dx) * response);
748 accumulatedVarianceXY += ((x - dx) * (y - dy) * response);
749 accumulatedVarianceYY += (
math::Square(y - dy) * response);
756 kt_double varianceXX = accumulatedVarianceXX / norm;
757 kt_double varianceXY = accumulatedVarianceXY / norm;
758 kt_double varianceYY = accumulatedVarianceYY / norm;
769 kt_double multiplier = 1.0 / bestResponse;
770 rCovariance(0, 0) = varianceXX * multiplier;
771 rCovariance(0, 1) = varianceXY * multiplier;
772 rCovariance(1, 0) = varianceXY * multiplier;
773 rCovariance(1, 1) = varianceYY * multiplier;
774 rCovariance(2, 2) = varianceTHTH;
801 const Pose2& rSearchCenter,
812 kt_int32s gridIndex = m_pCorrelationGrid->GridIndex(gridPoint);
821 for (
kt_int32u angleIndex = 0; angleIndex < nAngles; angleIndex++)
823 angle = startAngle + angleIndex * searchAngleResolution;
824 kt_double response = GetResponse(angleIndex, gridIndex);
827 if (response >= (bestResponse - 0.1))
830 accumulatedVarianceThTh += (
math::Square(angle - bestAngle) * response);
839 accumulatedVarianceThTh =
math::Square(searchAngleResolution);
842 accumulatedVarianceThTh /= norm;
846 accumulatedVarianceThTh = 1000 *
math::Square(searchAngleResolution);
849 rCovariance(2, 2) = accumulatedVarianceThTh;
859 m_pCorrelationGrid->Clear();
882 if (!
math::IsUpTo(gridPoint.
GetX(), m_pCorrelationGrid->GetROI().GetWidth()) ||
889 int gridIndex = m_pCorrelationGrid->GridIndex(gridPoint);
903 m_pCorrelationGrid->SmearPoint(gridPoint);
923 PointVectorDouble::const_iterator trailingPointIter = rPointReadings.begin();
932 if (firstTime && !std::isnan(currentPoint.
GetX()) && !std::isnan(currentPoint.
GetY()))
934 firstPoint = currentPoint;
946 double a = rViewPoint.
GetY() - firstPoint.
GetY();
947 double b = firstPoint.
GetX() - rViewPoint.
GetX();
948 double c = firstPoint.
GetY() * rViewPoint.
GetX() - firstPoint.
GetX() * rViewPoint.
GetY();
949 double ss = currentPoint.GetX() * a + currentPoint.GetY() * b + c;
952 firstPoint = currentPoint;
956 trailingPointIter = iter;
960 for (; trailingPointIter != iter; ++trailingPointIter)
962 validPoints.push_back(*trailingPointIter);
982 kt_int8u* pByte = m_pCorrelationGrid->GetDataPointer() + gridPositionIndex;
984 const LookupArray* pOffsets = m_pGridLookup->GetLookupArray(angleIndex);
985 assert(pOffsets != NULL);
999 kt_int32s pointGridIndex = gridPositionIndex + pAngleIndexPointer[i];
1006 response += pByte[pAngleIndexPointer[i]];
1011 assert(fabs(response) <= 1.0);
1021 template<
typename T>
1049 std::queue<Vertex<T>*> toVisit;
1050 std::set<Vertex<T>*> seenVertices;
1051 std::vector<Vertex<T>*> validVertices;
1053 toVisit.push(pStartVertex);
1054 seenVertices.insert(pStartVertex);
1061 if (pVisitor->
Visit(pNext))
1064 validVertices.push_back(pNext);
1072 if (seenVertices.find(pAdjacent) == seenVertices.end())
1074 toVisit.push(pAdjacent);
1075 seenVertices.insert(pAdjacent);
1079 }
while (toVisit.empty() ==
false);
1081 std::vector<T*> objects;
1084 objects.push_back((*iter)->GetObject());
1099 : m_MaxDistanceSquared(math::
Square(maxDistance))
1100 , m_UseScanBarycenter(useScanBarycenter)
1112 return (squaredDistance <= m_MaxDistanceSquared -
KT_TOLERANCE);
1126 : m_pMapper(pMapper)
1168 if (pSensorManager->
GetLastScan(rSensorName) != NULL)
1170 assert(previousScanNum >= 0);
1175 std::vector<Matrix3> covariances;
1178 if (pSensorManager->
GetLastScan(rSensorName) == NULL)
1180 assert(pSensorManager->
GetScans(rSensorName).size() == 1);
1182 std::vector<Name> deviceNames = pSensorManager->
GetSensorNames();
1183 forEach(std::vector<Name>, &deviceNames)
1185 const Name& rCandidateSensorName = *iter;
1188 if ((rCandidateSensorName == rSensorName) || (pSensorManager->
GetScans(rCandidateSensorName).empty()))
1196 pSensorManager->
GetScans(rCandidateSensorName),
1197 bestPose, covariance);
1198 LinkScans(pScan, pSensorManager->
GetScan(rCandidateSensorName, 0), bestPose, covariance);
1203 means.push_back(bestPose);
1204 covariances.push_back(covariance);
1212 means.push_back(scanPose);
1213 covariances.push_back(rCovariance);
1234 while (!candidateChain.empty())
1239 bestPose, covariance,
false,
false);
1241 std::stringstream stream;
1242 stream <<
"COARSE RESPONSE: " << coarseResponse
1245 stream <<
" var: " << covariance(0, 0) <<
", " << covariance(1, 1)
1256 tmpScan.SetTime(pScan->
GetTime());
1259 tmpScan.SetSensorPose(bestPose);
1261 bestPose, covariance,
false);
1263 std::stringstream stream1;
1264 stream1 <<
"FINE RESPONSE: " << fineResponse <<
" (>" 1268 if (fineResponse < m_pMapper->m_pLoopMatchMinimumResponseFine->GetValue())
1293 const Pose2& rPose)
const 1296 kt_double bestSquaredDistance = DBL_MAX;
1303 if (squaredDistance < bestSquaredDistance)
1305 bestSquaredDistance = squaredDistance;
1306 pClosestScan = *iter;
1310 return pClosestScan;
1348 if (isNewEdge ==
true)
1360 const std::vector<LocalizedRangeScanVector> nearChains =
FindNearChains(pScan);
1361 const_forEach(std::vector<LocalizedRangeScanVector>, &nearChains)
1374 rMeans.push_back(mean);
1375 rCovariances.push_back(covariance);
1387 assert(pClosestScan != NULL);
1394 LinkScans(pClosestScan, pScan, rMean, rCovariance);
1400 std::vector<LocalizedRangeScanVector> nearChains;
1413 if (pNearScan == pScan)
1419 if (find(processed.begin(), processed.end(), pNearScan) != processed.end())
1424 processed.push_back(pNearScan);
1428 std::list<LocalizedRangeScan*> chain;
1431 for (
kt_int32s candidateScanNum = pNearScan->
GetStateId() - 1; candidateScanNum >= 0; candidateScanNum--)
1437 if (pCandidateScan == pScan)
1439 isValidChain =
false;
1447 chain.push_front(pCandidateScan);
1448 processed.push_back(pCandidateScan);
1456 chain.push_back(pNearScan);
1460 for (
kt_int32u candidateScanNum = pNearScan->
GetStateId() + 1; candidateScanNum < end; candidateScanNum++)
1465 if (pCandidateScan == pScan)
1467 isValidChain =
false;
1475 chain.push_back(pCandidateScan);
1476 processed.push_back(pCandidateScan);
1488 std::copy(chain.begin(), chain.end(), std::inserter(tempChain, tempChain.begin()));
1490 nearChains.push_back(tempChain);
1503 return nearLinkedScans;
1508 assert(rMeans.size() == rCovariances.size());
1511 std::vector<Matrix3> inverses;
1512 inverses.reserve(rCovariances.size());
1518 inverses.push_back(inverse);
1520 sumOfInverses += inverse;
1525 Pose2 accumulatedPose;
1529 Pose2Vector::const_iterator meansIter = rMeans.begin();
1532 Pose2 pose = *meansIter;
1534 thetaX += cos(angle);
1535 thetaY += sin(angle);
1537 Matrix3 weight = inverseOfSumOfInverses * (*iter);
1538 accumulatedPose += weight * pose;
1543 thetaX /= rMeans.size();
1544 thetaY /= rMeans.size();
1545 accumulatedPose.
SetHeading(atan2(thetaY, thetaX));
1547 return accumulatedPose;
1551 const Name& rSensorName,
1564 for (; rStartNum < nScans; rStartNum++)
1574 if (find(nearLinkedScans.begin(), nearLinkedScans.end(), pCandidateScan) != nearLinkedScans.end())
1580 chain.push_back(pCandidateScan);
1604 if (pSolver != NULL)
1626 , m_Initialized(false)
1627 , m_pSequentialScanMatcher(NULL)
1628 , m_pMapperSensorManager(NULL)
1630 , m_pScanOptimizer(NULL)
1663 "When set to true, the mapper will use a scan matching algorithm. " 1664 "In most real-world situations this should be set to true so that the " 1665 "mapper algorithm can correct for noise and errors in odometry and " 1666 "scan data. In some simulator environments where the simulated scan " 1667 "and odometry data are very accurate, the scan matching algorithm can " 1668 "produce worse results. In those cases set this to false to improve " 1674 "UseScanBarycenter",
1675 "Use the barycenter of scan endpoints to define distances between " 1680 "MinimumTimeInterval",
1681 "Sets the minimum time between scans. If a new scan's time stamp is " 1682 "longer than MinimumTimeInterval from the previously processed scan, " 1683 "the mapper will use the data from the new scan. Otherwise, it will " 1684 "discard the new scan if it also does not meet the minimum travel " 1685 "distance and heading requirements. For performance reasons, it is " 1686 "generally it is a good idea to only process scans if a reasonable " 1687 "amount of time has passed. This parameter is particularly useful " 1688 "when there is a need to process scans while the robot is stationary.",
1692 "MinimumTravelDistance",
1693 "Sets the minimum travel between scans. If a new scan's position is " 1694 "more than minimumTravelDistance from the previous scan, the mapper " 1695 "will use the data from the new scan. Otherwise, it will discard the " 1696 "new scan if it also does not meet the minimum change in heading " 1697 "requirement. For performance reasons, generally it is a good idea to " 1698 "only process scans if the robot has moved a reasonable amount.",
1702 "MinimumTravelHeading",
1703 "Sets the minimum heading change between scans. If a new scan's " 1704 "heading is more than MinimumTravelHeading from the previous scan, the " 1705 "mapper will use the data from the new scan. Otherwise, it will " 1706 "discard the new scan if it also does not meet the minimum travel " 1707 "distance requirement. For performance reasons, generally it is a good " 1708 "idea to only process scans if the robot has moved a reasonable " 1714 "Scan buffer size is the length of the scan chain stored for scan " 1715 "matching. \"ScanBufferSize\" should be set to approximately " 1716 "\"ScanBufferMaximumScanDistance\" / \"MinimumTravelDistance\". The " 1717 "idea is to get an area approximately 20 meters long for scan " 1718 "matching. For example, if we add scans every MinimumTravelDistance == " 1719 "0.3 meters, then \"scanBufferSize\" should be 20 / 0.3 = 67.)",
1723 "ScanBufferMaximumScanDistance",
1724 "Scan buffer maximum scan distance is the maximum distance between the " 1725 "first and last scans in the scan chain stored for matching.",
1729 "LinkMatchMinimumResponseFine",
1730 "Scans are linked only if the correlation response value is greater " 1735 "LinkScanMaximumDistance",
1736 "Maximum distance between linked scans. Scans that are farther apart " 1737 "will not be linked regardless of the correlation response value.",
1741 "LoopSearchMaximumDistance",
1742 "Scans less than this distance from the current position will be " 1743 "considered for a match in loop closure.",
1748 "Enable/disable loop closure.",
1752 "LoopMatchMinimumChainSize",
1753 "When the loop closure detection finds a candidate it must be part of " 1754 "a large set of linked scans. If the chain of scans is less than this " 1755 "value we do not attempt to close the loop.",
1759 "LoopMatchMaximumVarianceCoarse",
1760 "The co-variance values for a possible loop closure have to be less " 1761 "than this value to consider a viable solution. This applies to the " 1766 "LoopMatchMinimumResponseCoarse",
1767 "If response is larger then this, then initiate loop closure search at " 1768 "the coarse resolution.",
1772 "LoopMatchMinimumResponseFine",
1773 "If response is larger then this, then initiate loop closure search at " 1774 "the fine resolution.",
1781 "CorrelationSearchSpaceDimension",
1782 "The size of the search grid used by the matcher. The search grid will " 1783 "have the size CorrelationSearchSpaceDimension * " 1784 "CorrelationSearchSpaceDimension",
1788 "CorrelationSearchSpaceResolution",
1789 "The resolution (size of a grid cell) of the correlation grid.",
1793 "CorrelationSearchSpaceSmearDeviation",
1794 "The point readings are smeared by this value in X and Y to create a " 1795 "smoother response.",
1803 "LoopSearchSpaceDimension",
1804 "The size of the search grid used by the matcher.",
1808 "LoopSearchSpaceResolution",
1809 "The resolution (size of a grid cell) of the correlation grid.",
1813 "LoopSearchSpaceSmearDeviation",
1814 "The point readings are smeared by this value in X and Y to create a " 1815 "smoother response.",
1822 "DistanceVariancePenalty",
1823 "Variance of penalty for deviating from odometry when scan-matching. " 1824 "The penalty is a multiplier (less than 1.0) is a function of the " 1825 "delta of the scan position being tested and the odometric pose.",
1829 "AngleVariancePenalty",
1830 "See DistanceVariancePenalty.",
1834 "FineSearchAngleOffset",
1835 "The range of angles to search during a fine search.",
1839 "CoarseSearchAngleOffset",
1840 "The range of angles to search during a coarse search.",
1844 "CoarseAngleResolution",
1845 "Resolution of angles to search during a coarse search.",
1849 "MinimumAnglePenalty",
1850 "Minimum value of the angle penalty multiplier so scores do not become " 1855 "MinimumDistancePenalty",
1856 "Minimum value of the distance penalty multiplier so scores do not " 1857 "become too small.",
1861 "UseResponseExpansion",
1862 "Whether to increase the search space if no good matches are initially " 2222 if (pLaserRangeFinder == NULL || pScan == NULL || pLaserRangeFinder->
Validate(pScan) ==
false)
2237 if (pLastScan != NULL)
2239 Transform lastTransform(pLastScan->GetOdometricPose(), pLastScan->GetCorrectedPose());
2301 if (pLastScan == NULL)
2364 std::vector<MapperListener*>::iterator iter = std::find(
m_Listeners.begin(),
m_Listeners.end(), pListener);
2375 (*iter)->Info(rInfo);
2385 if (pListener != NULL)
2387 pListener->
Debug(rInfo);
2398 if (pListener != NULL)
2411 if (pListener != NULL)
2424 if (pListener != NULL)
std::vector< LocalizedRangeScanVector > FindNearChains(LocalizedRangeScan *pScan)
const Pose2 & GetOdometricPose() const
virtual kt_bool Process(LocalizedRangeScan *pScan)
std::map< Name, ScanManager * > ScanManagerMap
void InitializeParameters()
ScanMatcher * m_pSequentialScanMatcher
void RemoveListener(MapperListener *pListener)
double getParamMinimumAnglePenalty()
std::vector< Vertex< T > * > GetAdjacentVertices() const
double getParamLinkScanMaximumDistance()
kt_int32s GetStateId() const
RangeReadingsVector GetRangeReadingsVector() const
#define DISTANCE_PENALTY_GAIN
bool getParamDoLoopClosing()
virtual kt_bool Validate()
void setParamCorrelationSearchSpaceResolution(double d)
void setParamLoopMatchMinimumChainSize(int i)
const kt_int32s INVALID_SCAN
Parameter< kt_double > * m_pLinkScanMaximumDistance
kt_double GetHeading() const
kt_double Round(kt_double value)
const PointVectorDouble & GetPointReadings(kt_bool wantFiltered=false) const
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
NearScanVisitor(LocalizedRangeScan *pScan, kt_double maxDistance, kt_bool useScanBarycenter)
LocalizedRangeScanVector & GetScans(const Name &rSensorName)
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()
kt_bool m_UseScanBarycenter
void FireDebug(const std::string &rInfo) const
kt_int32s * GetArrayPointer()
const T & GetValue() const
kt_bool HasMovedEnough(LocalizedRangeScan *pScan, LocalizedRangeScan *pLastScan) const
Pose2 GetReferencePose(kt_bool useBarycenter) const
const T & Maximum(const T &value1, const T &value2)
kt_double DegreesToRadians(kt_double degrees)
double getParamCoarseAngleResolution()
std::vector< Name > GetSensorNames()
virtual ScanMatcher * GetSequentialScanMatcher() const
double getParamMinimumDistancePenalty()
virtual void LoopClosureCheck(const std::string &)
Parameter< kt_double > * m_pLoopSearchSpaceSmearDeviation
void setParamDoLoopClosing(bool b)
virtual kt_bool Visit(Vertex< LocalizedRangeScan > *pVertex)
void FireEndLoopClosure(const std::string &rInfo) 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
void SetStateId(kt_int32s stateId)
Parameter< kt_bool > * m_pUseScanMatching
LocalizedRangeScanVector & GetRunningScans(const Name &rSensorName)
#define forEach(listtype, list)
void setParamScanBufferSize(int i)
virtual ~BreadthFirstTraversal()
void AddScan(LocalizedRangeScan *pScan)
void setParamCorrelationSearchSpaceDimension(double d)
void SetSensorPose(const Pose2 &rScanPose)
LocalizedRangeScan * GetLastScan()
void setParamMinimumTimeInterval(double d)
void SetLastScan(LocalizedRangeScan *pScan)
LocalizedRangeScanVector m_RunningScans
#define ANGLE_PENALTY_GAIN
void LinkChainToScan(const LocalizedRangeScanVector &rChain, LocalizedRangeScan *pScan, const Pose2 &rMean, const Matrix3 &rCovariance)
double getParamLoopMatchMinimumResponseCoarse()
void LinkScans(LocalizedRangeScan *pFromScan, LocalizedRangeScan *pToScan, const Pose2 &rMean, const Matrix3 &rCovariance)
MapperSensorManager * m_pMapperSensorManager
GraphTraversal< LocalizedRangeScan > * m_pTraversal
double getParamLoopMatchMinimumResponseFine()
Parameter< kt_bool > * m_pDoLoopClosing
virtual kt_bool Visit(Vertex< T > *pVertex)=0
BreadthFirstTraversal(Graph< T > *pGraph)
void setParamAngleVariancePenalty(double d)
Parameter< kt_double > * m_pFineSearchAngleOffset
kt_int32u m_RunningBufferMaximumSize
kt_double RadiansToDegrees(kt_double radians)
Parameter< kt_double > * m_pScanBufferMaximumScanDistance
ScanSolver * m_pScanOptimizer
Pose2 GetSensorPose() const
void setParamLoopMatchMaximumVarianceCoarse(double d)
virtual void Debug(const std::string &)
void AddListener(MapperListener *pListener)
Parameter< kt_double > * m_pLoopSearchSpaceDimension
void setParamLinkScanMaximumDistance(double d)
void SetLastScan(LocalizedRangeScan *pScan)
void setParamMinimumAnglePenalty(double d)
kt_double MatchScan(LocalizedRangeScan *pScan, const LocalizedRangeScanVector &rBaseScans, Pose2 &rMean, Matrix3 &rCovariance, kt_bool doPenalize=true, kt_bool doRefineMatch=true)
virtual ParameterManager * GetParameterManager()
virtual const IdPoseVector & GetCorrections() const =0
double getParamCorrelationSearchSpaceSmearDeviation()
const Name & GetSensorName() const
ScanManager(kt_int32u runningBufferMaximumSize, kt_double runningBufferMaximumDistance)
ScanMatcher * GetLoopScanMatcher() const
Parameter< kt_double > * m_pMinimumTravelDistance
void AddRunningScan(LocalizedRangeScan *pScan)
void AddRunningScan(LocalizedRangeScan *pScan)
kt_int32s GetUniqueId() 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)
LocalizedRangeScanVector & GetRunningScans()
double getParamMinimumTravelDistance()
PointVectorDouble FindValidPoints(LocalizedRangeScan *pScan, const Vector2< kt_double > &rViewPoint) const
std::vector< Pose2 > Pose2Vector
kt_double GetResponse(kt_int32u angleIndex, kt_int32s gridPositionIndex) const
double getParamLoopSearchSpaceSmearDeviation()
double getParamFineSearchAngleOffset()
void setParamLoopSearchMaximumDistance(double d)
void FireBeginLoopClosure(const std::string &rInfo) const
void setParamLoopMatchMinimumResponseCoarse(double d)
bool getParamUseScanBarycenter()
kt_double GetTime() const
kt_bool InRange(const T &value, const T &a, const T &b)
kt_double SquaredDistance(const Vector2 &rOther) const
void AddScan(LocalizedRangeScan *pScan, kt_int32s uniqueId)
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()
kt_int32u GetSize() const
virtual const LocalizedRangeScanVector GetAllProcessedScans() const
GridIndexLookup< kt_int8u > * m_pGridLookup
static CorrelationGrid * CreateGrid(kt_int32s width, kt_int32s height, kt_double resolution, kt_double smearDeviation)
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)
LaserRangeFinder * GetLaserRangeFinder() const
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)
Pose2 GetSensorAt(const Pose2 &rPose) const
Parameter< kt_double > * m_pLinkMatchMinimumResponseFine
Vertex< LocalizedRangeScan > * GetVertex(LocalizedRangeScan *pScan)
double getParamAngleVariancePenalty()
static ScanMatcher * Create(Mapper *pMapper, kt_double searchSize, kt_double resolution, kt_double smearDeviation, kt_double rangeThreshold)
kt_double SquaredLength() const
ScanMatcher * m_pLoopScanMatcher
void SetLabel(EdgeLabel *pLabel)
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
virtual std::vector< T * > Traverse(Vertex< T > *pStartVertex, Visitor< T > *pVisitor)
void setParamMinimumTravelHeading(double d)
void AddEdges(LocalizedRangeScan *pScan, const Matrix3 &rCovariance)
double getParamLoopSearchMaximumDistance()
void setParamUseResponseExpansion(bool b)
Pose2 ComputeWeightedMean(const Pose2Vector &rMeans, const std::vector< Matrix3 > &rCovariances) const
void FireLoopClosureCheck(const std::string &rInfo) const
Vertex< T > * GetTarget() const
Parameter< kt_double > * m_pLoopMatchMinimumResponseCoarse
double getParamLoopMatchMaximumVarianceCoarse()
kt_bool TryCloseLoop(LocalizedRangeScan *pScan, const Name &rSensorName)
virtual ScanMatcher * GetLoopScanMatcher() const
LocalizedRangeScan * m_pLastScan
double getParamLinkMatchMinimumResponseFine()
kt_double m_RunningBufferMaximumDistance
Parameter< kt_double > * m_pCoarseSearchAngleOffset
void setParamLoopMatchMinimumResponseFine(double d)
const Vector2< kt_double > & GetPosition() const
Parameter< kt_double > * m_pLoopSearchMaximumDistance
virtual MapperGraph * GetGraph() const
LocalizedRangeScan * GetClosestScanToPose(const LocalizedRangeScanVector &rScans, const Pose2 &rPose) const
void setParamUseScanBarycenter(bool b)
Parameter< kt_double > * m_pAngleVariancePenalty
kt_double GetRangeThreshold() const
kt_int32u GetNumberOfRangeReadings() const
MapperGraph(Mapper *pMapper, kt_double rangeThreshold)
double getParamLoopSearchSpaceDimension()
Parameter< kt_double > * m_pMinimumTimeInterval
const Pose2 & GetCorrectedPose() const
Parameter< kt_bool > * m_pUseResponseExpansion
Parameter< kt_int32u > * m_pScanBufferSize
kt_bool IsUpTo(const T &value, const T &maximum)
LocalizedRangeScan * GetLastScan(const Name &rSensorName)
void setParamLoopSearchSpaceSmearDeviation(double d)
void FireInfo(const std::string &rInfo) const
std::vector< LocalizedRangeScan * > LocalizedRangeScanVector
Parameter< kt_bool > * m_pUseScanBarycenter
LocalizedRangeScanVector m_Scans
Parameter< kt_double > * m_pLoopMatchMinimumResponseFine
void setParamCoarseAngleResolution(double d)
kt_double m_MaxDistanceSquared