Mapper.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2010 SRI International
3  *
4  * This program is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU Lesser General Public License as published by
6  * the Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * This program is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  * GNU Lesser General Public License for more details.
13  *
14  * You should have received a copy of the GNU Lesser General Public License
15  * along with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 
18 #include <sstream>
19 #include <fstream>
20 #include <stdexcept>
21 #include <set>
22 #include <list>
23 #include <iterator>
24 
25 #include <math.h>
26 #include <assert.h>
27 
28 #include "open_karto/Mapper.h"
29 
30 namespace karto
31 {
32 
33  // enable this for verbose debug information
34  // #define KARTO_DEBUG
35 
36  #define MAX_VARIANCE 500.0
37  #define DISTANCE_PENALTY_GAIN 0.2
38  #define ANGLE_PENALTY_GAIN 0.2
39 
43 
44  void MapperSensorManager::RegisterSensor(const Name& rSensorName)
45  {
46  if (GetScanManager(rSensorName) == NULL)
47  {
49  }
50  }
51 
52 
60  {
61  ScanManager* pScanManager = GetScanManager(rSensorName);
62  if (pScanManager != NULL)
63  {
64  return pScanManager->GetScans().at(scanIndex);
65  }
66 
67  assert(false);
68  return NULL;
69  }
70 
76  {
77  GetScanManager(pScan)->AddScan(pScan, m_NextScanId);
78  m_Scans.push_back(pScan);
79  m_NextScanId++;
80  }
81 
87  {
89 
91  {
92  LocalizedRangeScanVector& rScans = iter->second->GetScans();
93 
94  scans.insert(scans.end(), rScans.begin(), rScans.end());
95  }
96 
97  return scans;
98  }
99 
104  {
105 // SensorManager::Clear();
106 
108  {
109  delete iter->second;
110  }
111 
112  m_ScanManagers.clear();
113  }
114 
118 
120  {
121  delete m_pCorrelationGrid;
122  delete m_pSearchSpaceProbs;
123  delete m_pGridLookup;
124  }
125 
126  ScanMatcher* ScanMatcher::Create(Mapper* pMapper, kt_double searchSize, kt_double resolution,
127  kt_double smearDeviation, kt_double rangeThreshold)
128  {
129  // invalid parameters
130  if (resolution <= 0)
131  {
132  return NULL;
133  }
134  if (searchSize <= 0)
135  {
136  return NULL;
137  }
138  if (smearDeviation < 0)
139  {
140  return NULL;
141  }
142  if (rangeThreshold <= 0)
143  {
144  return NULL;
145  }
146 
147  assert(math::DoubleEqual(math::Round(searchSize / resolution), (searchSize / resolution)));
148 
149  // calculate search space in grid coordinates
150  kt_int32u searchSpaceSideSize = static_cast<kt_int32u>(math::Round(searchSize / resolution) + 1);
151 
152  // compute requisite size of correlation grid (pad grid so that scan points can't fall off the grid
153  // if a scan is on the border of the search space)
154  kt_int32u pointReadingMargin = static_cast<kt_int32u>(ceil(rangeThreshold / resolution));
155 
156  kt_int32s gridSize = searchSpaceSideSize + 2 * pointReadingMargin;
157 
158  // create correlation grid
159  assert(gridSize % 2 == 1);
160  CorrelationGrid* pCorrelationGrid = CorrelationGrid::CreateGrid(gridSize, gridSize, resolution, smearDeviation);
161 
162  // create search space probabilities
163  Grid<kt_double>* pSearchSpaceProbs = Grid<kt_double>::CreateGrid(searchSpaceSideSize,
164  searchSpaceSideSize, resolution);
165 
166  ScanMatcher* pScanMatcher = new ScanMatcher(pMapper);
167  pScanMatcher->m_pCorrelationGrid = pCorrelationGrid;
168  pScanMatcher->m_pSearchSpaceProbs = pSearchSpaceProbs;
169  pScanMatcher->m_pGridLookup = new GridIndexLookup<kt_int8u>(pCorrelationGrid);
170 
171  return pScanMatcher;
172  }
173 
185  Matrix3& rCovariance, kt_bool doPenalize, kt_bool doRefineMatch)
186  {
188  // set scan pose to be center of grid
189 
190  // 1. get scan position
191  Pose2 scanPose = pScan->GetSensorPose();
192 
193  // scan has no readings; cannot do scan matching
194  // best guess of pose is based off of adjusted odometer reading
195  if (pScan->GetNumberOfRangeReadings() == 0)
196  {
197  rMean = scanPose;
198 
199  // maximum covariance
200  rCovariance(0, 0) = MAX_VARIANCE; // XX
201  rCovariance(1, 1) = MAX_VARIANCE; // YY
202  rCovariance(2, 2) = 4 * math::Square(m_pMapper->m_pCoarseAngleResolution->GetValue()); // TH*TH
203 
204  return 0.0;
205  }
206 
207  // 2. get size of grid
209 
210  // 3. compute offset (in meters - lower left corner)
211  Vector2<kt_double> offset;
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()));
214 
215  // 4. set offset
217 
219 
220  // set up correlation grid
221  AddScans(rBaseScans, scanPose.GetPosition());
222 
223  // compute how far to search in each direction
225  Vector2<kt_double> coarseSearchOffset(0.5 * (searchDimensions.GetX() - 1) * m_pCorrelationGrid->GetResolution(),
226  0.5 * (searchDimensions.GetY() - 1) * m_pCorrelationGrid->GetResolution());
227 
228  // a coarse search only checks half the cells in each dimension
229  Vector2<kt_double> coarseSearchResolution(2 * m_pCorrelationGrid->GetResolution(),
231 
232  // actual scan-matching
233  kt_double bestResponse = CorrelateScan(pScan, scanPose, coarseSearchOffset, coarseSearchResolution,
236  doPenalize, rMean, rCovariance, false);
237 
239  {
240  if (math::DoubleEqual(bestResponse, 0.0))
241  {
242 #ifdef KARTO_DEBUG
243  std::cout << "Mapper Info: Expanding response search space!" << std::endl;
244 #endif
245  // try and increase search angle offset with 20 degrees and do another match
246  kt_double newSearchAngleOffset = m_pMapper->m_pCoarseSearchAngleOffset->GetValue();
247  for (kt_int32u i = 0; i < 3; i++)
248  {
249  newSearchAngleOffset += math::DegreesToRadians(20);
250 
251  bestResponse = CorrelateScan(pScan, scanPose, coarseSearchOffset, coarseSearchResolution,
252  newSearchAngleOffset, m_pMapper->m_pCoarseAngleResolution->GetValue(),
253  doPenalize, rMean, rCovariance, false);
254 
255  if (math::DoubleEqual(bestResponse, 0.0) == false)
256  {
257  break;
258  }
259  }
260 
261 #ifdef KARTO_DEBUG
262  if (math::DoubleEqual(bestResponse, 0.0))
263  {
264  std::cout << "Mapper Warning: Unable to calculate response!" << std::endl;
265  }
266 #endif
267  }
268  }
269 
270  if (doRefineMatch)
271  {
272  Vector2<kt_double> fineSearchOffset(coarseSearchResolution * 0.5);
274  bestResponse = CorrelateScan(pScan, rMean, fineSearchOffset, fineSearchResolution,
277  doPenalize, rMean, rCovariance, true);
278  }
279 
280 #ifdef KARTO_DEBUG
281  std::cout << " BEST POSE = " << rMean << " BEST RESPONSE = " << bestResponse << ", VARIANCE = "
282  << rCovariance(0, 0) << ", " << rCovariance(1, 1) << std::endl;
283 #endif
284  assert(math::InRange(rMean.GetHeading(), -KT_PI, KT_PI));
285 
286  return bestResponse;
287  }
288 
306  const Vector2<kt_double>& rSearchSpaceOffset,
307  const Vector2<kt_double>& rSearchSpaceResolution,
308  kt_double searchAngleOffset, kt_double searchAngleResolution,
309  kt_bool doPenalize, Pose2& rMean, Matrix3& rCovariance, kt_bool doingFineMatch)
310  {
311  assert(searchAngleResolution != 0.0);
312 
313  // setup lookup arrays
314  m_pGridLookup->ComputeOffsets(pScan, rSearchCenter.GetHeading(), searchAngleOffset, searchAngleResolution);
315 
316  // only initialize probability grid if computing positional covariance (during coarse match)
317  if (!doingFineMatch)
318  {
320 
321  // position search grid - finds lower left corner of search grid
322  Vector2<kt_double> offset(rSearchCenter.GetPosition() - rSearchSpaceOffset);
324  }
325 
326  // calculate position arrays
327 
328  std::vector<kt_double> xPoses;
329  kt_int32u nX = static_cast<kt_int32u>(math::Round(rSearchSpaceOffset.GetX() *
330  2.0 / rSearchSpaceResolution.GetX()) + 1);
331  kt_double startX = -rSearchSpaceOffset.GetX();
332  for (kt_int32u xIndex = 0; xIndex < nX; xIndex++)
333  {
334  xPoses.push_back(startX + xIndex * rSearchSpaceResolution.GetX());
335  }
336  assert(math::DoubleEqual(xPoses.back(), -startX));
337 
338  std::vector<kt_double> yPoses;
339  kt_int32u nY = static_cast<kt_int32u>(math::Round(rSearchSpaceOffset.GetY() *
340  2.0 / rSearchSpaceResolution.GetY()) + 1);
341  kt_double startY = -rSearchSpaceOffset.GetY();
342  for (kt_int32u yIndex = 0; yIndex < nY; yIndex++)
343  {
344  yPoses.push_back(startY + yIndex * rSearchSpaceResolution.GetY());
345  }
346  assert(math::DoubleEqual(yPoses.back(), -startY));
347 
348  // calculate pose response array size
349  kt_int32u nAngles = static_cast<kt_int32u>(math::Round(searchAngleOffset * 2.0 / searchAngleResolution) + 1);
350 
351  kt_int32u poseResponseSize = static_cast<kt_int32u>(xPoses.size() * yPoses.size() * nAngles);
352 
353  // allocate array
354  std::pair<kt_double, Pose2>* pPoseResponse = new std::pair<kt_double, Pose2>[poseResponseSize];
355 
357  + startX, rSearchCenter.GetY() + startY));
358 
359  kt_int32u poseResponseCounter = 0;
360  forEachAs(std::vector<kt_double>, &yPoses, yIter)
361  {
362  kt_double y = *yIter;
363  kt_double newPositionY = rSearchCenter.GetY() + y;
364  kt_double squareY = math::Square(y);
365 
366  forEachAs(std::vector<kt_double>, &xPoses, xIter)
367  {
368  kt_double x = *xIter;
369  kt_double newPositionX = rSearchCenter.GetX() + x;
370  kt_double squareX = math::Square(x);
371 
372  Vector2<kt_int32s> gridPoint = m_pCorrelationGrid->WorldToGrid(Vector2<kt_double>(newPositionX, newPositionY));
373  kt_int32s gridIndex = m_pCorrelationGrid->GridIndex(gridPoint);
374  assert(gridIndex >= 0);
375 
376  kt_double angle = 0.0;
377  kt_double startAngle = rSearchCenter.GetHeading() - searchAngleOffset;
378  for (kt_int32u angleIndex = 0; angleIndex < nAngles; angleIndex++)
379  {
380  angle = startAngle + angleIndex * searchAngleResolution;
381 
382  kt_double response = GetResponse(angleIndex, gridIndex);
383  if (doPenalize && (math::DoubleEqual(response, 0.0) == false))
384  {
385  // simple model (approximate Gaussian) to take odometry into account
386 
387  kt_double squaredDistance = squareX + squareY;
388  kt_double distancePenalty = 1.0 - (DISTANCE_PENALTY_GAIN *
389  squaredDistance / m_pMapper->m_pDistanceVariancePenalty->GetValue());
390  distancePenalty = math::Maximum(distancePenalty, m_pMapper->m_pMinimumDistancePenalty->GetValue());
391 
392  kt_double squaredAngleDistance = math::Square(angle - rSearchCenter.GetHeading());
393  kt_double anglePenalty = 1.0 - (ANGLE_PENALTY_GAIN *
394  squaredAngleDistance / m_pMapper->m_pAngleVariancePenalty->GetValue());
395  anglePenalty = math::Maximum(anglePenalty, m_pMapper->m_pMinimumAnglePenalty->GetValue());
396 
397  response *= (distancePenalty * anglePenalty);
398  }
399 
400  // store response and pose
401  pPoseResponse[poseResponseCounter] = std::pair<kt_double, Pose2>(response, Pose2(newPositionX, newPositionY,
402  math::NormalizeAngle(angle)));
403  poseResponseCounter++;
404  }
405 
406  assert(math::DoubleEqual(angle, rSearchCenter.GetHeading() + searchAngleOffset));
407  }
408  }
409 
410  assert(poseResponseSize == poseResponseCounter);
411 
412  // find value of best response (in [0; 1])
413  kt_double bestResponse = -1;
414  for (kt_int32u i = 0; i < poseResponseSize; i++)
415  {
416  bestResponse = math::Maximum(bestResponse, pPoseResponse[i].first);
417 
418  // will compute positional covariance, save best relative probability for each cell
419  if (!doingFineMatch)
420  {
421  const Pose2& rPose = pPoseResponse[i].second;
423 
424  // Changed (kt_double*) to the reinterpret_cast - Luc
425  kt_double* ptr = reinterpret_cast<kt_double*>(m_pSearchSpaceProbs->GetDataPointer(grid));
426  if (ptr == NULL)
427  {
428  throw std::runtime_error("Mapper FATAL ERROR - Index out of range in probability search!");
429  }
430 
431  *ptr = math::Maximum(pPoseResponse[i].first, *ptr);
432  }
433  }
434 
435  // average all poses with same highest response
436  Vector2<kt_double> averagePosition;
437  kt_double thetaX = 0.0;
438  kt_double thetaY = 0.0;
439  kt_int32s averagePoseCount = 0;
440  for (kt_int32u i = 0; i < poseResponseSize; i++)
441  {
442  if (math::DoubleEqual(pPoseResponse[i].first, bestResponse))
443  {
444  averagePosition += pPoseResponse[i].second.GetPosition();
445 
446  kt_double heading = pPoseResponse[i].second.GetHeading();
447  thetaX += cos(heading);
448  thetaY += sin(heading);
449 
450  averagePoseCount++;
451  }
452  }
453 
454  Pose2 averagePose;
455  if (averagePoseCount > 0)
456  {
457  averagePosition /= averagePoseCount;
458 
459  thetaX /= averagePoseCount;
460  thetaY /= averagePoseCount;
461 
462  averagePose = Pose2(averagePosition, atan2(thetaY, thetaX));
463  }
464  else
465  {
466  throw std::runtime_error("Mapper FATAL ERROR - Unable to find best position");
467  }
468 
469  // delete pose response array
470  delete [] pPoseResponse;
471 
472 #ifdef KARTO_DEBUG
473  std::cout << "bestPose: " << averagePose << std::endl;
474  std::cout << "bestResponse: " << bestResponse << std::endl;
475 #endif
476 
477  if (!doingFineMatch)
478  {
479  ComputePositionalCovariance(averagePose, bestResponse, rSearchCenter, rSearchSpaceOffset,
480  rSearchSpaceResolution, searchAngleResolution, rCovariance);
481  }
482  else
483  {
484  ComputeAngularCovariance(averagePose, bestResponse, rSearchCenter,
485  searchAngleOffset, searchAngleResolution, rCovariance);
486  }
487 
488  rMean = averagePose;
489 
490 #ifdef KARTO_DEBUG
491  std::cout << "bestPose: " << averagePose << std::endl;
492 #endif
493 
494  if (bestResponse > 1.0)
495  {
496  bestResponse = 1.0;
497  }
498 
499  assert(math::InRange(bestResponse, 0.0, 1.0));
500  assert(math::InRange(rMean.GetHeading(), -KT_PI, KT_PI));
501 
502  return bestResponse;
503  }
504 
515  void ScanMatcher::ComputePositionalCovariance(const Pose2& rBestPose, kt_double bestResponse,
516  const Pose2& rSearchCenter,
517  const Vector2<kt_double>& rSearchSpaceOffset,
518  const Vector2<kt_double>& rSearchSpaceResolution,
519  kt_double searchAngleResolution, Matrix3& rCovariance)
520  {
521  // reset covariance to identity matrix
522  rCovariance.SetToIdentity();
523 
524  // if best response is vary small return max variance
525  if (bestResponse < KT_TOLERANCE)
526  {
527  rCovariance(0, 0) = MAX_VARIANCE; // XX
528  rCovariance(1, 1) = MAX_VARIANCE; // YY
529  rCovariance(2, 2) = 4 * math::Square(searchAngleResolution); // TH*TH
530 
531  return;
532  }
533 
534  kt_double accumulatedVarianceXX = 0;
535  kt_double accumulatedVarianceXY = 0;
536  kt_double accumulatedVarianceYY = 0;
537  kt_double norm = 0;
538 
539  kt_double dx = rBestPose.GetX() - rSearchCenter.GetX();
540  kt_double dy = rBestPose.GetY() - rSearchCenter.GetY();
541 
542  kt_double offsetX = rSearchSpaceOffset.GetX();
543  kt_double offsetY = rSearchSpaceOffset.GetY();
544 
545  kt_int32u nX = static_cast<kt_int32u>(math::Round(offsetX * 2.0 / rSearchSpaceResolution.GetX()) + 1);
546  kt_double startX = -offsetX;
547  assert(math::DoubleEqual(startX + (nX - 1) * rSearchSpaceResolution.GetX(), -startX));
548 
549  kt_int32u nY = static_cast<kt_int32u>(math::Round(offsetY * 2.0 / rSearchSpaceResolution.GetY()) + 1);
550  kt_double startY = -offsetY;
551  assert(math::DoubleEqual(startY + (nY - 1) * rSearchSpaceResolution.GetY(), -startY));
552 
553  for (kt_int32u yIndex = 0; yIndex < nY; yIndex++)
554  {
555  kt_double y = startY + yIndex * rSearchSpaceResolution.GetY();
556 
557  for (kt_int32u xIndex = 0; xIndex < nX; xIndex++)
558  {
559  kt_double x = startX + xIndex * rSearchSpaceResolution.GetX();
560 
562  rSearchCenter.GetY() + y));
564 
565  // response is not a low response
566  if (response >= (bestResponse - 0.1))
567  {
568  norm += response;
569  accumulatedVarianceXX += (math::Square(x - dx) * response);
570  accumulatedVarianceXY += ((x - dx) * (y - dy) * response);
571  accumulatedVarianceYY += (math::Square(y - dy) * response);
572  }
573  }
574  }
575 
576  if (norm > KT_TOLERANCE)
577  {
578  kt_double varianceXX = accumulatedVarianceXX / norm;
579  kt_double varianceXY = accumulatedVarianceXY / norm;
580  kt_double varianceYY = accumulatedVarianceYY / norm;
581  kt_double varianceTHTH = 4 * math::Square(searchAngleResolution);
582 
583  // lower-bound variances so that they are not too small;
584  // ensures that links are not too tight
585  kt_double minVarianceXX = 0.1 * math::Square(rSearchSpaceResolution.GetX());
586  kt_double minVarianceYY = 0.1 * math::Square(rSearchSpaceResolution.GetY());
587  varianceXX = math::Maximum(varianceXX, minVarianceXX);
588  varianceYY = math::Maximum(varianceYY, minVarianceYY);
589 
590  // increase variance for poorer responses
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; // this value will be set in ComputeAngularCovariance
597  }
598 
599  // if values are 0, set to MAX_VARIANCE
600  // values might be 0 if points are too sparse and thus don't hit other points
601  if (math::DoubleEqual(rCovariance(0, 0), 0.0))
602  {
603  rCovariance(0, 0) = MAX_VARIANCE;
604  }
605 
606  if (math::DoubleEqual(rCovariance(1, 1), 0.0))
607  {
608  rCovariance(1, 1) = MAX_VARIANCE;
609  }
610  }
611 
622  kt_double bestResponse,
623  const Pose2& rSearchCenter,
624  kt_double searchAngleOffset,
625  kt_double searchAngleResolution,
626  Matrix3& rCovariance)
627  {
628  // NOTE: do not reset covariance matrix
629 
630  // normalize angle difference
631  kt_double bestAngle = math::NormalizeAngleDifference(rBestPose.GetHeading(), rSearchCenter.GetHeading());
632 
634  kt_int32s gridIndex = m_pCorrelationGrid->GridIndex(gridPoint);
635 
636  kt_int32u nAngles = static_cast<kt_int32u>(math::Round(searchAngleOffset * 2 / searchAngleResolution) + 1);
637 
638  kt_double angle = 0.0;
639  kt_double startAngle = rSearchCenter.GetHeading() - searchAngleOffset;
640 
641  kt_double norm = 0.0;
642  kt_double accumulatedVarianceThTh = 0.0;
643  for (kt_int32u angleIndex = 0; angleIndex < nAngles; angleIndex++)
644  {
645  angle = startAngle + angleIndex * searchAngleResolution;
646  kt_double response = GetResponse(angleIndex, gridIndex);
647 
648  // response is not a low response
649  if (response >= (bestResponse - 0.1))
650  {
651  norm += response;
652  accumulatedVarianceThTh += (math::Square(angle - bestAngle) * response);
653  }
654  }
655  assert(math::DoubleEqual(angle, rSearchCenter.GetHeading() + searchAngleOffset));
656 
657  if (norm > KT_TOLERANCE)
658  {
659  if (accumulatedVarianceThTh < KT_TOLERANCE)
660  {
661  accumulatedVarianceThTh = math::Square(searchAngleResolution);
662  }
663 
664  accumulatedVarianceThTh /= norm;
665  }
666  else
667  {
668  accumulatedVarianceThTh = 1000 * math::Square(searchAngleResolution);
669  }
670 
671  rCovariance(2, 2) = accumulatedVarianceThTh;
672  }
673 
680  {
682 
683  // add all scans to grid
685  {
686  AddScan(*iter, viewPoint);
687  }
688  }
689 
696  void ScanMatcher::AddScan(LocalizedRangeScan* pScan, const Vector2<kt_double>& rViewPoint, kt_bool doSmear)
697  {
698  PointVectorDouble validPoints = FindValidPoints(pScan, rViewPoint);
699 
700  // put in all valid points
701  const_forEach(PointVectorDouble, &validPoints)
702  {
704  if (!math::IsUpTo(gridPoint.GetX(), m_pCorrelationGrid->GetROI().GetWidth()) ||
706  {
707  // point not in grid
708  continue;
709  }
710 
711  int gridIndex = m_pCorrelationGrid->GridIndex(gridPoint);
712 
713  // set grid cell as occupied
715  {
716  // value already set
717  continue;
718  }
719 
721 
722  // smear grid
723  if (doSmear == true)
724  {
725  m_pCorrelationGrid->SmearPoint(gridPoint);
726  }
727  }
728  }
729 
737  {
738  const PointVectorDouble& rPointReadings = pScan->GetPointReadings();
739 
740  // points must be at least 10 cm away when making comparisons of inside/outside of viewpoint
741  const kt_double minSquareDistance = math::Square(0.1); // in m^2
742 
743  // this iterator lags from the main iterator adding points only when the points are on
744  // the same side as the viewpoint
745  PointVectorDouble::const_iterator trailingPointIter = rPointReadings.begin();
746  PointVectorDouble validPoints;
747 
748  Vector2<kt_double> firstPoint;
749  kt_bool firstTime = true;
750  const_forEach(PointVectorDouble, &rPointReadings)
751  {
752  Vector2<kt_double> currentPoint = *iter;
753 
754  if (firstTime && !std::isnan(currentPoint.GetX()) && !std::isnan(currentPoint.GetY()))
755  {
756  firstPoint = currentPoint;
757  firstTime = false;
758  }
759 
760  Vector2<kt_double> delta = firstPoint - currentPoint;
761  if (delta.SquaredLength() > minSquareDistance)
762  {
763  // This compute the Determinant (viewPoint FirstPoint, viewPoint currentPoint)
764  // Which computes the direction of rotation, if the rotation is counterclock
765  // wise then we are looking at data we should keep. If it's negative rotation
766  // we should not included in in the matching
767  // have enough distance, check viewpoint
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;
772 
773  // reset beginning point
774  firstPoint = currentPoint;
775 
776  if (ss < 0.0) // wrong side, skip and keep going
777  {
778  trailingPointIter = iter;
779  }
780  else
781  {
782  for (; trailingPointIter != iter; ++trailingPointIter)
783  {
784  validPoints.push_back(*trailingPointIter);
785  }
786  }
787  }
788  }
789 
790  return validPoints;
791  }
792 
799  kt_double ScanMatcher::GetResponse(kt_int32u angleIndex, kt_int32s gridPositionIndex) const
800  {
801  kt_double response = 0.0;
802 
803  // add up value for each point
804  kt_int8u* pByte = m_pCorrelationGrid->GetDataPointer() + gridPositionIndex;
805 
806  const LookupArray* pOffsets = m_pGridLookup->GetLookupArray(angleIndex);
807  assert(pOffsets != NULL);
808 
809  // get number of points in offset list
810  kt_int32u nPoints = pOffsets->GetSize();
811  if (nPoints == 0)
812  {
813  return response;
814  }
815 
816  // calculate response
817  kt_int32s* pAngleIndexPointer = pOffsets->GetArrayPointer();
818  for (kt_int32u i = 0; i < nPoints; i++)
819  {
820  // ignore points that fall off the grid
821  kt_int32s pointGridIndex = gridPositionIndex + pAngleIndexPointer[i];
822  if (!math::IsUpTo(pointGridIndex, m_pCorrelationGrid->GetDataSize()) || pAngleIndexPointer[i] == INVALID_SCAN)
823  {
824  continue;
825  }
826 
827  // uses index offsets to efficiently find location of point in the grid
828  response += pByte[pAngleIndexPointer[i]];
829  }
830 
831  // normalize response
832  response /= (nPoints * GridStates_Occupied);
833  assert(fabs(response) <= 1.0);
834 
835  return response;
836  }
837 
838 
842 
843  MapperGraph::MapperGraph(Mapper* pMapper, kt_double rangeThreshold)
844  : m_pMapper(pMapper)
845  {
849  assert(m_pLoopScanMatcher);
850 
852  }
853 
855  {
856  delete m_pLoopScanMatcher;
857  m_pLoopScanMatcher = NULL;
858 
859  delete m_pTraversal;
860  m_pTraversal = NULL;
861  }
862 
864  {
865  assert(pScan);
866 
867  if (pScan != NULL)
868  {
871  if (m_pMapper->m_pScanOptimizer != NULL)
872  {
874  }
875  }
876  }
877 
878  void MapperGraph::AddEdges(LocalizedRangeScan* pScan, const Matrix3& rCovariance)
879  {
881 
882  const Name& rSensorName = pScan->GetSensorName();
883 
884  // link to previous scan
885  kt_int32s previousScanNum = pScan->GetStateId() - 1;
886  if (pSensorManager->GetLastScan(rSensorName) != NULL)
887  {
888  assert(previousScanNum >= 0);
889  LinkScans(pSensorManager->GetScan(rSensorName, previousScanNum), pScan, pScan->GetSensorPose(), rCovariance);
890  }
891 
892  Pose2Vector means;
893  std::vector<Matrix3> covariances;
894 
895  // first scan (link to first scan of other robots)
896  if (pSensorManager->GetLastScan(rSensorName) == NULL)
897  {
898  assert(pSensorManager->GetScans(rSensorName).size() == 1);
899 
900  std::vector<Name> deviceNames = pSensorManager->GetSensorNames();
901  forEach(std::vector<Name>, &deviceNames)
902  {
903  const Name& rCandidateSensorName = *iter;
904 
905  // skip if candidate device is the same or other device has no scans
906  if ((rCandidateSensorName == rSensorName) || (pSensorManager->GetScans(rCandidateSensorName).empty()))
907  {
908  continue;
909  }
910 
911  Pose2 bestPose;
912  Matrix3 covariance;
914  pSensorManager->GetScans(rCandidateSensorName),
915  bestPose, covariance);
916  LinkScans(pSensorManager->GetScan(rCandidateSensorName, 0), pScan, bestPose, covariance);
917 
918  // only add to means and covariances if response was high "enough"
920  {
921  means.push_back(bestPose);
922  covariances.push_back(covariance);
923  }
924  }
925  }
926  else
927  {
928  // link to running scans
929  Pose2 scanPose = pScan->GetSensorPose();
930  means.push_back(scanPose);
931  covariances.push_back(rCovariance);
932  LinkChainToScan(pSensorManager->GetRunningScans(rSensorName), pScan, scanPose, rCovariance);
933  }
934 
935  // link to other near chains (chains that include new scan are invalid)
936  LinkNearChains(pScan, means, covariances);
937 
938  if (!means.empty())
939  {
940  pScan->SetSensorPose(ComputeWeightedMean(means, covariances));
941  }
942  }
943 
945  {
946  kt_bool loopClosed = false;
947 
948  kt_int32u scanIndex = 0;
949 
950  LocalizedRangeScanVector candidateChain = FindPossibleLoopClosure(pScan, rSensorName, scanIndex);
951 
952  while (!candidateChain.empty())
953  {
954  Pose2 bestPose;
955  Matrix3 covariance;
956  kt_double coarseResponse = m_pLoopScanMatcher->MatchScan(pScan, candidateChain,
957  bestPose, covariance, false, false);
958 
959  std::stringstream stream;
960  stream << "COARSE RESPONSE: " << coarseResponse
962  << std::endl;
963  stream << " var: " << covariance(0, 0) << ", " << covariance(1, 1)
964  << " (< " << m_pMapper->m_pLoopMatchMaximumVarianceCoarse->GetValue() << ")";
965 
966  m_pMapper->FireLoopClosureCheck(stream.str());
967 
968  if ((coarseResponse > m_pMapper->m_pLoopMatchMinimumResponseCoarse->GetValue()) &&
969  (covariance(0, 0) < m_pMapper->m_pLoopMatchMaximumVarianceCoarse->GetValue()) &&
970  (covariance(1, 1) < m_pMapper->m_pLoopMatchMaximumVarianceCoarse->GetValue()))
971  {
972  LocalizedRangeScan tmpScan(pScan->GetSensorName(), pScan->GetRangeReadingsVector());
973  tmpScan.SetUniqueId(pScan->GetUniqueId());
974  tmpScan.SetTime(pScan->GetTime());
975  tmpScan.SetStateId(pScan->GetStateId());
976  tmpScan.SetCorrectedPose(pScan->GetCorrectedPose());
977  tmpScan.SetSensorPose(bestPose); // This also updates OdometricPose.
978  kt_double fineResponse = m_pMapper->m_pSequentialScanMatcher->MatchScan(&tmpScan, candidateChain,
979  bestPose, covariance, false);
980 
981  std::stringstream stream1;
982  stream1 << "FINE RESPONSE: " << fineResponse << " (>"
983  << m_pMapper->m_pLoopMatchMinimumResponseFine->GetValue() << ")" << std::endl;
984  m_pMapper->FireLoopClosureCheck(stream1.str());
985 
986  if (fineResponse < m_pMapper->m_pLoopMatchMinimumResponseFine->GetValue())
987  {
988  m_pMapper->FireLoopClosureCheck("REJECTED!");
989  }
990  else
991  {
992  m_pMapper->FireBeginLoopClosure("Closing loop...");
993 
994  pScan->SetSensorPose(bestPose);
995  LinkChainToScan(candidateChain, pScan, bestPose, covariance);
996  CorrectPoses();
997 
998  m_pMapper->FireEndLoopClosure("Loop closed!");
999 
1000  loopClosed = true;
1001  }
1002  }
1003 
1004  candidateChain = FindPossibleLoopClosure(pScan, rSensorName, scanIndex);
1005  }
1006 
1007  return loopClosed;
1008  }
1009 
1011  const Pose2& rPose) const
1012  {
1013  LocalizedRangeScan* pClosestScan = NULL;
1014  kt_double bestSquaredDistance = DBL_MAX;
1015 
1017  {
1018  Pose2 scanPose = (*iter)->GetReferencePose(m_pMapper->m_pUseScanBarycenter->GetValue());
1019 
1020  kt_double squaredDistance = rPose.GetPosition().SquaredDistance(scanPose.GetPosition());
1021  if (squaredDistance < bestSquaredDistance)
1022  {
1023  bestSquaredDistance = squaredDistance;
1024  pClosestScan = *iter;
1025  }
1026  }
1027 
1028  return pClosestScan;
1029  }
1030 
1032  LocalizedRangeScan* pTargetScan, kt_bool& rIsNewEdge)
1033  {
1034  // check that vertex exists
1035  assert(pSourceScan->GetStateId() < (kt_int32s)m_Vertices[pSourceScan->GetSensorName()].size());
1036  assert(pTargetScan->GetStateId() < (kt_int32s)m_Vertices[pTargetScan->GetSensorName()].size());
1037 
1038  Vertex<LocalizedRangeScan>* v1 = m_Vertices[pSourceScan->GetSensorName()][pSourceScan->GetStateId()];
1039  Vertex<LocalizedRangeScan>* v2 = m_Vertices[pTargetScan->GetSensorName()][pTargetScan->GetStateId()];
1040 
1041  // see if edge already exists
1042  const_forEach(std::vector<Edge<LocalizedRangeScan>*>, &(v1->GetEdges()))
1043  {
1044  Edge<LocalizedRangeScan>* pEdge = *iter;
1045 
1046  if (pEdge->GetTarget() == v2)
1047  {
1048  rIsNewEdge = false;
1049  return pEdge;
1050  }
1051  }
1052 
1055  rIsNewEdge = true;
1056  return pEdge;
1057  }
1058 
1060  const Pose2& rMean, const Matrix3& rCovariance)
1061  {
1062  kt_bool isNewEdge = true;
1063  Edge<LocalizedRangeScan>* pEdge = AddEdge(pFromScan, pToScan, isNewEdge);
1064 
1065  // only attach link information if the edge is new
1066  if (isNewEdge == true)
1067  {
1068  pEdge->SetLabel(new LinkInfo(pFromScan->GetSensorPose(), rMean, rCovariance));
1069  if (m_pMapper->m_pScanOptimizer != NULL)
1070  {
1072  }
1073  }
1074  }
1075 
1076  void MapperGraph::LinkNearChains(LocalizedRangeScan* pScan, Pose2Vector& rMeans, std::vector<Matrix3>& rCovariances)
1077  {
1078  const std::vector<LocalizedRangeScanVector> nearChains = FindNearChains(pScan);
1079  const_forEach(std::vector<LocalizedRangeScanVector>, &nearChains)
1080  {
1081  if (iter->size() < m_pMapper->m_pLoopMatchMinimumChainSize->GetValue())
1082  {
1083  continue;
1084  }
1085 
1086  Pose2 mean;
1087  Matrix3 covariance;
1088  // match scan against "near" chain
1089  kt_double response = m_pMapper->m_pSequentialScanMatcher->MatchScan(pScan, *iter, mean, covariance, false);
1091  {
1092  rMeans.push_back(mean);
1093  rCovariances.push_back(covariance);
1094  LinkChainToScan(*iter, pScan, mean, covariance);
1095  }
1096  }
1097  }
1098 
1100  const Pose2& rMean, const Matrix3& rCovariance)
1101  {
1103 
1104  LocalizedRangeScan* pClosestScan = GetClosestScanToPose(rChain, pose);
1105  assert(pClosestScan != NULL);
1106 
1107  Pose2 closestScanPose = pClosestScan->GetReferencePose(m_pMapper->m_pUseScanBarycenter->GetValue());
1108 
1109  kt_double squaredDistance = pose.GetPosition().SquaredDistance(closestScanPose.GetPosition());
1111  {
1112  LinkScans(pClosestScan, pScan, rMean, rCovariance);
1113  }
1114  }
1115 
1116  std::vector<LocalizedRangeScanVector> MapperGraph::FindNearChains(LocalizedRangeScan* pScan)
1117  {
1118  std::vector<LocalizedRangeScanVector> nearChains;
1119 
1121 
1122  // to keep track of which scans have been added to a chain
1123  LocalizedRangeScanVector processed;
1124 
1125  const LocalizedRangeScanVector nearLinkedScans = FindNearLinkedScans(pScan,
1127  const_forEach(LocalizedRangeScanVector, &nearLinkedScans)
1128  {
1129  LocalizedRangeScan* pNearScan = *iter;
1130 
1131  if (pNearScan == pScan)
1132  {
1133  continue;
1134  }
1135 
1136  // scan has already been processed, skip
1137  if (find(processed.begin(), processed.end(), pNearScan) != processed.end())
1138  {
1139  continue;
1140  }
1141 
1142  processed.push_back(pNearScan);
1143 
1144  // build up chain
1145  kt_bool isValidChain = true;
1146  std::list<LocalizedRangeScan*> chain;
1147 
1148  // add scans before current scan being processed
1149  for (kt_int32s candidateScanNum = pNearScan->GetStateId() - 1; candidateScanNum >= 0; candidateScanNum--)
1150  {
1151  LocalizedRangeScan* pCandidateScan = m_pMapper->m_pMapperSensorManager->GetScan(pNearScan->GetSensorName(),
1152  candidateScanNum);
1153 
1154  // chain is invalid--contains scan being added
1155  if (pCandidateScan == pScan)
1156  {
1157  isValidChain = false;
1158  }
1159 
1160  Pose2 candidatePose = pCandidateScan->GetReferencePose(m_pMapper->m_pUseScanBarycenter->GetValue());
1161  kt_double squaredDistance = scanPose.GetPosition().SquaredDistance(candidatePose.GetPosition());
1162 
1164  {
1165  chain.push_front(pCandidateScan);
1166  processed.push_back(pCandidateScan);
1167  }
1168  else
1169  {
1170  break;
1171  }
1172  }
1173 
1174  chain.push_back(pNearScan);
1175 
1176  // add scans after current scan being processed
1177  kt_int32u end = static_cast<kt_int32u>(m_pMapper->m_pMapperSensorManager->GetScans(pNearScan->GetSensorName()).size());
1178  for (kt_int32u candidateScanNum = pNearScan->GetStateId() + 1; candidateScanNum < end; candidateScanNum++)
1179  {
1180  LocalizedRangeScan* pCandidateScan = m_pMapper->m_pMapperSensorManager->GetScan(pNearScan->GetSensorName(),
1181  candidateScanNum);
1182 
1183  if (pCandidateScan == pScan)
1184  {
1185  isValidChain = false;
1186  }
1187 
1188  Pose2 candidatePose = pCandidateScan->GetReferencePose(m_pMapper->m_pUseScanBarycenter->GetValue());;
1189  kt_double squaredDistance = scanPose.GetPosition().SquaredDistance(candidatePose.GetPosition());
1190 
1192  {
1193  chain.push_back(pCandidateScan);
1194  processed.push_back(pCandidateScan);
1195  }
1196  else
1197  {
1198  break;
1199  }
1200  }
1201 
1202  if (isValidChain)
1203  {
1204  // change list to vector
1205  LocalizedRangeScanVector tempChain;
1206  std::copy(chain.begin(), chain.end(), std::inserter(tempChain, tempChain.begin()));
1207  // add chain to collection
1208  nearChains.push_back(tempChain);
1209  }
1210  }
1211 
1212  return nearChains;
1213  }
1214 
1216  {
1217  NearScanVisitor* pVisitor = new NearScanVisitor(pScan, maxDistance, m_pMapper->m_pUseScanBarycenter->GetValue());
1218  LocalizedRangeScanVector nearLinkedScans = m_pTraversal->Traverse(GetVertex(pScan), pVisitor);
1219  delete pVisitor;
1220 
1221  return nearLinkedScans;
1222  }
1223 
1224  Pose2 MapperGraph::ComputeWeightedMean(const Pose2Vector& rMeans, const std::vector<Matrix3>& rCovariances) const
1225  {
1226  assert(rMeans.size() == rCovariances.size());
1227 
1228  // compute sum of inverses and create inverse list
1229  std::vector<Matrix3> inverses;
1230  inverses.reserve(rCovariances.size());
1231 
1232  Matrix3 sumOfInverses;
1233  const_forEach(std::vector<Matrix3>, &rCovariances)
1234  {
1235  Matrix3 inverse = iter->Inverse();
1236  inverses.push_back(inverse);
1237 
1238  sumOfInverses += inverse;
1239  }
1240  Matrix3 inverseOfSumOfInverses = sumOfInverses.Inverse();
1241 
1242  // compute weighted mean
1243  Pose2 accumulatedPose;
1244  kt_double thetaX = 0.0;
1245  kt_double thetaY = 0.0;
1246 
1247  Pose2Vector::const_iterator meansIter = rMeans.begin();
1248  const_forEach(std::vector<Matrix3>, &inverses)
1249  {
1250  Pose2 pose = *meansIter;
1251  kt_double angle = pose.GetHeading();
1252  thetaX += cos(angle);
1253  thetaY += sin(angle);
1254 
1255  Matrix3 weight = inverseOfSumOfInverses * (*iter);
1256  accumulatedPose += weight * pose;
1257 
1258  ++meansIter;
1259  }
1260 
1261  thetaX /= rMeans.size();
1262  thetaY /= rMeans.size();
1263  accumulatedPose.SetHeading(atan2(thetaY, thetaX));
1264 
1265  return accumulatedPose;
1266  }
1267 
1269  const Name& rSensorName,
1270  kt_int32u& rStartNum)
1271  {
1272  LocalizedRangeScanVector chain; // return value
1273 
1275 
1276  // possible loop closure chain should not include close scans that have a
1277  // path of links to the scan of interest
1278  const LocalizedRangeScanVector nearLinkedScans =
1280 
1281  kt_int32u nScans = static_cast<kt_int32u>(m_pMapper->m_pMapperSensorManager->GetScans(rSensorName).size());
1282  for (; rStartNum < nScans; rStartNum++)
1283  {
1284  LocalizedRangeScan* pCandidateScan = m_pMapper->m_pMapperSensorManager->GetScan(rSensorName, rStartNum);
1285 
1286  Pose2 candidateScanPose = pCandidateScan->GetReferencePose(m_pMapper->m_pUseScanBarycenter->GetValue());
1287 
1288  kt_double squaredDistance = candidateScanPose.GetPosition().SquaredDistance(pose.GetPosition());
1290  {
1291  // a linked scan cannot be in the chain
1292  if (find(nearLinkedScans.begin(), nearLinkedScans.end(), pCandidateScan) != nearLinkedScans.end())
1293  {
1294  chain.clear();
1295  }
1296  else
1297  {
1298  chain.push_back(pCandidateScan);
1299  }
1300  }
1301  else
1302  {
1303  // return chain if it is long "enough"
1304  if (chain.size() >= m_pMapper->m_pLoopMatchMinimumChainSize->GetValue())
1305  {
1306  return chain;
1307  }
1308  else
1309  {
1310  chain.clear();
1311  }
1312  }
1313  }
1314 
1315  return chain;
1316  }
1317 
1319  {
1320  // optimize scans!
1322  if (pSolver != NULL)
1323  {
1324  pSolver->Compute();
1325 
1327  {
1328  m_pMapper->m_pMapperSensorManager->GetScan(iter->first)->SetSensorPose(iter->second);
1329  }
1330 
1331  pSolver->Clear();
1332  }
1333  }
1334 
1338 
1343  : Module("Mapper")
1344  , m_Initialized(false)
1345  , m_pSequentialScanMatcher(NULL)
1346  , m_pMapperSensorManager(NULL)
1347  , m_pGraph(NULL)
1348  , m_pScanOptimizer(NULL)
1349  {
1351  }
1352 
1356  Mapper::Mapper(const std::string& rName)
1357  : Module(rName)
1358  , m_Initialized(false)
1359  , m_pSequentialScanMatcher(NULL)
1360  , m_pMapperSensorManager(NULL)
1361  , m_pGraph(NULL)
1362  , m_pScanOptimizer(NULL)
1363  {
1365  }
1366 
1371  {
1372  Reset();
1373 
1374  delete m_pMapperSensorManager;
1375  }
1376 
1378  {
1380  "UseScanMatching",
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 "
1387  "results.",
1388  true,
1390 
1392  "UseScanBarycenter",
1393  "Use the barycenter of scan endpoints to define distances between "
1394  "scans.",
1395  true, GetParameterManager());
1396 
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.",
1407  3600, GetParameterManager());
1408 
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.",
1417  0.2, GetParameterManager());
1418 
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 "
1427  "amount.",
1429 
1431  "ScanBufferSize",
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.)",
1438  70, GetParameterManager());
1439 
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.",
1444  20.0, GetParameterManager());
1445 
1447  "LinkMatchMinimumResponseFine",
1448  "Scans are linked only if the correlation response value is greater "
1449  "than this value.",
1450  0.8, GetParameterManager());
1451 
1453  "LinkScanMaximumDistance",
1454  "Maximum distance between linked scans. Scans that are farther apart "
1455  "will not be linked regardless of the correlation response value.",
1456  10.0, GetParameterManager());
1457 
1459  "LoopSearchMaximumDistance",
1460  "Scans less than this distance from the current position will be "
1461  "considered for a match in loop closure.",
1462  4.0, GetParameterManager());
1463 
1465  "DoLoopClosing",
1466  "Enable/disable loop closure.",
1467  true, GetParameterManager());
1468 
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.",
1474  10, GetParameterManager());
1475 
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 "
1480  "coarse search.",
1482 
1484  "LoopMatchMinimumResponseCoarse",
1485  "If response is larger then this, then initiate loop closure search at "
1486  "the coarse resolution.",
1487  0.8, GetParameterManager());
1488 
1490  "LoopMatchMinimumResponseFine",
1491  "If response is larger then this, then initiate loop closure search at "
1492  "the fine resolution.",
1493  0.8, GetParameterManager());
1494 
1496  // CorrelationParameters correlationParameters;
1497 
1499  "CorrelationSearchSpaceDimension",
1500  "The size of the search grid used by the matcher. The search grid will "
1501  "have the size CorrelationSearchSpaceDimension * "
1502  "CorrelationSearchSpaceDimension",
1503  0.3, GetParameterManager());
1504 
1506  "CorrelationSearchSpaceResolution",
1507  "The resolution (size of a grid cell) of the correlation grid.",
1508  0.01, GetParameterManager());
1509 
1511  "CorrelationSearchSpaceSmearDeviation",
1512  "The point readings are smeared by this value in X and Y to create a "
1513  "smoother response.",
1514  0.03, GetParameterManager());
1515 
1516 
1518  // CorrelationParameters loopCorrelationParameters;
1519 
1521  "LoopSearchSpaceDimension",
1522  "The size of the search grid used by the matcher.",
1523  8.0, GetParameterManager());
1524 
1526  "LoopSearchSpaceResolution",
1527  "The resolution (size of a grid cell) of the correlation grid.",
1528  0.05, GetParameterManager());
1529 
1531  "LoopSearchSpaceSmearDeviation",
1532  "The point readings are smeared by this value in X and Y to create a "
1533  "smoother response.",
1534  0.03, GetParameterManager());
1535 
1537  // ScanMatcherParameters;
1538 
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.",
1545 
1547  "AngleVariancePenalty",
1548  "See DistanceVariancePenalty.",
1550 
1552  "FineSearchAngleOffset",
1553  "The range of angles to search during a fine search.",
1555 
1557  "CoarseSearchAngleOffset",
1558  "The range of angles to search during a coarse search.",
1560 
1562  "CoarseAngleResolution",
1563  "Resolution of angles to search during a coarse search.",
1565 
1567  "MinimumAnglePenalty",
1568  "Minimum value of the angle penalty multiplier so scores do not become "
1569  "too small.",
1570  0.9, GetParameterManager());
1571 
1573  "MinimumDistancePenalty",
1574  "Minimum value of the distance penalty multiplier so scores do not "
1575  "become too small.",
1576  0.5, GetParameterManager());
1577 
1579  "UseResponseExpansion",
1580  "Whether to increase the search space if no good matches are initially "
1581  "found.",
1582  false, GetParameterManager());
1583  }
1584  /* Adding in getters and setters here for easy parameter access */
1585 
1586  // General Parameters
1587 
1589  {
1590  return static_cast<bool>(m_pUseScanMatching->GetValue());
1591  }
1592 
1594  {
1595  return static_cast<bool>(m_pUseScanBarycenter->GetValue());
1596  }
1597 
1599  {
1600  return static_cast<double>(m_pMinimumTimeInterval->GetValue());
1601  }
1602 
1604  {
1605  return static_cast<double>(m_pMinimumTravelDistance->GetValue());
1606  }
1607 
1609  {
1610  return math::RadiansToDegrees(static_cast<double>(m_pMinimumTravelHeading->GetValue()));
1611  }
1612 
1614  {
1615  return static_cast<int>(m_pScanBufferSize->GetValue());
1616  }
1617 
1619  {
1620  return static_cast<double>(m_pScanBufferMaximumScanDistance->GetValue());
1621  }
1622 
1624  {
1625  return static_cast<double>(m_pLinkMatchMinimumResponseFine->GetValue());
1626  }
1627 
1629  {
1630  return static_cast<double>(m_pLinkScanMaximumDistance->GetValue());
1631  }
1632 
1634  {
1635  return static_cast<double>(m_pLoopSearchMaximumDistance->GetValue());
1636  }
1637 
1639  {
1640  return static_cast<bool>(m_pDoLoopClosing->GetValue());
1641  }
1642 
1644  {
1645  return static_cast<int>(m_pLoopMatchMinimumChainSize->GetValue());
1646  }
1647 
1649  {
1650  return static_cast<double>(std::sqrt(m_pLoopMatchMaximumVarianceCoarse->GetValue()));
1651  }
1652 
1654  {
1655  return static_cast<double>(m_pLoopMatchMinimumResponseCoarse->GetValue());
1656  }
1657 
1659  {
1660  return static_cast<double>(m_pLoopMatchMinimumResponseFine->GetValue());
1661  }
1662 
1663  // Correlation Parameters - Correlation Parameters
1664 
1666  {
1667  return static_cast<double>(m_pCorrelationSearchSpaceDimension->GetValue());
1668  }
1669 
1671  {
1672  return static_cast<double>(m_pCorrelationSearchSpaceResolution->GetValue());
1673  }
1674 
1676  {
1677  return static_cast<double>(m_pCorrelationSearchSpaceSmearDeviation->GetValue());
1678  }
1679 
1680  // Correlation Parameters - Loop Correlation Parameters
1681 
1683  {
1684  return static_cast<double>(m_pLoopSearchSpaceDimension->GetValue());
1685  }
1686 
1688  {
1689  return static_cast<double>(m_pLoopSearchSpaceResolution->GetValue());
1690  }
1691 
1693  {
1694  return static_cast<double>(m_pLoopSearchSpaceSmearDeviation->GetValue());
1695  }
1696 
1697  // ScanMatcher Parameters
1698 
1700  {
1701  return std::sqrt(static_cast<double>(m_pDistanceVariancePenalty->GetValue()));
1702  }
1703 
1705  {
1706  return std::sqrt(static_cast<double>(m_pAngleVariancePenalty->GetValue()));
1707  }
1708 
1710  {
1711  return static_cast<double>(m_pFineSearchAngleOffset->GetValue());
1712  }
1713 
1715  {
1716  return static_cast<double>(m_pCoarseSearchAngleOffset->GetValue());
1717  }
1718 
1720  {
1721  return static_cast<double>(m_pCoarseAngleResolution->GetValue());
1722  }
1723 
1725  {
1726  return static_cast<double>(m_pMinimumAnglePenalty->GetValue());
1727  }
1728 
1730  {
1731  return static_cast<double>(m_pMinimumDistancePenalty->GetValue());
1732  }
1733 
1735  {
1736  return static_cast<bool>(m_pUseResponseExpansion->GetValue());
1737  }
1738 
1739  /* Setters for parameters */
1740  // General Parameters
1742  {
1744  }
1745 
1747  {
1749  }
1750 
1752  {
1754  }
1755 
1757  {
1759  }
1760 
1762  {
1764  }
1765 
1767  {
1769  }
1770 
1772  {
1774  }
1775 
1777  {
1779  }
1780 
1782  {
1784  }
1785 
1787  {
1789  }
1790 
1792  {
1794  }
1795 
1797  {
1799  }
1800 
1802  {
1804  }
1805 
1807  {
1809  }
1810 
1812  {
1814  }
1815 
1816  // Correlation Parameters - Correlation Parameters
1818  {
1820  }
1821 
1823  {
1825  }
1826 
1828  {
1830  }
1831 
1832 
1833  // Correlation Parameters - Loop Closure Parameters
1835  {
1837  }
1838 
1840  {
1842  }
1843 
1845  {
1847  }
1848 
1849 
1850  // Scan Matcher Parameters
1852  {
1854  }
1855 
1857  {
1859  }
1860 
1862  {
1864  }
1865 
1867  {
1869  }
1870 
1872  {
1874  }
1875 
1877  {
1879  }
1880 
1882  {
1884  }
1885 
1887  {
1889  }
1890 
1891 
1892 
1893  void Mapper::Initialize(kt_double rangeThreshold)
1894  {
1895  if (m_Initialized == false)
1896  {
1897  // create sequential scan and loop matcher
1902  rangeThreshold);
1903  assert(m_pSequentialScanMatcher);
1904 
1907 
1908  m_pGraph = new MapperGraph(this, rangeThreshold);
1909 
1910  m_Initialized = true;
1911  }
1912  }
1913 
1915  {
1916  delete m_pSequentialScanMatcher;
1917  m_pSequentialScanMatcher = NULL;
1918 
1919  delete m_pGraph;
1920  m_pGraph = NULL;
1921 
1922  delete m_pMapperSensorManager;
1923  m_pMapperSensorManager = NULL;
1924 
1925  m_Initialized = false;
1926  }
1927 
1929  {
1930  return true;
1931  }
1932 
1934  {
1935  if (pScan != NULL)
1936  {
1937  karto::LaserRangeFinder* pLaserRangeFinder = pScan->GetLaserRangeFinder();
1938 
1939  // validate scan
1940  if (pLaserRangeFinder == NULL || pScan == NULL || pLaserRangeFinder->Validate(pScan) == false)
1941  {
1942  return false;
1943  }
1944 
1945  if (m_Initialized == false)
1946  {
1947  // initialize mapper with range threshold from device
1948  Initialize(pLaserRangeFinder->GetRangeThreshold());
1949  }
1950 
1951  // get last scan
1953 
1954  // update scans corrected pose based on last correction
1955  if (pLastScan != NULL)
1956  {
1957  Transform lastTransform(pLastScan->GetOdometricPose(), pLastScan->GetCorrectedPose());
1958  pScan->SetCorrectedPose(lastTransform.TransformPose(pScan->GetOdometricPose()));
1959  }
1960 
1961  // test if scan is outside minimum boundary or if heading is larger then minimum heading
1962  if (!HasMovedEnough(pScan, pLastScan))
1963  {
1964  return false;
1965  }
1966 
1967  Matrix3 covariance;
1968  covariance.SetToIdentity();
1969 
1970  // correct scan (if not first scan)
1971  if (m_pUseScanMatching->GetValue() && pLastScan != NULL)
1972  {
1973  Pose2 bestPose;
1976  bestPose,
1977  covariance);
1978  pScan->SetSensorPose(bestPose);
1979  }
1980 
1981  // add scan to buffer and assign id
1983 
1985  {
1986  // add to graph
1987  m_pGraph->AddVertex(pScan);
1988  m_pGraph->AddEdges(pScan, covariance);
1989 
1991 
1992  if (m_pDoLoopClosing->GetValue())
1993  {
1994  std::vector<Name> deviceNames = m_pMapperSensorManager->GetSensorNames();
1995  const_forEach(std::vector<Name>, &deviceNames)
1996  {
1997  m_pGraph->TryCloseLoop(pScan, *iter);
1998  }
1999  }
2000  }
2001 
2003 
2004  return true;
2005  }
2006 
2007  return false;
2008  }
2009 
2017  {
2018  // test if first scan
2019  if (pLastScan == NULL)
2020  {
2021  return true;
2022  }
2023 
2024  // test if enough time has passed
2025  kt_double timeInterval = pScan->GetTime() - pLastScan->GetTime();
2026  if (timeInterval >= m_pMinimumTimeInterval->GetValue())
2027  {
2028  return true;
2029  }
2030 
2031  Pose2 lastScannerPose = pLastScan->GetSensorAt(pLastScan->GetOdometricPose());
2032  Pose2 scannerPose = pScan->GetSensorAt(pScan->GetOdometricPose());
2033 
2034  // test if we have turned enough
2035  kt_double deltaHeading = math::NormalizeAngle(scannerPose.GetHeading() - lastScannerPose.GetHeading());
2036  if (fabs(deltaHeading) >= m_pMinimumTravelHeading->GetValue())
2037  {
2038  return true;
2039  }
2040 
2041  // test if we have moved enough
2042  kt_double squaredTravelDistance = lastScannerPose.GetPosition().SquaredDistance(scannerPose.GetPosition());
2043  if (squaredTravelDistance >= math::Square(m_pMinimumTravelDistance->GetValue()) - KT_TOLERANCE)
2044  {
2045  return true;
2046  }
2047 
2048  return false;
2049  }
2050 
2056  {
2057  LocalizedRangeScanVector allScans;
2058 
2059  if (m_pMapperSensorManager != NULL)
2060  {
2061  allScans = m_pMapperSensorManager->GetAllScans();
2062  }
2063 
2064  return allScans;
2065  }
2066 
2072  {
2073  m_Listeners.push_back(pListener);
2074  }
2075 
2081  {
2082  std::vector<MapperListener*>::iterator iter = std::find(m_Listeners.begin(), m_Listeners.end(), pListener);
2083  if (iter != m_Listeners.end())
2084  {
2085  m_Listeners.erase(iter);
2086  }
2087  }
2088 
2089  void Mapper::FireInfo(const std::string& rInfo) const
2090  {
2091  const_forEach(std::vector<MapperListener*>, &m_Listeners)
2092  {
2093  (*iter)->Info(rInfo);
2094  }
2095  }
2096 
2097  void Mapper::FireDebug(const std::string& rInfo) const
2098  {
2099  const_forEach(std::vector<MapperListener*>, &m_Listeners)
2100  {
2101  MapperDebugListener* pListener = dynamic_cast<MapperDebugListener*>(*iter);
2102 
2103  if (pListener != NULL)
2104  {
2105  pListener->Debug(rInfo);
2106  }
2107  }
2108  }
2109 
2110  void Mapper::FireLoopClosureCheck(const std::string& rInfo) const
2111  {
2112  const_forEach(std::vector<MapperListener*>, &m_Listeners)
2113  {
2114  MapperLoopClosureListener* pListener = dynamic_cast<MapperLoopClosureListener*>(*iter);
2115 
2116  if (pListener != NULL)
2117  {
2118  pListener->LoopClosureCheck(rInfo);
2119  }
2120  }
2121  }
2122 
2123  void Mapper::FireBeginLoopClosure(const std::string& rInfo) const
2124  {
2125  const_forEach(std::vector<MapperListener*>, &m_Listeners)
2126  {
2127  MapperLoopClosureListener* pListener = dynamic_cast<MapperLoopClosureListener*>(*iter);
2128 
2129  if (pListener != NULL)
2130  {
2131  pListener->BeginLoopClosure(rInfo);
2132  }
2133  }
2134  }
2135 
2136  void Mapper::FireEndLoopClosure(const std::string& rInfo) const
2137  {
2138  const_forEach(std::vector<MapperListener*>, &m_Listeners)
2139  {
2140  MapperLoopClosureListener* pListener = dynamic_cast<MapperLoopClosureListener*>(*iter);
2141 
2142  if (pListener != NULL)
2143  {
2144  pListener->EndLoopClosure(rInfo);
2145  }
2146  }
2147  }
2148 
2149  void Mapper::SetScanSolver(ScanSolver* pScanOptimizer)
2150  {
2151  m_pScanOptimizer = pScanOptimizer;
2152  }
2153 
2155  {
2156  return m_pGraph;
2157  }
2158 
2160  {
2161  return m_pSequentialScanMatcher;
2162  }
2163 
2165  {
2166  return m_pGraph->GetLoopScanMatcher();
2167  }
2168 } // namespace karto
karto::MapperDebugListener
Definition: Mapper.h:48
karto::Name
Definition: Karto.h:354
response
const std::string response
const_forEach
#define const_forEach(listtype, list)
Definition: Macros.h:72
karto::math::Round
kt_double Round(kt_double value)
Definition: Math.h:87
karto::ScanMatcher::m_pGridLookup
GridIndexLookup< kt_int8u > * m_pGridLookup
Definition: Mapper.h:1282
karto::Mapper::getParamCoarseAngleResolution
double getParamCoarseAngleResolution()
Definition: Mapper.cpp:1719
karto::Mapper
Definition: Mapper.h:1750
karto::Mapper::m_pAngleVariancePenalty
Parameter< kt_double > * m_pAngleVariancePenalty
Definition: Mapper.h:2113
karto::ScanSolver
Definition: Mapper.h:824
karto::ScanSolver::AddConstraint
virtual void AddConstraint(Edge< LocalizedRangeScan > *)
Definition: Mapper.h:875
karto::Mapper::getParamLoopMatchMinimumChainSize
int getParamLoopMatchMinimumChainSize()
Definition: Mapper.cpp:1643
karto::KT_TOLERANCE
const kt_double KT_TOLERANCE
Definition: Math.h:41
karto::Transform::TransformPose
Pose2 TransformPose(const Pose2 &rSourcePose)
Definition: Karto.h:2890
karto::Rectangle2< kt_int32s >
karto::Mapper::getParamLoopMatchMinimumResponseCoarse
double getParamLoopMatchMinimumResponseCoarse()
Definition: Mapper.cpp:1653
karto::Mapper::m_pDoLoopClosing
Parameter< kt_bool > * m_pDoLoopClosing
Definition: Mapper.h:2027
karto::Mapper::getParamScanBufferMaximumScanDistance
double getParamScanBufferMaximumScanDistance()
Definition: Mapper.cpp:1618
karto::ScanMatcher::MatchScan
kt_double MatchScan(LocalizedRangeScan *pScan, const LocalizedRangeScanVector &rBaseScans, Pose2 &rMean, Matrix3 &rCovariance, kt_bool doPenalize=true, kt_bool doRefineMatch=true)
Definition: Mapper.cpp:184
karto::Mapper::FireLoopClosureCheck
void FireLoopClosureCheck(const std::string &rInfo) const
Definition: Mapper.cpp:2110
karto::GridIndexLookup::ComputeOffsets
void ComputeOffsets(LocalizedRangeScan *pScan, kt_double angleCenter, kt_double angleOffset, kt_double angleResolution)
Definition: Karto.h:6433
karto::KT_PI
const kt_double KT_PI
Definition: Math.h:32
karto::Pose2Vector
std::vector< Pose2 > Pose2Vector
Definition: Karto.h:2174
karto::MapperGraph::TryCloseLoop
kt_bool TryCloseLoop(LocalizedRangeScan *pScan, const Name &rSensorName)
Definition: Mapper.cpp:944
karto::LaserRangeScan::GetLaserRangeFinder
LaserRangeFinder * GetLaserRangeFinder() const
Definition: Karto.h:5091
karto::Mapper::getParamMinimumTravelHeading
double getParamMinimumTravelHeading()
Definition: Mapper.cpp:1608
kt_double
double kt_double
Definition: Types.h:67
karto::MapperGraph::AddVertex
void AddVertex(LocalizedRangeScan *pScan)
Definition: Mapper.cpp:863
karto::LocalizedRangeScan::GetOdometricPose
const Pose2 & GetOdometricPose() const
Definition: Karto.h:5217
karto::LaserRangeFinder
Definition: Karto.h:3721
karto::LocalizedRangeScan::GetReferencePose
Pose2 GetReferencePose(kt_bool useBarycenter) const
Definition: Karto.h:5277
karto::ScanMatcher::AddScans
void AddScans(const LocalizedRangeScanVector &rScans, Vector2< kt_double > viewPoint)
Definition: Mapper.cpp:679
karto::Pose2::GetPosition
const Vector2< kt_double > & GetPosition() const
Definition: Karto.h:2046
karto::MapperGraph::LinkChainToScan
void LinkChainToScan(const LocalizedRangeScanVector &rChain, LocalizedRangeScan *pScan, const Pose2 &rMean, const Matrix3 &rCovariance)
Definition: Mapper.cpp:1099
karto::LocalizedRangeScan::GetSensorPose
Pose2 GetSensorPose() const
Definition: Karto.h:5295
karto::MapperGraph::GetLoopScanMatcher
ScanMatcher * GetLoopScanMatcher() const
Definition: Mapper.h:713
karto::Mapper::getParamCorrelationSearchSpaceResolution
double getParamCorrelationSearchSpaceResolution()
Definition: Mapper.cpp:1670
karto::Mapper::FireEndLoopClosure
void FireEndLoopClosure(const std::string &rInfo) const
Definition: Mapper.cpp:2136
karto::Mapper::GetGraph
virtual MapperGraph * GetGraph() const
Definition: Mapper.cpp:2154
karto::Parameter::SetValue
void SetValue(const T &rValue)
Definition: Karto.h:3141
karto::Module
Definition: Karto.h:762
MAX_VARIANCE
#define MAX_VARIANCE
Definition: Mapper.cpp:36
karto::Mapper::FireDebug
void FireDebug(const std::string &rInfo) const
Definition: Mapper.cpp:2097
karto::NearScanVisitor
Definition: Mapper.h:618
karto::Mapper::GetLoopScanMatcher
virtual ScanMatcher * GetLoopScanMatcher() const
Definition: Mapper.cpp:2164
karto::Mapper::setParamDoLoopClosing
void setParamDoLoopClosing(bool b)
Definition: Mapper.cpp:1791
karto::math::DegreesToRadians
kt_double DegreesToRadians(kt_double degrees)
Definition: Math.h:56
karto::Pose2::GetY
kt_double GetY() const
Definition: Karto.h:2028
karto::Mapper::setParamLinkMatchMinimumResponseFine
void setParamLinkMatchMinimumResponseFine(double d)
Definition: Mapper.cpp:1776
karto::Mapper::setParamCoarseAngleResolution
void setParamCoarseAngleResolution(double d)
Definition: Mapper.cpp:1871
karto::Mapper::InitializeParameters
void InitializeParameters()
Definition: Mapper.cpp:1377
karto::Mapper::m_pLoopSearchMaximumDistance
Parameter< kt_double > * m_pLoopSearchMaximumDistance
Definition: Mapper.h:2034
karto::MapperGraph::LinkScans
void LinkScans(LocalizedRangeScan *pFromScan, LocalizedRangeScan *pToScan, const Pose2 &rMean, const Matrix3 &rCovariance)
Definition: Mapper.cpp:1059
DISTANCE_PENALTY_GAIN
#define DISTANCE_PENALTY_GAIN
Definition: Mapper.cpp:37
karto::Mapper::setParamMinimumAnglePenalty
void setParamMinimumAnglePenalty(double d)
Definition: Mapper.cpp:1876
karto::MapperGraph::~MapperGraph
virtual ~MapperGraph()
Definition: Mapper.cpp:854
karto::MapperGraph::m_pMapper
Mapper * m_pMapper
Definition: Mapper.h:804
karto::ScanMatcher::CorrelateScan
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)
Definition: Mapper.cpp:305
karto::ScanSolver::Compute
virtual void Compute()=0
karto::Mapper::setParamScanBufferMaximumScanDistance
void setParamScanBufferMaximumScanDistance(double d)
Definition: Mapper.cpp:1771
karto::LookupArray
Definition: Karto.h:6252
karto::LaserRangeFinder::GetRangeThreshold
kt_double GetRangeThreshold() const
Definition: Karto.h:3781
karto::MapperGraph::FindPossibleLoopClosure
LocalizedRangeScanVector FindPossibleLoopClosure(LocalizedRangeScan *pScan, const Name &rSensorName, kt_int32u &rStartNum)
Definition: Mapper.cpp:1268
karto::Mapper::HasMovedEnough
kt_bool HasMovedEnough(LocalizedRangeScan *pScan, LocalizedRangeScan *pLastScan) const
Definition: Mapper.cpp:2016
karto::MapperGraph::GetClosestScanToPose
LocalizedRangeScan * GetClosestScanToPose(const LocalizedRangeScanVector &rScans, const Pose2 &rPose) const
Definition: Mapper.cpp:1010
karto::Vector2::GetX
const T & GetX() const
Definition: Karto.h:957
karto::MapperGraph::AddEdges
void AddEdges(LocalizedRangeScan *pScan, const Matrix3 &rCovariance)
Definition: Mapper.cpp:878
karto::LocalizedRangeScan
Definition: Karto.h:5185
karto::ScanManager::AddScan
void AddScan(LocalizedRangeScan *pScan, kt_int32s uniqueId)
Definition: Mapper.h:1318
karto::Mapper::getParamCoarseSearchAngleOffset
double getParamCoarseSearchAngleOffset()
Definition: Mapper.cpp:1714
karto::LookupArray::GetArrayPointer
kt_int32s * GetArrayPointer()
Definition: Karto.h:6343
karto::MapperLoopClosureListener::EndLoopClosure
virtual void EndLoopClosure(const std::string &)
Definition: Mapper.h:76
karto::LocalizedRangeScan::GetPointReadings
const PointVectorDouble & GetPointReadings(kt_bool wantFiltered=false) const
Definition: Karto.h:5351
karto::ScanMatcher::m_pSearchSpaceProbs
Grid< kt_double > * m_pSearchSpaceProbs
Definition: Mapper.h:1280
karto::BreadthFirstTraversal
Definition: Mapper.h:545
karto::Mapper::m_pScanBufferMaximumScanDistance
Parameter< kt_double > * m_pScanBufferMaximumScanDistance
Definition: Mapper.h:2008
karto::Mapper::m_pMinimumTimeInterval
Parameter< kt_double > * m_pMinimumTimeInterval
Definition: Mapper.h:1971
kt_int32s
int32_t kt_int32s
Definition: Types.h:51
karto::math::Maximum
const T & Maximum(const T &value1, const T &value2)
Definition: Math.h:111
karto::LocalizedRangeScan::SetSensorPose
void SetSensorPose(const Pose2 &rScanPose)
Definition: Karto.h:5304
karto::Mapper::setParamScanBufferSize
void setParamScanBufferSize(int i)
Definition: Mapper.cpp:1766
karto::Matrix3::SetToIdentity
void SetToIdentity()
Definition: Karto.h:2370
karto::Mapper::setParamLoopSearchSpaceDimension
void setParamLoopSearchSpaceDimension(double d)
Definition: Mapper.cpp:1834
karto::Mapper::getParamLoopMatchMinimumResponseFine
double getParamLoopMatchMinimumResponseFine()
Definition: Mapper.cpp:1658
karto::SensorData::SetUniqueId
void SetUniqueId(kt_int32u uniqueId)
Definition: Karto.h:4884
karto::MapperSensorManager::GetAllScans
LocalizedRangeScanVector GetAllScans()
Definition: Mapper.cpp:86
karto::Matrix3
Definition: Karto.h:2347
karto::Mapper::setParamAngleVariancePenalty
void setParamAngleVariancePenalty(double d)
Definition: Mapper.cpp:1856
karto::ScanSolver::IdPoseVector
std::vector< std::pair< kt_int32s, Pose2 > > IdPoseVector
Definition: Mapper.h:830
karto::Mapper::getParamMinimumTravelDistance
double getParamMinimumTravelDistance()
Definition: Mapper.cpp:1603
karto::Grid< kt_double >
karto::MapperGraph::GetVertex
Vertex< LocalizedRangeScan > * GetVertex(LocalizedRangeScan *pScan)
Definition: Mapper.h:724
karto::Mapper::getParamUseResponseExpansion
bool getParamUseResponseExpansion()
Definition: Mapper.cpp:1734
karto::LocalizedRangeScan::GetSensorAt
Pose2 GetSensorAt(const Pose2 &rPose) const
Definition: Karto.h:5325
karto::MapperLoopClosureListener::LoopClosureCheck
virtual void LoopClosureCheck(const std::string &)
Definition: Mapper.h:66
karto::Matrix3::Inverse
Matrix3 Inverse() const
Definition: Karto.h:2448
karto::MapperSensorManager
Definition: Mapper.h:1419
karto::Mapper::Reset
void Reset()
Definition: Mapper.cpp:1914
karto::Mapper::setParamCorrelationSearchSpaceSmearDeviation
void setParamCorrelationSearchSpaceSmearDeviation(double d)
Definition: Mapper.cpp:1827
karto::Grid::GetCoordinateConverter
CoordinateConverter * GetCoordinateConverter() const
Definition: Karto.h:4657
karto::Grid::CreateGrid
static Grid * CreateGrid(kt_int32s width, kt_int32s height, kt_double resolution)
Definition: Karto.h:4401
karto::math::RadiansToDegrees
kt_double RadiansToDegrees(kt_double radians)
Definition: Math.h:66
karto::Mapper::m_pLoopMatchMaximumVarianceCoarse
Parameter< kt_double > * m_pLoopMatchMaximumVarianceCoarse
Definition: Mapper.h:2049
karto::MapperGraph::m_pTraversal
GraphTraversal< LocalizedRangeScan > * m_pTraversal
Definition: Mapper.h:814
karto::MapperListener
Definition: Mapper.h:36
karto::LinkInfo
Definition: Mapper.h:111
karto::math::NormalizeAngle
kt_double NormalizeAngle(kt_double angle)
Definition: Math.h:182
karto::ScanMatcher::ComputeAngularCovariance
void ComputeAngularCovariance(const Pose2 &rBestPose, kt_double bestResponse, const Pose2 &rSearchCenter, kt_double searchAngleOffset, kt_double searchAngleResolution, Matrix3 &rCovariance)
Definition: Mapper.cpp:621
karto::Mapper::GetAllProcessedScans
virtual const LocalizedRangeScanVector GetAllProcessedScans() const
Definition: Mapper.cpp:2055
karto::SensorData::GetStateId
kt_int32s GetStateId() const
Definition: Karto.h:4857
karto::Mapper::setParamLoopSearchSpaceResolution
void setParamLoopSearchSpaceResolution(double d)
Definition: Mapper.cpp:1839
karto::MapperGraph
Definition: Mapper.h:654
karto::Mapper::SetScanSolver
void SetScanSolver(ScanSolver *pSolver)
Definition: Mapper.cpp:2149
karto::Vector2::GetY
const T & GetY() const
Definition: Karto.h:975
karto::ScanMatcher::m_pCorrelationGrid
CorrelationGrid * m_pCorrelationGrid
Definition: Mapper.h:1279
karto::MapperSensorManager::m_ScanManagers
ScanManagerMap m_ScanManagers
Definition: Mapper.h:1579
karto::Mapper::getParamLoopSearchSpaceDimension
double getParamLoopSearchSpaceDimension()
Definition: Mapper.cpp:1682
karto::MapperSensorManager::GetLastScan
LocalizedRangeScan * GetLastScan(const Name &rSensorName)
Definition: Mapper.h:1478
karto::Mapper::m_pMapperSensorManager
MapperSensorManager * m_pMapperSensorManager
Definition: Mapper.h:1937
karto::Grid::GetDataPointer
T * GetDataPointer(const Vector2< kt_int32s > &rGrid)
Definition: Karto.h:4562
karto::ScanMatcher::ComputePositionalCovariance
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)
Definition: Mapper.cpp:515
karto::Mapper::getParamLoopSearchMaximumDistance
double getParamLoopSearchMaximumDistance()
Definition: Mapper.cpp:1633
karto::Graph< LocalizedRangeScan >::m_Vertices
VertexMap m_Vertices
Definition: Mapper.h:532
karto::MapperLoopClosureListener
Definition: Mapper.h:60
karto::LocalizedRangeScanVector
std::vector< LocalizedRangeScan * > LocalizedRangeScanVector
Definition: Karto.h:5490
karto::MapperSensorManager::GetSensorNames
std::vector< Name > GetSensorNames()
Definition: Mapper.h:1462
karto::Parameter< kt_bool >
karto::Grid::GetResolution
kt_double GetResolution() const
Definition: Karto.h:4666
karto::CorrelationGrid::CreateGrid
static CorrelationGrid * CreateGrid(kt_int32s width, kt_int32s height, kt_double resolution, kt_double smearDeviation)
Definition: Mapper.h:919
karto::Mapper::setParamUseScanBarycenter
void setParamUseScanBarycenter(bool b)
Definition: Mapper.cpp:1746
karto::ScanMatcher::FindValidPoints
PointVectorDouble FindValidPoints(LocalizedRangeScan *pScan, const Vector2< kt_double > &rViewPoint) const
Definition: Mapper.cpp:736
karto::Mapper::m_pMinimumTravelDistance
Parameter< kt_double > * m_pMinimumTravelDistance
Definition: Mapper.h:1981
ANGLE_PENALTY_GAIN
#define ANGLE_PENALTY_GAIN
Definition: Mapper.cpp:38
karto::Mapper::Mapper
Mapper()
Definition: Mapper.cpp:1342
karto::Mapper::GetSequentialScanMatcher
virtual ScanMatcher * GetSequentialScanMatcher() const
Definition: Mapper.cpp:2159
karto::Mapper::getParamScanBufferSize
int getParamScanBufferSize()
Definition: Mapper.cpp:1613
karto::Mapper::m_pLoopSearchSpaceDimension
Parameter< kt_double > * m_pLoopSearchSpaceDimension
Definition: Mapper.h:2092
karto::SensorData::SetStateId
void SetStateId(kt_int32s stateId)
Definition: Karto.h:4866
karto::LaserRangeScan::GetNumberOfRangeReadings
kt_int32u GetNumberOfRangeReadings() const
Definition: Karto.h:5100
karto::MapperGraph::MapperGraph
MapperGraph(Mapper *pMapper, kt_double rangeThreshold)
Definition: Mapper.cpp:843
karto::Graph::AddEdge
void AddEdge(Edge< T > *pEdge)
Definition: Mapper.h:483
karto::MapperSensorManager::m_RunningBufferMaximumSize
kt_int32u m_RunningBufferMaximumSize
Definition: Mapper.h:1581
karto::Mapper::getParamUseScanBarycenter
bool getParamUseScanBarycenter()
Definition: Mapper.cpp:1593
karto::Mapper::m_pLinkScanMaximumDistance
Parameter< kt_double > * m_pLinkScanMaximumDistance
Definition: Mapper.h:2021
d
d
karto::LocalizedRangeScan::SetCorrectedPose
void SetCorrectedPose(const Pose2 &rPose)
Definition: Karto.h:5248
karto::GridIndexLookup::GetLookupArray
const LookupArray * GetLookupArray(kt_int32u index) const
Definition: Karto.h:6410
karto::Grid::GetWidth
kt_int32s GetWidth() const
Definition: Karto.h:4583
karto::Mapper::m_pLoopMatchMinimumChainSize
Parameter< kt_int32u > * m_pLoopMatchMinimumChainSize
Definition: Mapper.h:2042
karto::LocalizedRangeScan::GetCorrectedPose
const Pose2 & GetCorrectedPose() const
Definition: Karto.h:5239
karto::Mapper::getParamFineSearchAngleOffset
double getParamFineSearchAngleOffset()
Definition: Mapper.cpp:1709
karto::Mapper::m_pLoopSearchSpaceSmearDeviation
Parameter< kt_double > * m_pLoopSearchSpaceSmearDeviation
Definition: Mapper.h:2104
karto::Rectangle2::GetHeight
T GetHeight() const
Definition: Karto.h:1846
karto::Mapper::m_pGraph
MapperGraph * m_pGraph
Definition: Mapper.h:1939
karto::ScanManager
Definition: Mapper.h:1292
karto::Mapper::getParamLoopSearchSpaceSmearDeviation
double getParamLoopSearchSpaceSmearDeviation()
Definition: Mapper.cpp:1692
kt_bool
bool kt_bool
Definition: Types.h:64
karto::MapperGraph::LinkNearChains
void LinkNearChains(LocalizedRangeScan *pScan, Pose2Vector &rMeans, std::vector< Matrix3 > &rCovariances)
Definition: Mapper.cpp:1076
karto::Mapper::RemoveListener
void RemoveListener(MapperListener *pListener)
Definition: Mapper.cpp:2080
karto::Mapper::m_pFineSearchAngleOffset
Parameter< kt_double > * m_pFineSearchAngleOffset
Definition: Mapper.h:2116
karto::MapperGraph::FindNearLinkedScans
LocalizedRangeScanVector FindNearLinkedScans(LocalizedRangeScan *pScan, kt_double maxDistance)
Definition: Mapper.cpp:1215
karto::CoordinateConverter::SetOffset
void SetOffset(const Vector2< kt_double > &rOffset)
Definition: Karto.h:4317
karto::Mapper::setParamLoopSearchSpaceSmearDeviation
void setParamLoopSearchSpaceSmearDeviation(double d)
Definition: Mapper.cpp:1844
karto::MapperSensorManager::AddScan
void AddScan(LocalizedRangeScan *pScan)
Definition: Mapper.cpp:75
karto::Mapper::setParamMinimumTimeInterval
void setParamMinimumTimeInterval(double d)
Definition: Mapper.cpp:1751
karto::MapperSensorManager::ScanManagerMap
std::map< Name, ScanManager * > ScanManagerMap
Definition: Mapper.h:1421
karto::math::InRange
kt_bool InRange(const T &value, const T &a, const T &b)
Definition: Math.h:172
karto::MapperSensorManager::m_NextScanId
kt_int32s m_NextScanId
Definition: Mapper.h:1584
karto::PointVectorDouble
std::vector< Vector2< kt_double > > PointVectorDouble
Definition: Karto.h:1204
karto::Mapper::setParamCoarseSearchAngleOffset
void setParamCoarseSearchAngleOffset(double d)
Definition: Mapper.cpp:1866
karto::LaserRangeFinder::Validate
virtual kt_bool Validate()
Definition: Karto.h:3954
karto::Vector2< kt_double >
karto::Mapper::getParamUseScanMatching
bool getParamUseScanMatching()
Definition: Mapper.cpp:1588
karto::LookupArray::GetSize
kt_int32u GetSize() const
Definition: Karto.h:6289
karto::ScanSolver::GetCorrections
virtual const IdPoseVector & GetCorrections() const =0
karto::Mapper::m_pLinkMatchMinimumResponseFine
Parameter< kt_double > * m_pLinkMatchMinimumResponseFine
Definition: Mapper.h:2014
karto::Mapper::getParamDistanceVariancePenalty
double getParamDistanceVariancePenalty()
Definition: Mapper.cpp:1699
karto::MapperLoopClosureListener::BeginLoopClosure
virtual void BeginLoopClosure(const std::string &)
Definition: Mapper.h:71
karto::Mapper::m_pSequentialScanMatcher
ScanMatcher * m_pSequentialScanMatcher
Definition: Mapper.h:1935
karto::math::DoubleEqual
kt_bool DoubleEqual(kt_double a, kt_double b)
Definition: Math.h:135
karto::Mapper::setParamLoopMatchMinimumResponseCoarse
void setParamLoopMatchMinimumResponseCoarse(double d)
Definition: Mapper.cpp:1806
forEachAs
#define forEachAs(listtype, list, iter)
Definition: Macros.h:69
karto::Vector2::SetX
void SetX(const T &x)
Definition: Karto.h:966
karto::CorrelationGrid::GetROI
const Rectangle2< kt_int32s > & GetROI() const
Definition: Mapper.h:952
karto::Object::GetParameterManager
virtual ParameterManager * GetParameterManager()
Definition: Karto.h:635
karto::Mapper::m_pCorrelationSearchSpaceResolution
Parameter< kt_double > * m_pCorrelationSearchSpaceResolution
Definition: Mapper.h:2076
karto::Grid::GetDataSize
kt_int32s GetDataSize() const
Definition: Karto.h:4637
karto::Mapper::setParamLoopMatchMinimumChainSize
void setParamLoopMatchMinimumChainSize(int i)
Definition: Mapper.cpp:1796
karto::Mapper::m_pCoarseSearchAngleOffset
Parameter< kt_double > * m_pCoarseSearchAngleOffset
Definition: Mapper.h:2117
karto::Edge::GetTarget
Vertex< T > * GetTarget() const
Definition: Mapper.h:343
karto::Mapper::m_pMinimumAnglePenalty
Parameter< kt_double > * m_pMinimumAnglePenalty
Definition: Mapper.h:2124
karto::Transform
Definition: Karto.h:2862
karto::ScanMatcher::AddScan
void AddScan(LocalizedRangeScan *pScan, const Vector2< kt_double > &rViewPoint, kt_bool doSmear=true)
Definition: Mapper.cpp:696
karto::SensorData::GetUniqueId
kt_int32s GetUniqueId() const
Definition: Karto.h:4875
karto::Edge::SetLabel
void SetLabel(EdgeLabel *pLabel)
Definition: Mapper.h:361
karto::MapperGraph::CorrectPoses
void CorrectPoses()
Definition: Mapper.cpp:1318
karto::Mapper::m_pScanBufferSize
Parameter< kt_int32u > * m_pScanBufferSize
Definition: Mapper.h:2001
karto::MapperDebugListener::Debug
virtual void Debug(const std::string &)
Definition: Mapper.h:54
karto::Mapper::setParamLinkScanMaximumDistance
void setParamLinkScanMaximumDistance(double d)
Definition: Mapper.cpp:1781
karto::ScanMatcher::m_pMapper
Mapper * m_pMapper
Definition: Mapper.h:1277
karto::Mapper::setParamLoopMatchMaximumVarianceCoarse
void setParamLoopMatchMaximumVarianceCoarse(double d)
Definition: Mapper.cpp:1801
karto::Mapper::m_pCoarseAngleResolution
Parameter< kt_double > * m_pCoarseAngleResolution
Definition: Mapper.h:2120
karto::Mapper::setParamMinimumTravelHeading
void setParamMinimumTravelHeading(double d)
Definition: Mapper.cpp:1761
karto::ScanMatcher::~ScanMatcher
virtual ~ScanMatcher()
Definition: Mapper.cpp:119
karto::Mapper::setParamDistanceVariancePenalty
void setParamDistanceVariancePenalty(double d)
Definition: Mapper.cpp:1851
karto::math::Square
T Square(T value)
Definition: Math.h:77
karto::Mapper::getParamLoopMatchMaximumVarianceCoarse
double getParamLoopMatchMaximumVarianceCoarse()
Definition: Mapper.cpp:1648
kt_int32u
uint32_t kt_int32u
Definition: Types.h:52
karto::Pose2::GetX
kt_double GetX() const
Definition: Karto.h:2010
karto::Rectangle2::GetWidth
T GetWidth() const
Definition: Karto.h:1828
karto::Mapper::m_pUseScanBarycenter
Parameter< kt_bool > * m_pUseScanBarycenter
Definition: Mapper.h:1958
karto::Mapper::m_pUseScanMatching
Parameter< kt_bool > * m_pUseScanMatching
Definition: Mapper.h:1953
karto::Mapper::m_pLoopMatchMinimumResponseCoarse
Parameter< kt_double > * m_pLoopMatchMinimumResponseCoarse
Definition: Mapper.h:2055
karto::Mapper::getParamMinimumAnglePenalty
double getParamMinimumAnglePenalty()
Definition: Mapper.cpp:1724
karto::MapperSensorManager::AddRunningScan
void AddRunningScan(LocalizedRangeScan *pScan)
Definition: Mapper.h:1516
karto::Grid::Clear
void Clear()
Definition: Karto.h:4423
karto::CorrelationGrid::SmearPoint
void SmearPoint(const Vector2< kt_int32s > &rGridPoint)
Definition: Mapper.h:970
karto::Vertex
Definition: Mapper.h:209
karto::Pose2::SetHeading
void SetHeading(kt_double heading)
Definition: Karto.h:2073
karto::Mapper::m_pDistanceVariancePenalty
Parameter< kt_double > * m_pDistanceVariancePenalty
Definition: Mapper.h:2112
karto::Mapper::m_pCorrelationSearchSpaceSmearDeviation
Parameter< kt_double > * m_pCorrelationSearchSpaceSmearDeviation
Definition: Mapper.h:2082
karto::Mapper::getParamLinkScanMaximumDistance
double getParamLinkScanMaximumDistance()
Definition: Mapper.cpp:1628
karto::Mapper::getParamCorrelationSearchSpaceSmearDeviation
double getParamCorrelationSearchSpaceSmearDeviation()
Definition: Mapper.cpp:1675
karto::GridIndexLookup< kt_int8u >
karto::Vector2::SetY
void SetY(const T &y)
Definition: Karto.h:984
karto::Mapper::m_pLoopMatchMinimumResponseFine
Parameter< kt_double > * m_pLoopMatchMinimumResponseFine
Definition: Mapper.h:2061
karto::Mapper::setParamUseResponseExpansion
void setParamUseResponseExpansion(bool b)
Definition: Mapper.cpp:1886
karto::Mapper::m_pMinimumTravelHeading
Parameter< kt_double > * m_pMinimumTravelHeading
Definition: Mapper.h:1991
karto::MapperGraph::FindNearChains
std::vector< LocalizedRangeScanVector > FindNearChains(LocalizedRangeScan *pScan)
Definition: Mapper.cpp:1116
karto::MapperSensorManager::m_RunningBufferMaximumDistance
kt_double m_RunningBufferMaximumDistance
Definition: Mapper.h:1582
karto::MapperGraph::ComputeWeightedMean
Pose2 ComputeWeightedMean(const Pose2Vector &rMeans, const std::vector< Matrix3 > &rCovariances) const
Definition: Mapper.cpp:1224
karto::Mapper::setParamMinimumDistancePenalty
void setParamMinimumDistancePenalty(double d)
Definition: Mapper.cpp:1881
karto::Mapper::AddListener
void AddListener(MapperListener *pListener)
Definition: Mapper.cpp:2071
Mapper.h
karto::Mapper::getParamDoLoopClosing
bool getParamDoLoopClosing()
Definition: Mapper.cpp:1638
karto::math::NormalizeAngleDifference
kt_double NormalizeAngleDifference(kt_double minuend, kt_double subtrahend)
Definition: Math.h:221
karto::MapperSensorManager::m_Scans
std::vector< LocalizedRangeScan * > m_Scans
Definition: Mapper.h:1586
forEach
#define forEach(listtype, list)
Definition: Macros.h:66
karto::Pose2
Definition: Karto.h:1957
karto::MapperSensorManager::GetRunningScans
LocalizedRangeScanVector & GetRunningScans(const Name &rSensorName)
Definition: Mapper.h:1536
karto::SensorData::SetTime
void SetTime(kt_double time)
Definition: Karto.h:4902
karto::Mapper::setParamUseScanMatching
void setParamUseScanMatching(bool b)
Definition: Mapper.cpp:1741
karto::Object
Definition: Karto.h:590
karto::Mapper::MapperGraph
friend class MapperGraph
Definition: Mapper.h:1752
karto::Mapper::m_pMinimumDistancePenalty
Parameter< kt_double > * m_pMinimumDistancePenalty
Definition: Mapper.h:2125
karto::ScanMatcher::Create
static ScanMatcher * Create(Mapper *pMapper, kt_double searchSize, kt_double resolution, kt_double smearDeviation, kt_double rangeThreshold)
Definition: Mapper.cpp:126
karto::Graph::AddVertex
void AddVertex(const Name &rName, Vertex< T > *pVertex)
Definition: Mapper.h:474
karto::Mapper::m_Initialized
kt_bool m_Initialized
Definition: Mapper.h:1933
karto::Vector2::SquaredLength
kt_double SquaredLength() const
Definition: Karto.h:1013
karto::Mapper::getParamAngleVariancePenalty
double getParamAngleVariancePenalty()
Definition: Mapper.cpp:1704
karto::Mapper::setParamCorrelationSearchSpaceDimension
void setParamCorrelationSearchSpaceDimension(double d)
Definition: Mapper.cpp:1817
karto::Mapper::m_pLoopSearchSpaceResolution
Parameter< kt_double > * m_pLoopSearchSpaceResolution
Definition: Mapper.h:2098
karto::ScanMatcher
Definition: Mapper.h:1128
karto::math::IsUpTo
kt_bool IsUpTo(const T &value, const T &maximum)
Definition: Math.h:147
karto::Mapper::~Mapper
virtual ~Mapper()
Definition: Mapper.cpp:1370
karto::GridStates_Occupied
@ GridStates_Occupied
Definition: Karto.h:4205
assert.h
karto::ScanManager::GetScans
LocalizedRangeScanVector & GetScans()
Definition: Mapper.h:1353
karto::Mapper::Process
virtual kt_bool Process(LocalizedRangeScan *pScan)
Definition: Mapper.cpp:1933
karto::CorrelationGrid
Definition: Mapper.h:899
karto::MapperSensorManager::SetLastScan
void SetLastScan(LocalizedRangeScan *pScan)
Definition: Mapper.h:1489
karto::Mapper::Initialize
void Initialize(kt_double rangeThreshold)
Definition: Mapper.cpp:1893
karto::Mapper::m_pScanOptimizer
ScanSolver * m_pScanOptimizer
Definition: Mapper.h:1940
karto::MapperSensorManager::GetScans
LocalizedRangeScanVector & GetScans(const Name &rSensorName)
Definition: Mapper.h:1526
karto::MapperGraph::m_pLoopScanMatcher
ScanMatcher * m_pLoopScanMatcher
Definition: Mapper.h:809
karto::Mapper::FireInfo
void FireInfo(const std::string &rInfo) const
Definition: Mapper.cpp:2089
kt_int8u
uint8_t kt_int8u
Definition: Types.h:46
karto::Mapper::FireBeginLoopClosure
void FireBeginLoopClosure(const std::string &rInfo) const
Definition: Mapper.cpp:2123
karto::Mapper::setParamCorrelationSearchSpaceResolution
void setParamCorrelationSearchSpaceResolution(double d)
Definition: Mapper.cpp:1822
karto::Grid::WorldToGrid
Vector2< kt_int32s > WorldToGrid(const Vector2< kt_double > &rWorld, kt_bool flipY=false) const
Definition: Karto.h:4541
karto::Mapper::setParamFineSearchAngleOffset
void setParamFineSearchAngleOffset(double d)
Definition: Mapper.cpp:1861
karto::Mapper::m_Listeners
std::vector< MapperListener * > m_Listeners
Definition: Mapper.h:1942
karto::ScanSolver::Clear
virtual void Clear()
Definition: Mapper.h:889
karto::INVALID_SCAN
const kt_int32s INVALID_SCAN
Definition: Math.h:47
karto::Mapper::setParamLoopSearchMaximumDistance
void setParamLoopSearchMaximumDistance(double d)
Definition: Mapper.cpp:1786
karto::Vertex::GetEdges
const std::vector< Edge< T > * > & GetEdges() const
Definition: Mapper.h:234
karto::Parameter::GetValue
const T & GetValue() const
Definition: Karto.h:3132
karto::MapperSensorManager::GetScan
LocalizedRangeScan * GetScan(const Name &rSensorName, kt_int32s scanIndex)
Definition: Mapper.cpp:59
karto::MapperSensorManager::RegisterSensor
void RegisterSensor(const Name &rSensorName)
Definition: Mapper.cpp:44
karto::ScanSolver::AddNode
virtual void AddNode(Vertex< LocalizedRangeScan > *)
Definition: Mapper.h:861
karto::MapperSensorManager::GetScanManager
ScanManager * GetScanManager(LocalizedRangeScan *pScan)
Definition: Mapper.h:1557
karto::Mapper::setParamMinimumTravelDistance
void setParamMinimumTravelDistance(double d)
Definition: Mapper.cpp:1756
karto::Mapper::getParamLinkMatchMinimumResponseFine
double getParamLinkMatchMinimumResponseFine()
Definition: Mapper.cpp:1623
karto::Mapper::getParamLoopSearchSpaceResolution
double getParamLoopSearchSpaceResolution()
Definition: Mapper.cpp:1687
karto::Mapper::getParamMinimumDistancePenalty
double getParamMinimumDistancePenalty()
Definition: Mapper.cpp:1729
karto::Mapper::m_pUseResponseExpansion
Parameter< kt_bool > * m_pUseResponseExpansion
Definition: Mapper.h:2128
karto::Vector2::SquaredDistance
kt_double SquaredDistance(const Vector2 &rOther) const
Definition: Karto.h:1031
karto::Edge
Definition: Mapper.h:203
karto::CorrelationGrid::GridIndex
virtual kt_int32s GridIndex(const Vector2< kt_int32s > &rGrid, kt_bool boundaryCheck=true) const
Definition: Mapper.h:940
karto::ScanMatcher::GetResponse
kt_double GetResponse(kt_int32u angleIndex, kt_int32s gridPositionIndex) const
Definition: Mapper.cpp:799
karto::Pose2::GetHeading
kt_double GetHeading() const
Definition: Karto.h:2064
karto::MapperSensorManager::Clear
void Clear()
Definition: Mapper.cpp:103
karto::LaserRangeScan::GetRangeReadingsVector
RangeReadingsVector GetRangeReadingsVector() const
Definition: Karto.h:5039
karto::Mapper::setParamLoopMatchMinimumResponseFine
void setParamLoopMatchMinimumResponseFine(double d)
Definition: Mapper.cpp:1811
karto::SensorData::GetTime
kt_double GetTime() const
Definition: Karto.h:4893
karto::ScanMatcher::ScanMatcher
ScanMatcher(Mapper *pMapper)
Definition: Mapper.h:1268
karto::Mapper::getParamCorrelationSearchSpaceDimension
double getParamCorrelationSearchSpaceDimension()
Definition: Mapper.cpp:1665
karto
Definition: Karto.h:73
karto::Mapper::m_pCorrelationSearchSpaceDimension
Parameter< kt_double > * m_pCorrelationSearchSpaceDimension
Definition: Mapper.h:2070
karto::MapperGraph::AddEdge
Edge< LocalizedRangeScan > * AddEdge(LocalizedRangeScan *pSourceScan, LocalizedRangeScan *pTargetScan, kt_bool &rIsNewEdge)
Definition: Mapper.cpp:1031
karto::Mapper::getParamMinimumTimeInterval
double getParamMinimumTimeInterval()
Definition: Mapper.cpp:1598
karto::Grid::GetHeight
kt_int32s GetHeight() const
Definition: Karto.h:4592
karto::SensorData::GetSensorName
const Name & GetSensorName() const
Definition: Karto.h:4911


open_karto
Author(s):
autogenerated on Tue Jul 23 2024 02:26:00