Mapper.h
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 #ifndef OPEN_KARTO_MAPPER_H
19 #define OPEN_KARTO_MAPPER_H
20 
21 #include <map>
22 #include <set>
23 #include <vector>
24 #include <queue>
25 
26 #include <open_karto/Karto.h>
27 
28 namespace karto
29 {
31  // Listener classes
32 
37  {
38  public:
42  virtual void Info(const std::string& /*rInfo*/) {};
43  };
44 
49  {
50  public:
54  virtual void Debug(const std::string& /*rInfo*/) {};
55  };
56 
61  {
62  public:
66  virtual void LoopClosureCheck(const std::string& /*rInfo*/) {};
67 
71  virtual void BeginLoopClosure(const std::string& /*rInfo*/) {};
72 
76  virtual void EndLoopClosure(const std::string& /*rInfo*/) {};
77  }; // MapperListener
78 
82 
86  class EdgeLabel
87  {
88  public:
93  {
94  }
95 
99  virtual ~EdgeLabel()
100  {
101  }
102  }; // EdgeLabel
103 
107 
108  // A LinkInfo object contains the requisite information for the "spring"
109  // that links two scans together--the pose difference and the uncertainty
110  // (represented by a covariance matrix).
111  class LinkInfo : public EdgeLabel
112  {
113  public:
120  LinkInfo(const Pose2& rPose1, const Pose2& rPose2, const Matrix3& rCovariance)
121  {
122  Update(rPose1, rPose2, rCovariance);
123  }
124 
128  virtual ~LinkInfo()
129  {
130  }
131 
132  public:
139  void Update(const Pose2& rPose1, const Pose2& rPose2, const Matrix3& rCovariance)
140  {
141  m_Pose1 = rPose1;
142  m_Pose2 = rPose2;
143 
144  // transform second pose into the coordinate system of the first pose
145  Transform transform(rPose1, Pose2());
146  m_PoseDifference = transform.TransformPose(rPose2);
147 
148  // transform covariance into reference of first pose
149  Matrix3 rotationMatrix;
150  rotationMatrix.FromAxisAngle(0, 0, 1, -rPose1.GetHeading());
151 
152  m_Covariance = rotationMatrix * rCovariance * rotationMatrix.Transpose();
153  }
154 
159  inline const Pose2& GetPose1()
160  {
161  return m_Pose1;
162  }
163 
168  inline const Pose2& GetPose2()
169  {
170  return m_Pose2;
171  }
172 
177  inline const Pose2& GetPoseDifference()
178  {
179  return m_PoseDifference;
180  }
181 
186  inline const Matrix3& GetCovariance()
187  {
188  return m_Covariance;
189  }
190 
191  private:
196  }; // LinkInfo
197 
201 
202  template<typename T>
203  class Edge;
204 
208  template<typename T>
209  class Vertex
210  {
211  friend class Edge<T>;
212 
213  public:
218  Vertex(T* pObject)
219  : m_pObject(pObject)
220  {
221  }
222 
226  virtual ~Vertex()
227  {
228  }
229 
234  inline const std::vector<Edge<T>*>& GetEdges() const
235  {
236  return m_Edges;
237  }
238 
243  inline T* GetObject() const
244  {
245  return m_pObject;
246  }
247 
252  std::vector<Vertex<T>*> GetAdjacentVertices() const
253  {
254  std::vector<Vertex<T>*> vertices;
255 
256  const_forEach(typename std::vector<Edge<T>*>, &m_Edges)
257  {
258  Edge<T>* pEdge = *iter;
259 
260  // check both source and target because we have a undirected graph
261  if (pEdge->GetSource() != this)
262  {
263  vertices.push_back(pEdge->GetSource());
264  }
265 
266  if (pEdge->GetTarget() != this)
267  {
268  vertices.push_back(pEdge->GetTarget());
269  }
270  }
271 
272  return vertices;
273  }
274 
275  private:
280  inline void AddEdge(Edge<T>* pEdge)
281  {
282  m_Edges.push_back(pEdge);
283  }
284 
286  std::vector<Edge<T>*> m_Edges;
287  }; // Vertex<T>
288 
292 
296  template<typename T>
297  class Edge
298  {
299  public:
305  Edge(Vertex<T>* pSource, Vertex<T>* pTarget)
306  : m_pSource(pSource)
307  , m_pTarget(pTarget)
308  , m_pLabel(NULL)
309  {
310  m_pSource->AddEdge(this);
311  m_pTarget->AddEdge(this);
312  }
313 
317  virtual ~Edge()
318  {
319  m_pSource = NULL;
320  m_pTarget = NULL;
321 
322  if (m_pLabel != NULL)
323  {
324  delete m_pLabel;
325  m_pLabel = NULL;
326  }
327  }
328 
329  public:
334  inline Vertex<T>* GetSource() const
335  {
336  return m_pSource;
337  }
338 
343  inline Vertex<T>* GetTarget() const
344  {
345  return m_pTarget;
346  }
347 
352  inline EdgeLabel* GetLabel()
353  {
354  return m_pLabel;
355  }
356 
361  inline void SetLabel(EdgeLabel* pLabel)
362  {
363  m_pLabel = pLabel;
364  }
365 
366  private:
370  }; // class Edge<T>
371 
375 
379  template<typename T>
380  class Visitor
381  {
382  public:
388  virtual kt_bool Visit(Vertex<T>* pVertex) = 0;
389  }; // Visitor<T>
390 
394 
395  template<typename T>
396  class Graph;
397 
401  template<typename T>
403  {
404  public:
410  : m_pGraph(pGraph)
411  {
412  }
413 
417  virtual ~GraphTraversal()
418  {
419  }
420 
421  public:
427  virtual std::vector<T*> Traverse(Vertex<T>* pStartVertex, Visitor<T>* pVisitor) = 0;
428 
429  protected:
434  }; // GraphTraversal<T>
435 
439 
443  template<typename T>
444  class Graph
445  {
446  public:
450  typedef std::map<Name, std::vector<Vertex<T>*> > VertexMap;
451 
452  public:
457  {
458  }
459 
463  virtual ~Graph()
464  {
465  Clear();
466  }
467 
468  public:
474  inline void AddVertex(const Name& rName, Vertex<T>* pVertex)
475  {
476  m_Vertices[rName].push_back(pVertex);
477  }
478 
483  inline void AddEdge(Edge<T>* pEdge)
484  {
485  m_Edges.push_back(pEdge);
486  }
487 
491  void Clear()
492  {
493  forEachAs(typename VertexMap, &m_Vertices, indexIter)
494  {
495  // delete each vertex
496  forEach(typename std::vector<Vertex<T>*>, &(indexIter->second))
497  {
498  delete *iter;
499  }
500  }
501  m_Vertices.clear();
502 
503  const_forEach(typename std::vector<Edge<T>*>, &m_Edges)
504  {
505  delete *iter;
506  }
507  m_Edges.clear();
508  }
509 
514  inline const std::vector<Edge<T>*>& GetEdges() const
515  {
516  return m_Edges;
517  }
518 
523  inline const VertexMap& GetVertices() const
524  {
525  return m_Vertices;
526  }
527 
528  protected:
533 
537  std::vector<Edge<T>*> m_Edges;
538  }; // Graph<T>
539 
543 
544  template<typename T>
546  {
547  public:
552  : GraphTraversal<T>(pGraph)
553  {
554  }
555 
560  {
561  }
562 
563  public:
570  virtual std::vector<T*> Traverse(Vertex<T>* pStartVertex, Visitor<T>* pVisitor)
571  {
572  std::queue<Vertex<T>*> toVisit;
573  std::set<Vertex<T>*> seenVertices;
574  std::vector<Vertex<T>*> validVertices;
575 
576  toVisit.push(pStartVertex);
577  seenVertices.insert(pStartVertex);
578 
579  do
580  {
581  Vertex<T>* pNext = toVisit.front();
582  toVisit.pop();
583 
584  if (pVisitor->Visit(pNext))
585  {
586  // vertex is valid, explore neighbors
587  validVertices.push_back(pNext);
588 
589  std::vector<Vertex<T>*> adjacentVertices = pNext->GetAdjacentVertices();
590  forEach(typename std::vector<Vertex<T>*>, &adjacentVertices)
591  {
592  Vertex<T>* pAdjacent = *iter;
593 
594  // adjacent vertex has not yet been seen, add to queue for processing
595  if (seenVertices.find(pAdjacent) == seenVertices.end())
596  {
597  toVisit.push(pAdjacent);
598  seenVertices.insert(pAdjacent);
599  }
600  }
601  }
602  } while (toVisit.empty() == false);
603 
604  std::vector<T*> objects;
605  forEach(typename std::vector<Vertex<T>*>, &validVertices)
606  {
607  objects.push_back((*iter)->GetObject());
608  }
609 
610  return objects;
611  }
612  }; // class BreadthFirstTraversal
613 
617 
618  class NearScanVisitor : public Visitor<LocalizedRangeScan>
619  {
620  public:
621  NearScanVisitor(LocalizedRangeScan* pScan, kt_double maxDistance, kt_bool useScanBarycenter)
622  : m_MaxDistanceSquared(math::Square(maxDistance))
623  , m_UseScanBarycenter(useScanBarycenter)
624  {
626  }
627 
629  {
630  LocalizedRangeScan* pScan = pVertex->GetObject();
631 
633 
634  kt_double squaredDistance = pose.GetPosition().SquaredDistance(m_CenterPose.GetPosition());
635  return (squaredDistance <= m_MaxDistanceSquared - KT_TOLERANCE);
636  }
637 
638  protected:
642  }; // NearScanVisitor
643 
647 
648  class Mapper;
649  class ScanMatcher;
650 
654  class KARTO_EXPORT MapperGraph : public Graph<LocalizedRangeScan>
655  {
656  public:
662  MapperGraph(Mapper* pMapper, kt_double rangeThreshold);
663 
667  virtual ~MapperGraph();
668 
669  public:
674  void AddVertex(LocalizedRangeScan* pScan);
675 
684  Edge<LocalizedRangeScan>* AddEdge(LocalizedRangeScan* pSourceScan,
685  LocalizedRangeScan* pTargetScan,
686  kt_bool& rIsNewEdge);
687 
693  void AddEdges(LocalizedRangeScan* pScan, const Matrix3& rCovariance);
694 
700  kt_bool TryCloseLoop(LocalizedRangeScan* pScan, const Name& rSensorName);
701 
707  LocalizedRangeScanVector FindNearLinkedScans(LocalizedRangeScan* pScan, kt_double maxDistance);
708 
714  {
715  return m_pLoopScanMatcher;
716  }
717 
718  private:
725  {
726  return m_Vertices[pScan->GetSensorName()][pScan->GetStateId()];
727  }
728 
734  LocalizedRangeScan* GetClosestScanToPose(const LocalizedRangeScanVector& rScans, const Pose2& rPose) const;
735 
743  void LinkScans(LocalizedRangeScan* pFromScan,
744  LocalizedRangeScan* pToScan,
745  const Pose2& rMean,
746  const Matrix3& rCovariance);
747 
754  void LinkNearChains(LocalizedRangeScan* pScan, Pose2Vector& rMeans, std::vector<Matrix3>& rCovariances);
755 
763  void LinkChainToScan(const LocalizedRangeScanVector& rChain,
764  LocalizedRangeScan* pScan,
765  const Pose2& rMean,
766  const Matrix3& rCovariance);
767 
773  std::vector<LocalizedRangeScanVector> FindNearChains(LocalizedRangeScan* pScan);
774 
781  Pose2 ComputeWeightedMean(const Pose2Vector& rMeans, const std::vector<Matrix3>& rCovariances) const;
782 
791  LocalizedRangeScanVector FindPossibleLoopClosure(LocalizedRangeScan* pScan,
792  const Name& rSensorName,
793  kt_int32u& rStartNum);
794 
798  void CorrectPoses();
799 
800  private:
805 
810 
815  }; // MapperGraph
816 
820 
825  {
826  public:
830  typedef std::vector<std::pair<kt_int32s, Pose2> > IdPoseVector;
831 
836  {
837  }
838 
842  virtual ~ScanSolver()
843  {
844  }
845 
846  public:
850  virtual void Compute() = 0;
851 
856  virtual const IdPoseVector& GetCorrections() const = 0;
857 
861  virtual void AddNode(Vertex<LocalizedRangeScan>* /*pVertex*/)
862  {
863  }
864 
868  virtual void RemoveNode(kt_int32s /*id*/)
869  {
870  }
871 
875  virtual void AddConstraint(Edge<LocalizedRangeScan>* /*pEdge*/)
876  {
877  }
878 
882  virtual void RemoveConstraint(kt_int32s /*sourceId*/, kt_int32s /*targetId*/)
883  {
884  }
885 
889  virtual void Clear() {};
890  }; // ScanSolver
891 
895 
899  class CorrelationGrid : public Grid<kt_int8u>
900  {
901  public:
906  {
907  delete [] m_pKernel;
908  }
909 
910  public:
920  kt_int32s height,
921  kt_double resolution,
922  kt_double smearDeviation)
923  {
924  assert(resolution != 0.0);
925 
926  // +1 in case of roundoff
927  kt_int32u borderSize = GetHalfKernelSize(smearDeviation, resolution) + 1;
928 
929  CorrelationGrid* pGrid = new CorrelationGrid(width, height, borderSize, resolution, smearDeviation);
930 
931  return pGrid;
932  }
933 
940  virtual kt_int32s GridIndex(const Vector2<kt_int32s>& rGrid, kt_bool boundaryCheck = true) const
941  {
942  kt_int32s x = rGrid.GetX() + m_Roi.GetX();
943  kt_int32s y = rGrid.GetY() + m_Roi.GetY();
944 
945  return Grid<kt_int8u>::GridIndex(Vector2<kt_int32s>(x, y), boundaryCheck);
946  }
947 
952  inline const Rectangle2<kt_int32s>& GetROI() const
953  {
954  return m_Roi;
955  }
956 
961  inline void SetROI(const Rectangle2<kt_int32s>& roi)
962  {
963  m_Roi = roi;
964  }
965 
970  inline void SmearPoint(const Vector2<kt_int32s>& rGridPoint)
971  {
972  assert(m_pKernel != NULL);
973 
974  int gridIndex = GridIndex(rGridPoint);
975  if (GetDataPointer()[gridIndex] != GridStates_Occupied)
976  {
977  return;
978  }
979 
980  kt_int32s halfKernel = m_KernelSize / 2;
981 
982  // apply kernel
983  for (kt_int32s j = -halfKernel; j <= halfKernel; j++)
984  {
985  kt_int8u* pGridAdr = GetDataPointer(Vector2<kt_int32s>(rGridPoint.GetX(), rGridPoint.GetY() + j));
986 
987  kt_int32s kernelConstant = (halfKernel) + m_KernelSize * (j + halfKernel);
988 
989  // if a point is on the edge of the grid, there is no problem
990  // with running over the edge of allowable memory, because
991  // the grid has margins to compensate for the kernel size
992  for (kt_int32s i = -halfKernel; i <= halfKernel; i++)
993  {
994  kt_int32s kernelArrayIndex = i + kernelConstant;
995 
996  kt_int8u kernelValue = m_pKernel[kernelArrayIndex];
997  if (kernelValue > pGridAdr[i])
998  {
999  // kernel value is greater, so set it to kernel value
1000  pGridAdr[i] = kernelValue;
1001  }
1002  }
1003  }
1004  }
1005 
1006  protected:
1015  CorrelationGrid(kt_int32u width, kt_int32u height, kt_int32u borderSize,
1016  kt_double resolution, kt_double smearDeviation)
1017  : Grid<kt_int8u>(width + borderSize * 2, height + borderSize * 2)
1018  , m_SmearDeviation(smearDeviation)
1019  , m_pKernel(NULL)
1020  {
1021  GetCoordinateConverter()->SetScale(1.0 / resolution);
1022 
1023  // setup region of interest
1024  m_Roi = Rectangle2<kt_int32s>(borderSize, borderSize, width, height);
1025 
1026  // calculate kernel
1027  CalculateKernel();
1028  }
1029 
1033  virtual void CalculateKernel()
1034  {
1035  kt_double resolution = GetResolution();
1036 
1037  assert(resolution != 0.0);
1038  assert(m_SmearDeviation != 0.0);
1039 
1040  // min and max distance deviation for smearing;
1041  // will smear for two standard deviations, so deviation must be at least 1/2 of the resolution
1042  const kt_double MIN_SMEAR_DISTANCE_DEVIATION = 0.5 * resolution;
1043  const kt_double MAX_SMEAR_DISTANCE_DEVIATION = 10 * resolution;
1044 
1045  // check if given value too small or too big
1046  if (!math::InRange(m_SmearDeviation, MIN_SMEAR_DISTANCE_DEVIATION, MAX_SMEAR_DISTANCE_DEVIATION))
1047  {
1048  std::stringstream error;
1049  error << "Mapper Error: Smear deviation too small: Must be between "
1050  << MIN_SMEAR_DISTANCE_DEVIATION
1051  << " and "
1052  << MAX_SMEAR_DISTANCE_DEVIATION;
1053  throw std::runtime_error(error.str());
1054  }
1055 
1056  // NOTE: Currently assumes a two-dimensional kernel
1057 
1058  // +1 for center
1059  m_KernelSize = 2 * GetHalfKernelSize(m_SmearDeviation, resolution) + 1;
1060 
1061  // allocate kernel
1063  if (m_pKernel == NULL)
1064  {
1065  throw std::runtime_error("Unable to allocate memory for kernel!");
1066  }
1067 
1068  // calculate kernel
1069  kt_int32s halfKernel = m_KernelSize / 2;
1070  for (kt_int32s i = -halfKernel; i <= halfKernel; i++)
1071  {
1072  for (kt_int32s j = -halfKernel; j <= halfKernel; j++)
1073  {
1074 #ifdef WIN32
1075  kt_double distanceFromMean = _hypot(i * resolution, j * resolution);
1076 #else
1077  kt_double distanceFromMean = hypot(i * resolution, j * resolution);
1078 #endif
1079  kt_double z = exp(-0.5 * pow(distanceFromMean / m_SmearDeviation, 2));
1080 
1081  kt_int32u kernelValue = static_cast<kt_int32u>(math::Round(z * GridStates_Occupied));
1082  assert(math::IsUpTo(kernelValue, static_cast<kt_int32u>(255)));
1083 
1084  int kernelArrayIndex = (i + halfKernel) + m_KernelSize * (j + halfKernel);
1085  m_pKernel[kernelArrayIndex] = static_cast<kt_int8u>(kernelValue);
1086  }
1087  }
1088  }
1089 
1097  static kt_int32s GetHalfKernelSize(kt_double smearDeviation, kt_double resolution)
1098  {
1099  assert(resolution != 0.0);
1100 
1101  return static_cast<kt_int32s>(math::Round(2.0 * smearDeviation / resolution));
1102  }
1103 
1104  private:
1110 
1111  // Size of one side of the kernel
1113 
1114  // Cached kernel for smearing
1116 
1117  // region of interest
1119  }; // CorrelationGrid
1120 
1124 
1129  {
1130  public:
1134  virtual ~ScanMatcher();
1135 
1136  public:
1140  static ScanMatcher* Create(Mapper* pMapper,
1141  kt_double searchSize,
1142  kt_double resolution,
1143  kt_double smearDeviation,
1144  kt_double rangeThreshold);
1145 
1156  kt_double MatchScan(LocalizedRangeScan* pScan,
1157  const LocalizedRangeScanVector& rBaseScans,
1158  Pose2& rMean, Matrix3& rCovariance,
1159  kt_bool doPenalize = true,
1160  kt_bool doRefineMatch = true);
1161 
1178  kt_double CorrelateScan(LocalizedRangeScan* pScan,
1179  const Pose2& rSearchCenter,
1180  const Vector2<kt_double>& rSearchSpaceOffset,
1181  const Vector2<kt_double>& rSearchSpaceResolution,
1182  kt_double searchAngleOffset,
1183  kt_double searchAngleResolution,
1184  kt_bool doPenalize,
1185  Pose2& rMean,
1186  Matrix3& rCovariance,
1187  kt_bool doingFineMatch);
1188 
1199  void ComputePositionalCovariance(const Pose2& rBestPose,
1200  kt_double bestResponse,
1201  const Pose2& rSearchCenter,
1202  const Vector2<kt_double>& rSearchSpaceOffset,
1203  const Vector2<kt_double>& rSearchSpaceResolution,
1204  kt_double searchAngleResolution,
1205  Matrix3& rCovariance);
1206 
1216  void ComputeAngularCovariance(const Pose2& rBestPose,
1217  kt_double bestResponse,
1218  const Pose2& rSearchCenter,
1219  kt_double searchAngleOffset,
1220  kt_double searchAngleResolution,
1221  Matrix3& rCovariance);
1222 
1228  {
1229  return m_pCorrelationGrid;
1230  }
1231 
1232  private:
1238  void AddScans(const LocalizedRangeScanVector& rScans, Vector2<kt_double> viewPoint);
1239 
1246  void AddScan(LocalizedRangeScan* pScan, const Vector2<kt_double>& rViewPoint, kt_bool doSmear = true);
1247 
1254  PointVectorDouble FindValidPoints(LocalizedRangeScan* pScan, const Vector2<kt_double>& rViewPoint) const;
1255 
1262  kt_double GetResponse(kt_int32u angleIndex, kt_int32s gridPositionIndex) const;
1263 
1264  protected:
1269  : m_pMapper(pMapper)
1270  , m_pCorrelationGrid(NULL)
1271  , m_pSearchSpaceProbs(NULL)
1272  , m_pGridLookup(NULL)
1273  {
1274  }
1275 
1276  private:
1278 
1281 
1283  }; // ScanMatcher
1284 
1288 
1293  {
1294  public:
1298  ScanManager(kt_int32u runningBufferMaximumSize, kt_double runningBufferMaximumDistance)
1299  : m_pLastScan(NULL)
1300  , m_RunningBufferMaximumSize(runningBufferMaximumSize)
1301  , m_RunningBufferMaximumDistance(runningBufferMaximumDistance)
1302  {
1303  }
1304 
1308  virtual ~ScanManager()
1309  {
1310  Clear();
1311  }
1312 
1313  public:
1318  inline void AddScan(LocalizedRangeScan* pScan, kt_int32s uniqueId)
1319  {
1320  // assign state id to scan
1321  pScan->SetStateId(static_cast<kt_int32u>(m_Scans.size()));
1322 
1323  // assign unique id to scan
1324  pScan->SetUniqueId(uniqueId);
1325 
1326  // add it to scan buffer
1327  m_Scans.push_back(pScan);
1328  }
1329 
1336  {
1337  return m_pLastScan;
1338  }
1339 
1344  inline void SetLastScan(LocalizedRangeScan* pScan)
1345  {
1346  m_pLastScan = pScan;
1347  }
1348 
1354  {
1355  return m_Scans;
1356  }
1357 
1363  {
1364  return m_RunningScans;
1365  }
1366 
1372  {
1373  m_RunningScans.push_back(pScan);
1374 
1375  // vector has at least one element (first line of this function), so this is valid
1376  Pose2 frontScanPose = m_RunningScans.front()->GetSensorPose();
1377  Pose2 backScanPose = m_RunningScans.back()->GetSensorPose();
1378 
1379  // cap vector size and remove all scans from front of vector that are too far from end of vector
1380  kt_double squaredDistance = frontScanPose.GetPosition().SquaredDistance(backScanPose.GetPosition());
1381  while (m_RunningScans.size() > m_RunningBufferMaximumSize ||
1383  {
1384  // remove front of running scans
1385  m_RunningScans.erase(m_RunningScans.begin());
1386 
1387  // recompute stats of running scans
1388  frontScanPose = m_RunningScans.front()->GetSensorPose();
1389  backScanPose = m_RunningScans.back()->GetSensorPose();
1390  squaredDistance = frontScanPose.GetPosition().SquaredDistance(backScanPose.GetPosition());
1391  }
1392  }
1393 
1397  void Clear()
1398  {
1399  m_Scans.clear();
1400  m_RunningScans.clear();
1401  }
1402 
1403  private:
1407 
1410  }; // ScanManager
1411 
1415 
1419  class KARTO_EXPORT MapperSensorManager // : public SensorManager
1420  {
1421  typedef std::map<Name, ScanManager*> ScanManagerMap;
1422 
1423  public:
1427  MapperSensorManager(kt_int32u runningBufferMaximumSize, kt_double runningBufferMaximumDistance)
1428  : m_RunningBufferMaximumSize(runningBufferMaximumSize)
1429  , m_RunningBufferMaximumDistance(runningBufferMaximumDistance)
1430  , m_NextScanId(0)
1431  {
1432  }
1433 
1438  {
1439  Clear();
1440  }
1441 
1442  public:
1448  void RegisterSensor(const Name& rSensorName);
1449 
1456  LocalizedRangeScan* GetScan(const Name& rSensorName, kt_int32s scanIndex);
1457 
1462  inline std::vector<Name> GetSensorNames()
1463  {
1464  std::vector<Name> deviceNames;
1465  const_forEach(ScanManagerMap, &m_ScanManagers)
1466  {
1467  deviceNames.push_back(iter->first);
1468  }
1469 
1470  return deviceNames;
1471  }
1472 
1478  inline LocalizedRangeScan* GetLastScan(const Name& rSensorName)
1479  {
1480  RegisterSensor(rSensorName);
1481 
1482  return GetScanManager(rSensorName)->GetLastScan();
1483  }
1484 
1489  inline void SetLastScan(LocalizedRangeScan* pScan)
1490  {
1491  GetScanManager(pScan)->SetLastScan(pScan);
1492  }
1493 
1500  {
1501  assert(math::IsUpTo(id, (kt_int32s)m_Scans.size()));
1502 
1503  return m_Scans[id];
1504  }
1505 
1510  void AddScan(LocalizedRangeScan* pScan);
1511 
1517  {
1518  GetScanManager(pScan)->AddRunningScan(pScan);
1519  }
1520 
1526  inline LocalizedRangeScanVector& GetScans(const Name& rSensorName)
1527  {
1528  return GetScanManager(rSensorName)->GetScans();
1529  }
1530 
1536  inline LocalizedRangeScanVector& GetRunningScans(const Name& rSensorName)
1537  {
1538  return GetScanManager(rSensorName)->GetRunningScans();
1539  }
1540 
1545  LocalizedRangeScanVector GetAllScans();
1546 
1550  void Clear();
1551 
1552  private:
1558  {
1559  return GetScanManager(pScan->GetSensorName());
1560  }
1561 
1567  inline ScanManager* GetScanManager(const Name& rSensorName)
1568  {
1569  if (m_ScanManagers.find(rSensorName) != m_ScanManagers.end())
1570  {
1571  return m_ScanManagers[rSensorName];
1572  }
1573 
1574  return NULL;
1575  }
1576 
1577  private:
1578  // map from device ID to scan data
1580 
1583 
1585 
1586  std::vector<LocalizedRangeScan*> m_Scans;
1587  }; // MapperSensorManager
1588 
1592 
1750  class KARTO_EXPORT Mapper : public Module
1751  {
1752  friend class MapperGraph;
1753  friend class ScanMatcher;
1754 
1755  public:
1759  Mapper();
1760 
1765  Mapper(const std::string& rName);
1766 
1770  virtual ~Mapper();
1771 
1772  public:
1777  void Initialize(kt_double rangeThreshold);
1778 
1783  void Reset();
1784 
1796  virtual kt_bool Process(LocalizedRangeScan* pScan);
1797 
1801  virtual kt_bool Process(Object* pObject);
1802 
1809  virtual const LocalizedRangeScanVector GetAllProcessedScans() const;
1810 
1815  void AddListener(MapperListener* pListener);
1816 
1821  void RemoveListener(MapperListener* pListener);
1822 
1827  void SetScanSolver(ScanSolver* pSolver);
1828 
1833  virtual MapperGraph* GetGraph() const;
1834 
1839  virtual ScanMatcher* GetSequentialScanMatcher() const;
1840 
1845  virtual ScanMatcher* GetLoopScanMatcher() const;
1846 
1852  {
1853  return m_pMapperSensorManager;
1854  }
1855 
1861  inline kt_bool TryCloseLoop(LocalizedRangeScan* pScan, const Name& rSensorName)
1862  {
1863  return m_pGraph->TryCloseLoop(pScan, rSensorName);
1864  }
1865 
1866  private:
1867  void InitializeParameters();
1868 
1876  kt_bool HasMovedEnough(LocalizedRangeScan* pScan, LocalizedRangeScan* pLastScan) const;
1877 
1878  public:
1880  // fire information for listeners!!
1881 
1886  void FireInfo(const std::string& rInfo) const;
1887 
1892  void FireDebug(const std::string& rInfo) const;
1893 
1898  void FireLoopClosureCheck(const std::string& rInfo) const;
1899 
1904  void FireBeginLoopClosure(const std::string& rInfo) const;
1905 
1910  void FireEndLoopClosure(const std::string& rInfo) const;
1911 
1912  // FireRunningScansUpdated
1913 
1914  // FireCovarianceCalculated
1915 
1916  // FireLoopClosureChain
1917 
1918  private:
1922  Mapper(const Mapper&);
1923 
1927  const Mapper& operator=(const Mapper&);
1928 
1929  public:
1930  void SetUseScanMatching(kt_bool val) { m_pUseScanMatching->SetValue(val); }
1931 
1932  private:
1934 
1936 
1938 
1941 
1942  std::vector<MapperListener*> m_Listeners;
1943 
1944 
1954 
1959 
1972 
1982 
1992 
2002 
2009 
2015 
2022 
2028 
2035 
2043 
2050 
2056 
2062 
2064  // CorrelationParameters correlationParameters;
2065 
2071 
2077 
2083 
2084 
2086  // CorrelationParameters loopCorrelationParameters;
2087 
2093 
2099 
2105 
2107  // ScanMatcherParameters;
2108 
2109  // Variance of penalty for deviating from odometry when scan-matching.
2110  // The penalty is a multiplier (less than 1.0) is a function of the
2111  // delta of the scan position being tested and the odometric pose
2114 
2115  // The range of angles to search during a coarse search and a finer search
2118 
2119  // Resolution of angles to search during a coarse search
2121 
2122  // Minimum value of the penalty multiplier so scores do not
2123  // become too small
2126 
2127  // whether to increase the search space if no good matches are initially found
2129 
2130  public:
2131  /* Abstract methods for parameter setters and getters */
2132 
2133  /* Getters */
2134  // General Parameters
2135  bool getParamUseScanMatching();
2136  bool getParamUseScanBarycenter();
2137  double getParamMinimumTimeInterval();
2138  double getParamMinimumTravelDistance();
2139  double getParamMinimumTravelHeading();
2140  int getParamScanBufferSize();
2141  double getParamScanBufferMaximumScanDistance();
2142  double getParamLinkMatchMinimumResponseFine();
2143  double getParamLinkScanMaximumDistance();
2144  double getParamLoopSearchMaximumDistance();
2145  bool getParamDoLoopClosing();
2146  int getParamLoopMatchMinimumChainSize();
2147  double getParamLoopMatchMaximumVarianceCoarse();
2148  double getParamLoopMatchMinimumResponseCoarse();
2149  double getParamLoopMatchMinimumResponseFine();
2150 
2151  // Correlation Parameters - Correlation Parameters
2152  double getParamCorrelationSearchSpaceDimension();
2153  double getParamCorrelationSearchSpaceResolution();
2154  double getParamCorrelationSearchSpaceSmearDeviation();
2155 
2156  // Correlation Parameters - Loop Closure Parameters
2157  double getParamLoopSearchSpaceDimension();
2158  double getParamLoopSearchSpaceResolution();
2159  double getParamLoopSearchSpaceSmearDeviation();
2160 
2161  // Scan Matcher Parameters
2162  double getParamDistanceVariancePenalty();
2163  double getParamAngleVariancePenalty();
2164  double getParamFineSearchAngleOffset();
2165  double getParamCoarseSearchAngleOffset();
2166  double getParamCoarseAngleResolution();
2167  double getParamMinimumAnglePenalty();
2168  double getParamMinimumDistancePenalty();
2169  bool getParamUseResponseExpansion();
2170 
2171  /* Setters */
2172  // General Parameters
2173  void setParamUseScanMatching(bool b);
2174  void setParamUseScanBarycenter(bool b);
2175  void setParamMinimumTimeInterval(double d);
2176  void setParamMinimumTravelDistance(double d);
2177  void setParamMinimumTravelHeading(double d);
2178  void setParamScanBufferSize(int i);
2179  void setParamScanBufferMaximumScanDistance(double d);
2180  void setParamLinkMatchMinimumResponseFine(double d);
2181  void setParamLinkScanMaximumDistance(double d);
2182  void setParamLoopSearchMaximumDistance(double d);
2183  void setParamDoLoopClosing(bool b);
2184  void setParamLoopMatchMinimumChainSize(int i);
2185  void setParamLoopMatchMaximumVarianceCoarse(double d);
2186  void setParamLoopMatchMinimumResponseCoarse(double d);
2187  void setParamLoopMatchMinimumResponseFine(double d);
2188 
2189  // Correlation Parameters - Correlation Parameters
2190  void setParamCorrelationSearchSpaceDimension(double d);
2191  void setParamCorrelationSearchSpaceResolution(double d);
2192  void setParamCorrelationSearchSpaceSmearDeviation(double d);
2193 
2194  // Correlation Parameters - Loop Closure Parameters
2195  void setParamLoopSearchSpaceDimension(double d);
2196  void setParamLoopSearchSpaceResolution(double d);
2197  void setParamLoopSearchSpaceSmearDeviation(double d);
2198 
2199  // Scan Matcher Parameters
2200  void setParamDistanceVariancePenalty(double d);
2201  void setParamAngleVariancePenalty(double d);
2202  void setParamFineSearchAngleOffset(double d);
2203  void setParamCoarseSearchAngleOffset(double d);
2204  void setParamCoarseAngleResolution(double d);
2205  void setParamMinimumAnglePenalty(double d);
2206  void setParamMinimumDistancePenalty(double d);
2207  void setParamUseResponseExpansion(bool b);
2208  };
2209 } // namespace karto
2210 
2211 #endif // OPEN_KARTO_MAPPER_H
karto::MapperDebugListener
Definition: Mapper.h:48
karto::Name
Definition: Karto.h:354
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
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::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::ScanSolver::RemoveConstraint
virtual void RemoveConstraint(kt_int32s, kt_int32s)
Definition: Mapper.h:882
karto::Mapper::m_pDoLoopClosing
Parameter< kt_bool > * m_pDoLoopClosing
Definition: Mapper.h:2027
karto::Vertex::m_Edges
std::vector< Edge< T > * > m_Edges
Definition: Mapper.h:286
karto::Pose2Vector
std::vector< Pose2 > Pose2Vector
Definition: Karto.h:2174
karto::BreadthFirstTraversal::~BreadthFirstTraversal
virtual ~BreadthFirstTraversal()
Definition: Mapper.h:559
karto::ScanManager::Clear
void Clear()
Definition: Mapper.h:1397
karto::Visitor::Visit
virtual kt_bool Visit(Vertex< T > *pVertex)=0
karto::Edge::Edge
Edge(Vertex< T > *pSource, Vertex< T > *pTarget)
Definition: Mapper.h:305
karto::LinkInfo::GetPose1
const Pose2 & GetPose1()
Definition: Mapper.h:159
karto::Visitor
Definition: Mapper.h:380
karto::CorrelationGrid::SetROI
void SetROI(const Rectangle2< kt_int32s > &roi)
Definition: Mapper.h:961
kt_double
double kt_double
Definition: Types.h:67
karto::ScanManager::ScanManager
ScanManager(kt_int32u runningBufferMaximumSize, kt_double runningBufferMaximumDistance)
Definition: Mapper.h:1298
karto::LocalizedRangeScan::GetReferencePose
Pose2 GetReferencePose(kt_bool useBarycenter) const
Definition: Karto.h:5277
karto::ScanManager::GetLastScan
LocalizedRangeScan * GetLastScan()
Definition: Mapper.h:1335
karto::Pose2::GetPosition
const Vector2< kt_double > & GetPosition() const
Definition: Karto.h:2046
karto::MapperGraph::GetLoopScanMatcher
ScanMatcher * GetLoopScanMatcher() const
Definition: Mapper.h:713
karto::Rectangle2::GetX
T GetX() const
Definition: Karto.h:1792
karto::Vertex::AddEdge
void AddEdge(Edge< T > *pEdge)
Definition: Mapper.h:280
karto::Module
Definition: Karto.h:762
karto::BreadthFirstTraversal::Traverse
virtual std::vector< T * > Traverse(Vertex< T > *pStartVertex, Visitor< T > *pVisitor)
Definition: Mapper.h:570
karto::Graph::m_Edges
std::vector< Edge< T > * > m_Edges
Definition: Mapper.h:537
karto::NearScanVisitor
Definition: Mapper.h:618
karto::Mapper::m_pLoopSearchMaximumDistance
Parameter< kt_double > * m_pLoopSearchMaximumDistance
Definition: Mapper.h:2034
karto::LinkInfo::Update
void Update(const Pose2 &rPose1, const Pose2 &rPose2, const Matrix3 &rCovariance)
Definition: Mapper.h:139
karto::MapperGraph::m_pMapper
Mapper * m_pMapper
Definition: Mapper.h:804
karto::ScanSolver::Compute
virtual void Compute()=0
karto::MapperSensorManager::MapperSensorManager
MapperSensorManager(kt_int32u runningBufferMaximumSize, kt_double runningBufferMaximumDistance)
Definition: Mapper.h:1427
karto::Vector2::GetX
const T & GetX() const
Definition: Karto.h:957
karto::Matrix3::Transpose
Matrix3 Transpose() const
Definition: Karto.h:2430
karto::CoordinateConverter::SetScale
void SetScale(kt_double scale)
Definition: Karto.h:4299
karto::ScanManager::~ScanManager
virtual ~ScanManager()
Definition: Mapper.h:1308
karto::BreadthFirstTraversal::BreadthFirstTraversal
BreadthFirstTraversal(Graph< T > *pGraph)
Definition: Mapper.h:551
karto::Grid< kt_int8u >::GetDataPointer
kt_int8u * GetDataPointer()
Definition: Karto.h:4619
karto::LocalizedRangeScan
Definition: Karto.h:5185
karto::ScanManager::AddScan
void AddScan(LocalizedRangeScan *pScan, kt_int32s uniqueId)
Definition: Mapper.h:1318
karto::ScanSolver::~ScanSolver
virtual ~ScanSolver()
Definition: Mapper.h:842
karto::Matrix3::FromAxisAngle
void FromAxisAngle(kt_double x, kt_double y, kt_double z, const kt_double radians)
Definition: Karto.h:2395
karto::NearScanVisitor::NearScanVisitor
NearScanVisitor(LocalizedRangeScan *pScan, kt_double maxDistance, kt_bool useScanBarycenter)
Definition: Mapper.h:621
karto::Mapper::TryCloseLoop
kt_bool TryCloseLoop(LocalizedRangeScan *pScan, const Name &rSensorName)
Definition: Mapper.h:1861
karto::LinkInfo::GetCovariance
const Matrix3 & GetCovariance()
Definition: Mapper.h:186
karto::MapperLoopClosureListener::EndLoopClosure
virtual void EndLoopClosure(const std::string &)
Definition: Mapper.h:76
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::NearScanVisitor::m_MaxDistanceSquared
kt_double m_MaxDistanceSquared
Definition: Mapper.h:640
karto::Mapper::m_pMinimumTimeInterval
Parameter< kt_double > * m_pMinimumTimeInterval
Definition: Mapper.h:1971
kt_int32s
int32_t kt_int32s
Definition: Types.h:51
karto::Grid::GridIndex
virtual kt_int32s GridIndex(const Vector2< kt_int32s > &rGrid, kt_bool boundaryCheck=true) const
Definition: Karto.h:4497
karto::Graph::~Graph
virtual ~Graph()
Definition: Mapper.h:463
karto::ScanManager::GetRunningScans
LocalizedRangeScanVector & GetRunningScans()
Definition: Mapper.h:1362
karto::CorrelationGrid::m_Roi
Rectangle2< kt_int32s > m_Roi
Definition: Mapper.h:1118
karto::SensorData::SetUniqueId
void SetUniqueId(kt_int32u uniqueId)
Definition: Karto.h:4884
karto::Matrix3
Definition: Karto.h:2347
karto::ScanSolver::IdPoseVector
std::vector< std::pair< kt_int32s, Pose2 > > IdPoseVector
Definition: Mapper.h:830
karto::Grid
Definition: Karto.h:4391
karto::MapperGraph::GetVertex
Vertex< LocalizedRangeScan > * GetVertex(LocalizedRangeScan *pScan)
Definition: Mapper.h:724
karto::MapperLoopClosureListener::LoopClosureCheck
virtual void LoopClosureCheck(const std::string &)
Definition: Mapper.h:66
karto::MapperSensorManager
Definition: Mapper.h:1419
karto::Vertex::GetObject
T * GetObject() const
Definition: Mapper.h:243
karto::Grid< kt_int8u >::GetCoordinateConverter
CoordinateConverter * GetCoordinateConverter() const
Definition: Karto.h:4657
Karto.h
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::SensorData::GetStateId
kt_int32s GetStateId() const
Definition: Karto.h:4857
karto::ScanMatcher::GetCorrelationGrid
CorrelationGrid * GetCorrelationGrid() const
Definition: Mapper.h:1227
karto::MapperGraph
Definition: Mapper.h:654
karto::Vector2::GetY
const T & GetY() const
Definition: Karto.h:975
karto::GraphTraversal::GraphTraversal
GraphTraversal(Graph< T > *pGraph)
Definition: Mapper.h:409
karto::ScanMatcher::m_pCorrelationGrid
CorrelationGrid * m_pCorrelationGrid
Definition: Mapper.h:1279
karto::MapperSensorManager::m_ScanManagers
ScanManagerMap m_ScanManagers
Definition: Mapper.h:1579
karto::Vertex::m_pObject
T * m_pObject
Definition: Mapper.h:285
karto::MapperSensorManager::GetLastScan
LocalizedRangeScan * GetLastScan(const Name &rSensorName)
Definition: Mapper.h:1478
karto::Mapper::m_pMapperSensorManager
MapperSensorManager * m_pMapperSensorManager
Definition: Mapper.h:1937
KARTO_EXPORT
#define KARTO_EXPORT
Definition: Macros.h:56
karto::Graph::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::CorrelationGrid::CorrelationGrid
CorrelationGrid(kt_int32u width, kt_int32u height, kt_int32u borderSize, kt_double resolution, kt_double smearDeviation)
Definition: Mapper.h:1015
karto::Parameter< kt_bool >
karto::Grid< kt_int8u >::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::m_pMinimumTravelDistance
Parameter< kt_double > * m_pMinimumTravelDistance
Definition: Mapper.h:1981
karto::NearScanVisitor::m_UseScanBarycenter
kt_bool m_UseScanBarycenter
Definition: Mapper.h:641
karto::ScanManager::m_pLastScan
LocalizedRangeScan * m_pLastScan
Definition: Mapper.h:1406
karto::Graph::GetVertices
const VertexMap & GetVertices() const
Definition: Mapper.h:523
karto::ScanSolver::RemoveNode
virtual void RemoveNode(kt_int32s)
Definition: Mapper.h:868
karto::Vertex::GetAdjacentVertices
std::vector< Vertex< T > * > GetAdjacentVertices() const
Definition: Mapper.h:252
karto::GraphTraversal::~GraphTraversal
virtual ~GraphTraversal()
Definition: Mapper.h:417
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::MapperListener::Info
virtual void Info(const std::string &)
Definition: Mapper.h:42
karto::Edge::GetLabel
EdgeLabel * GetLabel()
Definition: Mapper.h:352
karto::GraphTraversal
Definition: Mapper.h:402
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::m_pLinkScanMaximumDistance
Parameter< kt_double > * m_pLinkScanMaximumDistance
Definition: Mapper.h:2021
karto::ScanManager::SetLastScan
void SetLastScan(LocalizedRangeScan *pScan)
Definition: Mapper.h:1344
karto::CorrelationGrid::m_KernelSize
kt_int32s m_KernelSize
Definition: Mapper.h:1112
karto::Mapper::m_pLoopMatchMinimumChainSize
Parameter< kt_int32u > * m_pLoopMatchMinimumChainSize
Definition: Mapper.h:2042
karto::CorrelationGrid::CalculateKernel
virtual void CalculateKernel()
Definition: Mapper.h:1033
karto::Mapper::m_pLoopSearchSpaceSmearDeviation
Parameter< kt_double > * m_pLoopSearchSpaceSmearDeviation
Definition: Mapper.h:2104
karto::Mapper::m_pGraph
MapperGraph * m_pGraph
Definition: Mapper.h:1939
karto::ScanManager
Definition: Mapper.h:1292
kt_bool
bool kt_bool
Definition: Types.h:64
karto::Vertex::~Vertex
virtual ~Vertex()
Definition: Mapper.h:226
karto::Mapper::m_pFineSearchAngleOffset
Parameter< kt_double > * m_pFineSearchAngleOffset
Definition: Mapper.h:2116
karto::Mapper::GetMapperSensorManager
MapperSensorManager * GetMapperSensorManager() const
Definition: Mapper.h:1851
karto::LinkInfo::m_Covariance
Matrix3 m_Covariance
Definition: Mapper.h:195
karto::EdgeLabel::~EdgeLabel
virtual ~EdgeLabel()
Definition: Mapper.h:99
karto::Edge::m_pLabel
EdgeLabel * m_pLabel
Definition: Mapper.h:369
karto::MapperSensorManager::ScanManagerMap
std::map< Name, ScanManager * > ScanManagerMap
Definition: Mapper.h:1421
karto::Graph::GetEdges
const std::vector< Edge< T > * > & GetEdges() const
Definition: Mapper.h:514
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::MapperSensorManager::GetScanManager
ScanManager * GetScanManager(const Name &rSensorName)
Definition: Mapper.h:1567
karto::LinkInfo::m_Pose1
Pose2 m_Pose1
Definition: Mapper.h:192
karto::LinkInfo::LinkInfo
LinkInfo(const Pose2 &rPose1, const Pose2 &rPose2, const Matrix3 &rCovariance)
Definition: Mapper.h:120
karto::Vector2< kt_int32s >
karto::ScanSolver::GetCorrections
virtual const IdPoseVector & GetCorrections() const =0
karto::Mapper::m_pLinkMatchMinimumResponseFine
Parameter< kt_double > * m_pLinkMatchMinimumResponseFine
Definition: Mapper.h:2014
karto::MapperLoopClosureListener::BeginLoopClosure
virtual void BeginLoopClosure(const std::string &)
Definition: Mapper.h:71
karto::Mapper::m_pSequentialScanMatcher
ScanMatcher * m_pSequentialScanMatcher
Definition: Mapper.h:1935
forEachAs
#define forEachAs(listtype, list, iter)
Definition: Macros.h:69
karto::CorrelationGrid::GetROI
const Rectangle2< kt_int32s > & GetROI() const
Definition: Mapper.h:952
karto::LinkInfo::m_PoseDifference
Pose2 m_PoseDifference
Definition: Mapper.h:194
karto::Mapper::m_pCorrelationSearchSpaceResolution
Parameter< kt_double > * m_pCorrelationSearchSpaceResolution
Definition: Mapper.h:2076
karto::Mapper::m_pCoarseSearchAngleOffset
Parameter< kt_double > * m_pCoarseSearchAngleOffset
Definition: Mapper.h:2117
karto::LinkInfo::m_Pose2
Pose2 m_Pose2
Definition: Mapper.h:193
karto::MapperSensorManager::GetScan
LocalizedRangeScan * GetScan(kt_int32s id)
Definition: Mapper.h:1499
karto::Edge::GetTarget
Vertex< T > * GetTarget() const
Definition: Mapper.h:343
karto::ScanManager::m_RunningScans
LocalizedRangeScanVector m_RunningScans
Definition: Mapper.h:1405
karto::Mapper::m_pMinimumAnglePenalty
Parameter< kt_double > * m_pMinimumAnglePenalty
Definition: Mapper.h:2124
karto::Transform
Definition: Karto.h:2862
karto::LinkInfo::GetPose2
const Pose2 & GetPose2()
Definition: Mapper.h:168
karto::GraphTraversal::Traverse
virtual std::vector< T * > Traverse(Vertex< T > *pStartVertex, Visitor< T > *pVisitor)=0
karto::Edge::SetLabel
void SetLabel(EdgeLabel *pLabel)
Definition: Mapper.h:361
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::ScanMatcher::m_pMapper
Mapper * m_pMapper
Definition: Mapper.h:1277
karto::Mapper::m_pCoarseAngleResolution
Parameter< kt_double > * m_pCoarseAngleResolution
Definition: Mapper.h:2120
karto::CorrelationGrid::~CorrelationGrid
virtual ~CorrelationGrid()
Definition: Mapper.h:905
karto::math::Square
T Square(T value)
Definition: Math.h:77
kt_int32u
uint32_t kt_int32u
Definition: Types.h:52
karto::MapperSensorManager::~MapperSensorManager
virtual ~MapperSensorManager()
Definition: Mapper.h:1437
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::Edge::m_pTarget
Vertex< T > * m_pTarget
Definition: Mapper.h:368
karto::Mapper::m_pLoopMatchMinimumResponseCoarse
Parameter< kt_double > * m_pLoopMatchMinimumResponseCoarse
Definition: Mapper.h:2055
karto::MapperSensorManager::AddRunningScan
void AddRunningScan(LocalizedRangeScan *pScan)
Definition: Mapper.h:1516
karto::CorrelationGrid::SmearPoint
void SmearPoint(const Vector2< kt_int32s > &rGridPoint)
Definition: Mapper.h:970
karto::Vertex
Definition: Mapper.h:209
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::EdgeLabel::EdgeLabel
EdgeLabel()
Definition: Mapper.h:92
karto::GridIndexLookup< kt_int8u >
karto::Mapper::m_pLoopMatchMinimumResponseFine
Parameter< kt_double > * m_pLoopMatchMinimumResponseFine
Definition: Mapper.h:2061
karto::Mapper::m_pMinimumTravelHeading
Parameter< kt_double > * m_pMinimumTravelHeading
Definition: Mapper.h:1991
karto::MapperSensorManager::m_RunningBufferMaximumDistance
kt_double m_RunningBufferMaximumDistance
Definition: Mapper.h:1582
karto::GraphTraversal::m_pGraph
Graph< T > * m_pGraph
Definition: Mapper.h:433
karto::LinkInfo::~LinkInfo
virtual ~LinkInfo()
Definition: Mapper.h:128
karto::Mapper::SetUseScanMatching
void SetUseScanMatching(kt_bool val)
Definition: Mapper.h:1930
karto::Graph::Graph
Graph()
Definition: Mapper.h:456
karto::Edge::m_pSource
Vertex< T > * m_pSource
Definition: Mapper.h:367
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::ScanManager::m_RunningBufferMaximumDistance
kt_double m_RunningBufferMaximumDistance
Definition: Mapper.h:1409
karto::Object
Definition: Karto.h:590
karto::Mapper::m_pMinimumDistancePenalty
Parameter< kt_double > * m_pMinimumDistancePenalty
Definition: Mapper.h:2125
karto::Graph::AddVertex
void AddVertex(const Name &rName, Vertex< T > *pVertex)
Definition: Mapper.h:474
karto::ScanSolver::ScanSolver
ScanSolver()
Definition: Mapper.h:835
karto::Mapper::m_Initialized
kt_bool m_Initialized
Definition: Mapper.h:1933
karto::EdgeLabel
Definition: Mapper.h:86
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::ScanManager::AddRunningScan
void AddRunningScan(LocalizedRangeScan *pScan)
Definition: Mapper.h:1371
karto::GridStates_Occupied
@ GridStates_Occupied
Definition: Karto.h:4205
karto::ScanManager::GetScans
LocalizedRangeScanVector & GetScans()
Definition: Mapper.h:1353
karto::Graph::Clear
void Clear()
Definition: Mapper.h:491
karto::CorrelationGrid
Definition: Mapper.h:899
karto::MapperSensorManager::SetLastScan
void SetLastScan(LocalizedRangeScan *pScan)
Definition: Mapper.h:1489
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
kt_int8u
uint8_t kt_int8u
Definition: Types.h:46
karto::Edge::~Edge
virtual ~Edge()
Definition: Mapper.h:317
karto::Mapper::m_Listeners
std::vector< MapperListener * > m_Listeners
Definition: Mapper.h:1942
karto::CorrelationGrid::m_pKernel
kt_int8u * m_pKernel
Definition: Mapper.h:1115
karto::ScanSolver::Clear
virtual void Clear()
Definition: Mapper.h:889
karto::NearScanVisitor::Visit
virtual kt_bool Visit(Vertex< LocalizedRangeScan > *pVertex)
Definition: Mapper.h:628
karto::CorrelationGrid::m_SmearDeviation
kt_double m_SmearDeviation
Definition: Mapper.h:1109
karto::Edge::GetSource
Vertex< T > * GetSource() const
Definition: Mapper.h:334
karto::ScanManager::m_Scans
LocalizedRangeScanVector m_Scans
Definition: Mapper.h:1404
karto::Vertex::GetEdges
const std::vector< Edge< T > * > & GetEdges() const
Definition: Mapper.h:234
karto::ScanManager::m_RunningBufferMaximumSize
kt_int32u m_RunningBufferMaximumSize
Definition: Mapper.h:1408
karto::Graph::VertexMap
std::map< Name, std::vector< Vertex< T > * > > VertexMap
Definition: Mapper.h:450
karto::MapperSensorManager::GetScanManager
ScanManager * GetScanManager(LocalizedRangeScan *pScan)
Definition: Mapper.h:1557
karto::ScanSolver::AddNode
virtual void AddNode(Vertex< LocalizedRangeScan > *)
Definition: Mapper.h:861
karto::Rectangle2::GetY
T GetY() const
Definition: Karto.h:1810
karto::CorrelationGrid::GetHalfKernelSize
static kt_int32s GetHalfKernelSize(kt_double smearDeviation, kt_double resolution)
Definition: Mapper.h:1097
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::Pose2::GetHeading
kt_double GetHeading() const
Definition: Karto.h:2064
karto::ScanMatcher::ScanMatcher
ScanMatcher(Mapper *pMapper)
Definition: Mapper.h:1268
karto::Vertex::Vertex
Vertex(T *pObject)
Definition: Mapper.h:218
karto
Definition: Karto.h:73
karto::Mapper::m_pCorrelationSearchSpaceDimension
Parameter< kt_double > * m_pCorrelationSearchSpaceDimension
Definition: Mapper.h:2070
karto::NearScanVisitor::m_CenterPose
Pose2 m_CenterPose
Definition: Mapper.h:639
karto::SensorData::GetSensorName
const Name & GetSensorName() const
Definition: Karto.h:4911
karto::Graph
Definition: Mapper.h:396
karto::LinkInfo::GetPoseDifference
const Pose2 & GetPoseDifference()
Definition: Mapper.h:177


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