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 <vector>
23 #include <queue>
24 
25 #include <open_karto/Karto.h>
26 
27 namespace karto
28 {
30  // Listener classes
31 
36  {
37  public:
41  virtual void Info(const std::string& /*rInfo*/) {};
42  };
43 
48  {
49  public:
53  virtual void Debug(const std::string& /*rInfo*/) {};
54  };
55 
60  {
61  public:
65  virtual void LoopClosureCheck(const std::string& /*rInfo*/) {};
66 
70  virtual void BeginLoopClosure(const std::string& /*rInfo*/) {};
71 
75  virtual void EndLoopClosure(const std::string& /*rInfo*/) {};
76  }; // MapperListener
77 
81 
85  class EdgeLabel
86  {
87  public:
92  {
93  }
94 
98  virtual ~EdgeLabel()
99  {
100  }
101  }; // EdgeLabel
102 
106 
107  // A LinkInfo object contains the requisite information for the "spring"
108  // that links two scans together--the pose difference and the uncertainty
109  // (represented by a covariance matrix).
110  class LinkInfo : public EdgeLabel
111  {
112  public:
119  LinkInfo(const Pose2& rPose1, const Pose2& rPose2, const Matrix3& rCovariance)
120  {
121  Update(rPose1, rPose2, rCovariance);
122  }
123 
127  virtual ~LinkInfo()
128  {
129  }
130 
131  public:
138  void Update(const Pose2& rPose1, const Pose2& rPose2, const Matrix3& rCovariance)
139  {
140  m_Pose1 = rPose1;
141  m_Pose2 = rPose2;
142 
143  // transform second pose into the coordinate system of the first pose
144  Transform transform(rPose1, Pose2());
145  m_PoseDifference = transform.TransformPose(rPose2);
146 
147  // transform covariance into reference of first pose
148  Matrix3 rotationMatrix;
149  rotationMatrix.FromAxisAngle(0, 0, 1, -rPose1.GetHeading());
150 
151  m_Covariance = rotationMatrix * rCovariance * rotationMatrix.Transpose();
152  }
153 
158  inline const Pose2& GetPose1()
159  {
160  return m_Pose1;
161  }
162 
167  inline const Pose2& GetPose2()
168  {
169  return m_Pose2;
170  }
171 
176  inline const Pose2& GetPoseDifference()
177  {
178  return m_PoseDifference;
179  }
180 
185  inline const Matrix3& GetCovariance()
186  {
187  return m_Covariance;
188  }
189 
190  private:
195  }; // LinkInfo
196 
200 
201  template<typename T>
202  class Edge;
203 
207  template<typename T>
208  class Vertex
209  {
210  friend class Edge<T>;
211 
212  public:
217  Vertex(T* pObject)
218  : m_pObject(pObject)
219  {
220  }
221 
225  virtual ~Vertex()
226  {
227  }
228 
233  inline const std::vector<Edge<T>*>& GetEdges() const
234  {
235  return m_Edges;
236  }
237 
242  inline T* GetObject() const
243  {
244  return m_pObject;
245  }
246 
251  std::vector<Vertex<T>*> GetAdjacentVertices() const
252  {
253  std::vector<Vertex<T>*> vertices;
254 
255  const_forEach(typename std::vector<Edge<T>*>, &m_Edges)
256  {
257  Edge<T>* pEdge = *iter;
258 
259  // check both source and target because we have a undirected graph
260  if (pEdge->GetSource() != this)
261  {
262  vertices.push_back(pEdge->GetSource());
263  }
264 
265  if (pEdge->GetTarget() != this)
266  {
267  vertices.push_back(pEdge->GetTarget());
268  }
269  }
270 
271  return vertices;
272  }
273 
274  private:
279  inline void AddEdge(Edge<T>* pEdge)
280  {
281  m_Edges.push_back(pEdge);
282  }
283 
285  std::vector<Edge<T>*> m_Edges;
286  }; // Vertex<T>
287 
291 
295  template<typename T>
296  class Edge
297  {
298  public:
304  Edge(Vertex<T>* pSource, Vertex<T>* pTarget)
305  : m_pSource(pSource)
306  , m_pTarget(pTarget)
307  , m_pLabel(NULL)
308  {
309  m_pSource->AddEdge(this);
310  m_pTarget->AddEdge(this);
311  }
312 
316  virtual ~Edge()
317  {
318  m_pSource = NULL;
319  m_pTarget = NULL;
320 
321  if (m_pLabel != NULL)
322  {
323  delete m_pLabel;
324  m_pLabel = NULL;
325  }
326  }
327 
328  public:
333  inline Vertex<T>* GetSource() const
334  {
335  return m_pSource;
336  }
337 
342  inline Vertex<T>* GetTarget() const
343  {
344  return m_pTarget;
345  }
346 
351  inline EdgeLabel* GetLabel()
352  {
353  return m_pLabel;
354  }
355 
360  inline void SetLabel(EdgeLabel* pLabel)
361  {
362  m_pLabel = pLabel;
363  }
364 
365  private:
369  }; // class Edge<T>
370 
374 
378  template<typename T>
379  class Visitor
380  {
381  public:
387  virtual kt_bool Visit(Vertex<T>* pVertex) = 0;
388  }; // Visitor<T>
389 
393 
394  template<typename T>
395  class Graph;
396 
400  template<typename T>
402  {
403  public:
409  : m_pGraph(pGraph)
410  {
411  }
412 
416  virtual ~GraphTraversal()
417  {
418  }
419 
420  public:
426  virtual std::vector<T*> Traverse(Vertex<T>* pStartVertex, Visitor<T>* pVisitor) = 0;
427 
428  protected:
433  }; // GraphTraversal<T>
434 
438 
442  template<typename T>
443  class Graph
444  {
445  public:
449  typedef std::map<Name, std::vector<Vertex<T>*> > VertexMap;
450 
451  public:
456  {
457  }
458 
462  virtual ~Graph()
463  {
464  Clear();
465  }
466 
467  public:
473  inline void AddVertex(const Name& rName, Vertex<T>* pVertex)
474  {
475  m_Vertices[rName].push_back(pVertex);
476  }
477 
482  inline void AddEdge(Edge<T>* pEdge)
483  {
484  m_Edges.push_back(pEdge);
485  }
486 
490  void Clear()
491  {
492  forEachAs(typename VertexMap, &m_Vertices, indexIter)
493  {
494  // delete each vertex
495  forEach(typename std::vector<Vertex<T>*>, &(indexIter->second))
496  {
497  delete *iter;
498  }
499  }
500  m_Vertices.clear();
501 
502  const_forEach(typename std::vector<Edge<T>*>, &m_Edges)
503  {
504  delete *iter;
505  }
506  m_Edges.clear();
507  }
508 
513  inline const std::vector<Edge<T>*>& GetEdges() const
514  {
515  return m_Edges;
516  }
517 
522  inline const VertexMap& GetVertices() const
523  {
524  return m_Vertices;
525  }
526 
527  protected:
531  VertexMap m_Vertices;
532 
536  std::vector<Edge<T>*> m_Edges;
537  }; // Graph<T>
538 
542 
543  template<typename T>
545  {
546  public:
551  : GraphTraversal<T>(pGraph)
552  {
553  }
554 
559  {
560  }
561 
562  public:
569  virtual std::vector<T*> Traverse(Vertex<T>* pStartVertex, Visitor<T>* pVisitor)
570  {
571  std::queue<Vertex<T>*> toVisit;
572  std::set<Vertex<T>*> seenVertices;
573  std::vector<Vertex<T>*> validVertices;
574 
575  toVisit.push(pStartVertex);
576  seenVertices.insert(pStartVertex);
577 
578  do
579  {
580  Vertex<T>* pNext = toVisit.front();
581  toVisit.pop();
582 
583  if (pVisitor->Visit(pNext))
584  {
585  // vertex is valid, explore neighbors
586  validVertices.push_back(pNext);
587 
588  std::vector<Vertex<T>*> adjacentVertices = pNext->GetAdjacentVertices();
589  forEach(typename std::vector<Vertex<T>*>, &adjacentVertices)
590  {
591  Vertex<T>* pAdjacent = *iter;
592 
593  // adjacent vertex has not yet been seen, add to queue for processing
594  if (seenVertices.find(pAdjacent) == seenVertices.end())
595  {
596  toVisit.push(pAdjacent);
597  seenVertices.insert(pAdjacent);
598  }
599  }
600  }
601  } while (toVisit.empty() == false);
602 
603  std::vector<T*> objects;
604  forEach(typename std::vector<Vertex<T>*>, &validVertices)
605  {
606  objects.push_back((*iter)->GetObject());
607  }
608 
609  return objects;
610  }
611  }; // class BreadthFirstTraversal
612 
616 
617  class NearScanVisitor : public Visitor<LocalizedRangeScan>
618  {
619  public:
620  NearScanVisitor(LocalizedRangeScan* pScan, kt_double maxDistance, kt_bool useScanBarycenter)
621  : m_MaxDistanceSquared(math::Square(maxDistance))
622  , m_UseScanBarycenter(useScanBarycenter)
623  {
624  m_CenterPose = pScan->GetReferencePose(m_UseScanBarycenter);
625  }
626 
628  {
629  LocalizedRangeScan* pScan = pVertex->GetObject();
630 
631  Pose2 pose = pScan->GetReferencePose(m_UseScanBarycenter);
632 
633  kt_double squaredDistance = pose.GetPosition().SquaredDistance(m_CenterPose.GetPosition());
634  return (squaredDistance <= m_MaxDistanceSquared - KT_TOLERANCE);
635  }
636 
637  protected:
641  }; // NearScanVisitor
642 
646 
647  class Mapper;
648  class ScanMatcher;
649 
653  class KARTO_EXPORT MapperGraph : public Graph<LocalizedRangeScan>
654  {
655  public:
661  MapperGraph(Mapper* pMapper, kt_double rangeThreshold);
662 
666  virtual ~MapperGraph();
667 
668  public:
673  void AddVertex(LocalizedRangeScan* pScan);
674 
683  Edge<LocalizedRangeScan>* AddEdge(LocalizedRangeScan* pSourceScan,
684  LocalizedRangeScan* pTargetScan,
685  kt_bool& rIsNewEdge);
686 
692  void AddEdges(LocalizedRangeScan* pScan, const Matrix3& rCovariance);
693 
699  kt_bool TryCloseLoop(LocalizedRangeScan* pScan, const Name& rSensorName);
700 
706  LocalizedRangeScanVector FindNearLinkedScans(LocalizedRangeScan* pScan, kt_double maxDistance);
707 
713  {
714  return m_pLoopScanMatcher;
715  }
716 
717  private:
724  {
725  return m_Vertices[pScan->GetSensorName()][pScan->GetStateId()];
726  }
727 
733  LocalizedRangeScan* GetClosestScanToPose(const LocalizedRangeScanVector& rScans, const Pose2& rPose) const;
734 
742  void LinkScans(LocalizedRangeScan* pFromScan,
743  LocalizedRangeScan* pToScan,
744  const Pose2& rMean,
745  const Matrix3& rCovariance);
746 
753  void LinkNearChains(LocalizedRangeScan* pScan, Pose2Vector& rMeans, std::vector<Matrix3>& rCovariances);
754 
762  void LinkChainToScan(const LocalizedRangeScanVector& rChain,
763  LocalizedRangeScan* pScan,
764  const Pose2& rMean,
765  const Matrix3& rCovariance);
766 
772  std::vector<LocalizedRangeScanVector> FindNearChains(LocalizedRangeScan* pScan);
773 
780  Pose2 ComputeWeightedMean(const Pose2Vector& rMeans, const std::vector<Matrix3>& rCovariances) const;
781 
790  LocalizedRangeScanVector FindPossibleLoopClosure(LocalizedRangeScan* pScan,
791  const Name& rSensorName,
792  kt_int32u& rStartNum);
793 
797  void CorrectPoses();
798 
799  private:
804 
809 
814  }; // MapperGraph
815 
819 
824  {
825  public:
829  typedef std::vector<std::pair<kt_int32s, Pose2> > IdPoseVector;
830 
835  {
836  }
837 
841  virtual ~ScanSolver()
842  {
843  }
844 
845  public:
849  virtual void Compute() = 0;
850 
855  virtual const IdPoseVector& GetCorrections() const = 0;
856 
860  virtual void AddNode(Vertex<LocalizedRangeScan>* /*pVertex*/)
861  {
862  }
863 
867  virtual void RemoveNode(kt_int32s /*id*/)
868  {
869  }
870 
874  virtual void AddConstraint(Edge<LocalizedRangeScan>* /*pEdge*/)
875  {
876  }
877 
881  virtual void RemoveConstraint(kt_int32s /*sourceId*/, kt_int32s /*targetId*/)
882  {
883  }
884 
888  virtual void Clear() {};
889  }; // ScanSolver
890 
894 
898  class CorrelationGrid : public Grid<kt_int8u>
899  {
900  public:
905  {
906  delete [] m_pKernel;
907  }
908 
909  public:
919  kt_int32s height,
920  kt_double resolution,
921  kt_double smearDeviation)
922  {
923  assert(resolution != 0.0);
924 
925  // +1 in case of roundoff
926  kt_int32u borderSize = GetHalfKernelSize(smearDeviation, resolution) + 1;
927 
928  CorrelationGrid* pGrid = new CorrelationGrid(width, height, borderSize, resolution, smearDeviation);
929 
930  return pGrid;
931  }
932 
939  virtual kt_int32s GridIndex(const Vector2<kt_int32s>& rGrid, kt_bool boundaryCheck = true) const
940  {
941  kt_int32s x = rGrid.GetX() + m_Roi.GetX();
942  kt_int32s y = rGrid.GetY() + m_Roi.GetY();
943 
944  return Grid<kt_int8u>::GridIndex(Vector2<kt_int32s>(x, y), boundaryCheck);
945  }
946 
951  inline const Rectangle2<kt_int32s>& GetROI() const
952  {
953  return m_Roi;
954  }
955 
960  inline void SetROI(const Rectangle2<kt_int32s>& roi)
961  {
962  m_Roi = roi;
963  }
964 
969  inline void SmearPoint(const Vector2<kt_int32s>& rGridPoint)
970  {
971  assert(m_pKernel != NULL);
972 
973  int gridIndex = GridIndex(rGridPoint);
974  if (GetDataPointer()[gridIndex] != GridStates_Occupied)
975  {
976  return;
977  }
978 
979  kt_int32s halfKernel = m_KernelSize / 2;
980 
981  // apply kernel
982  for (kt_int32s j = -halfKernel; j <= halfKernel; j++)
983  {
984  kt_int8u* pGridAdr = GetDataPointer(Vector2<kt_int32s>(rGridPoint.GetX(), rGridPoint.GetY() + j));
985 
986  kt_int32s kernelConstant = (halfKernel) + m_KernelSize * (j + halfKernel);
987 
988  // if a point is on the edge of the grid, there is no problem
989  // with running over the edge of allowable memory, because
990  // the grid has margins to compensate for the kernel size
991  for (kt_int32s i = -halfKernel; i <= halfKernel; i++)
992  {
993  kt_int32s kernelArrayIndex = i + kernelConstant;
994 
995  kt_int8u kernelValue = m_pKernel[kernelArrayIndex];
996  if (kernelValue > pGridAdr[i])
997  {
998  // kernel value is greater, so set it to kernel value
999  pGridAdr[i] = kernelValue;
1000  }
1001  }
1002  }
1003  }
1004 
1005  protected:
1014  CorrelationGrid(kt_int32u width, kt_int32u height, kt_int32u borderSize,
1015  kt_double resolution, kt_double smearDeviation)
1016  : Grid<kt_int8u>(width + borderSize * 2, height + borderSize * 2)
1017  , m_SmearDeviation(smearDeviation)
1018  , m_pKernel(NULL)
1019  {
1020  GetCoordinateConverter()->SetScale(1.0 / resolution);
1021 
1022  // setup region of interest
1023  m_Roi = Rectangle2<kt_int32s>(borderSize, borderSize, width, height);
1024 
1025  // calculate kernel
1026  CalculateKernel();
1027  }
1028 
1032  virtual void CalculateKernel()
1033  {
1034  kt_double resolution = GetResolution();
1035 
1036  assert(resolution != 0.0);
1037  assert(m_SmearDeviation != 0.0);
1038 
1039  // min and max distance deviation for smearing;
1040  // will smear for two standard deviations, so deviation must be at least 1/2 of the resolution
1041  const kt_double MIN_SMEAR_DISTANCE_DEVIATION = 0.5 * resolution;
1042  const kt_double MAX_SMEAR_DISTANCE_DEVIATION = 10 * resolution;
1043 
1044  // check if given value too small or too big
1045  if (!math::InRange(m_SmearDeviation, MIN_SMEAR_DISTANCE_DEVIATION, MAX_SMEAR_DISTANCE_DEVIATION))
1046  {
1047  std::stringstream error;
1048  error << "Mapper Error: Smear deviation too small: Must be between "
1049  << MIN_SMEAR_DISTANCE_DEVIATION
1050  << " and "
1051  << MAX_SMEAR_DISTANCE_DEVIATION;
1052  throw std::runtime_error(error.str());
1053  }
1054 
1055  // NOTE: Currently assumes a two-dimensional kernel
1056 
1057  // +1 for center
1058  m_KernelSize = 2 * GetHalfKernelSize(m_SmearDeviation, resolution) + 1;
1059 
1060  // allocate kernel
1061  m_pKernel = new kt_int8u[m_KernelSize * m_KernelSize];
1062  if (m_pKernel == NULL)
1063  {
1064  throw std::runtime_error("Unable to allocate memory for kernel!");
1065  }
1066 
1067  // calculate kernel
1068  kt_int32s halfKernel = m_KernelSize / 2;
1069  for (kt_int32s i = -halfKernel; i <= halfKernel; i++)
1070  {
1071  for (kt_int32s j = -halfKernel; j <= halfKernel; j++)
1072  {
1073 #ifdef WIN32
1074  kt_double distanceFromMean = _hypot(i * resolution, j * resolution);
1075 #else
1076  kt_double distanceFromMean = hypot(i * resolution, j * resolution);
1077 #endif
1078  kt_double z = exp(-0.5 * pow(distanceFromMean / m_SmearDeviation, 2));
1079 
1080  kt_int32u kernelValue = static_cast<kt_int32u>(math::Round(z * GridStates_Occupied));
1081  assert(math::IsUpTo(kernelValue, static_cast<kt_int32u>(255)));
1082 
1083  int kernelArrayIndex = (i + halfKernel) + m_KernelSize * (j + halfKernel);
1084  m_pKernel[kernelArrayIndex] = static_cast<kt_int8u>(kernelValue);
1085  }
1086  }
1087  }
1088 
1096  static kt_int32s GetHalfKernelSize(kt_double smearDeviation, kt_double resolution)
1097  {
1098  assert(resolution != 0.0);
1099 
1100  return static_cast<kt_int32s>(math::Round(2.0 * smearDeviation / resolution));
1101  }
1102 
1103  private:
1109 
1110  // Size of one side of the kernel
1112 
1113  // Cached kernel for smearing
1115 
1116  // region of interest
1118  }; // CorrelationGrid
1119 
1123 
1128  {
1129  public:
1133  virtual ~ScanMatcher();
1134 
1135  public:
1139  static ScanMatcher* Create(Mapper* pMapper,
1140  kt_double searchSize,
1141  kt_double resolution,
1142  kt_double smearDeviation,
1143  kt_double rangeThreshold);
1144 
1155  kt_double MatchScan(LocalizedRangeScan* pScan,
1156  const LocalizedRangeScanVector& rBaseScans,
1157  Pose2& rMean, Matrix3& rCovariance,
1158  kt_bool doPenalize = true,
1159  kt_bool doRefineMatch = true);
1160 
1177  kt_double CorrelateScan(LocalizedRangeScan* pScan,
1178  const Pose2& rSearchCenter,
1179  const Vector2<kt_double>& rSearchSpaceOffset,
1180  const Vector2<kt_double>& rSearchSpaceResolution,
1181  kt_double searchAngleOffset,
1182  kt_double searchAngleResolution,
1183  kt_bool doPenalize,
1184  Pose2& rMean,
1185  Matrix3& rCovariance,
1186  kt_bool doingFineMatch);
1187 
1198  void ComputePositionalCovariance(const Pose2& rBestPose,
1199  kt_double bestResponse,
1200  const Pose2& rSearchCenter,
1201  const Vector2<kt_double>& rSearchSpaceOffset,
1202  const Vector2<kt_double>& rSearchSpaceResolution,
1203  kt_double searchAngleResolution,
1204  Matrix3& rCovariance);
1205 
1215  void ComputeAngularCovariance(const Pose2& rBestPose,
1216  kt_double bestResponse,
1217  const Pose2& rSearchCenter,
1218  kt_double searchAngleOffset,
1219  kt_double searchAngleResolution,
1220  Matrix3& rCovariance);
1221 
1227  {
1228  return m_pCorrelationGrid;
1229  }
1230 
1231  private:
1237  void AddScans(const LocalizedRangeScanVector& rScans, Vector2<kt_double> viewPoint);
1238 
1245  void AddScan(LocalizedRangeScan* pScan, const Vector2<kt_double>& rViewPoint, kt_bool doSmear = true);
1246 
1253  PointVectorDouble FindValidPoints(LocalizedRangeScan* pScan, const Vector2<kt_double>& rViewPoint) const;
1254 
1261  kt_double GetResponse(kt_int32u angleIndex, kt_int32s gridPositionIndex) const;
1262 
1263  protected:
1268  : m_pMapper(pMapper)
1269  , m_pCorrelationGrid(NULL)
1270  , m_pSearchSpaceProbs(NULL)
1271  , m_pGridLookup(NULL)
1272  {
1273  }
1274 
1275  private:
1277 
1280 
1282  }; // ScanMatcher
1283 
1287 
1292  {
1293  public:
1297  ScanManager(kt_int32u runningBufferMaximumSize, kt_double runningBufferMaximumDistance)
1298  : m_pLastScan(NULL)
1299  , m_RunningBufferMaximumSize(runningBufferMaximumSize)
1300  , m_RunningBufferMaximumDistance(runningBufferMaximumDistance)
1301  {
1302  }
1303 
1307  virtual ~ScanManager()
1308  {
1309  Clear();
1310  }
1311 
1312  public:
1317  inline void AddScan(LocalizedRangeScan* pScan, kt_int32s uniqueId)
1318  {
1319  // assign state id to scan
1320  pScan->SetStateId(static_cast<kt_int32u>(m_Scans.size()));
1321 
1322  // assign unique id to scan
1323  pScan->SetUniqueId(uniqueId);
1324 
1325  // add it to scan buffer
1326  m_Scans.push_back(pScan);
1327  }
1328 
1335  {
1336  return m_pLastScan;
1337  }
1338 
1343  inline void SetLastScan(LocalizedRangeScan* pScan)
1344  {
1345  m_pLastScan = pScan;
1346  }
1347 
1353  {
1354  return m_Scans;
1355  }
1356 
1362  {
1363  return m_RunningScans;
1364  }
1365 
1371  {
1372  m_RunningScans.push_back(pScan);
1373 
1374  // vector has at least one element (first line of this function), so this is valid
1375  Pose2 frontScanPose = m_RunningScans.front()->GetSensorPose();
1376  Pose2 backScanPose = m_RunningScans.back()->GetSensorPose();
1377 
1378  // cap vector size and remove all scans from front of vector that are too far from end of vector
1379  kt_double squaredDistance = frontScanPose.GetPosition().SquaredDistance(backScanPose.GetPosition());
1380  while (m_RunningScans.size() > m_RunningBufferMaximumSize ||
1381  squaredDistance > math::Square(m_RunningBufferMaximumDistance) - KT_TOLERANCE)
1382  {
1383  // remove front of running scans
1384  m_RunningScans.erase(m_RunningScans.begin());
1385 
1386  // recompute stats of running scans
1387  frontScanPose = m_RunningScans.front()->GetSensorPose();
1388  backScanPose = m_RunningScans.back()->GetSensorPose();
1389  squaredDistance = frontScanPose.GetPosition().SquaredDistance(backScanPose.GetPosition());
1390  }
1391  }
1392 
1396  void Clear()
1397  {
1398  m_Scans.clear();
1399  m_RunningScans.clear();
1400  }
1401 
1402  private:
1406 
1409  }; // ScanManager
1410 
1414 
1418  class KARTO_EXPORT MapperSensorManager // : public SensorManager
1419  {
1420  typedef std::map<Name, ScanManager*> ScanManagerMap;
1421 
1422  public:
1426  MapperSensorManager(kt_int32u runningBufferMaximumSize, kt_double runningBufferMaximumDistance)
1427  : m_RunningBufferMaximumSize(runningBufferMaximumSize)
1428  , m_RunningBufferMaximumDistance(runningBufferMaximumDistance)
1429  , m_NextScanId(0)
1430  {
1431  }
1432 
1437  {
1438  Clear();
1439  }
1440 
1441  public:
1447  void RegisterSensor(const Name& rSensorName);
1448 
1455  LocalizedRangeScan* GetScan(const Name& rSensorName, kt_int32s scanIndex);
1456 
1461  inline std::vector<Name> GetSensorNames()
1462  {
1463  std::vector<Name> deviceNames;
1464  const_forEach(ScanManagerMap, &m_ScanManagers)
1465  {
1466  deviceNames.push_back(iter->first);
1467  }
1468 
1469  return deviceNames;
1470  }
1471 
1477  inline LocalizedRangeScan* GetLastScan(const Name& rSensorName)
1478  {
1479  RegisterSensor(rSensorName);
1480 
1481  return GetScanManager(rSensorName)->GetLastScan();
1482  }
1483 
1488  inline void SetLastScan(LocalizedRangeScan* pScan)
1489  {
1490  GetScanManager(pScan)->SetLastScan(pScan);
1491  }
1492 
1499  {
1500  assert(math::IsUpTo(id, (kt_int32s)m_Scans.size()));
1501 
1502  return m_Scans[id];
1503  }
1504 
1509  void AddScan(LocalizedRangeScan* pScan);
1510 
1516  {
1517  GetScanManager(pScan)->AddRunningScan(pScan);
1518  }
1519 
1525  inline LocalizedRangeScanVector& GetScans(const Name& rSensorName)
1526  {
1527  return GetScanManager(rSensorName)->GetScans();
1528  }
1529 
1535  inline LocalizedRangeScanVector& GetRunningScans(const Name& rSensorName)
1536  {
1537  return GetScanManager(rSensorName)->GetRunningScans();
1538  }
1539 
1544  LocalizedRangeScanVector GetAllScans();
1545 
1549  void Clear();
1550 
1551  private:
1557  {
1558  return GetScanManager(pScan->GetSensorName());
1559  }
1560 
1566  inline ScanManager* GetScanManager(const Name& rSensorName)
1567  {
1568  if (m_ScanManagers.find(rSensorName) != m_ScanManagers.end())
1569  {
1570  return m_ScanManagers[rSensorName];
1571  }
1572 
1573  return NULL;
1574  }
1575 
1576  private:
1577  // map from device ID to scan data
1578  ScanManagerMap m_ScanManagers;
1579 
1582 
1584 
1585  std::vector<LocalizedRangeScan*> m_Scans;
1586  }; // MapperSensorManager
1587 
1591 
1749  class KARTO_EXPORT Mapper : public Module
1750  {
1751  friend class MapperGraph;
1752  friend class ScanMatcher;
1753 
1754  public:
1758  Mapper();
1759 
1764  Mapper(const std::string& rName);
1765 
1769  virtual ~Mapper();
1770 
1771  public:
1776  void Initialize(kt_double rangeThreshold);
1777 
1782  void Reset();
1783 
1795  virtual kt_bool Process(LocalizedRangeScan* pScan);
1796 
1800  virtual kt_bool Process(Object* pObject);
1801 
1808  virtual const LocalizedRangeScanVector GetAllProcessedScans() const;
1809 
1814  void AddListener(MapperListener* pListener);
1815 
1820  void RemoveListener(MapperListener* pListener);
1821 
1826  void SetScanSolver(ScanSolver* pSolver);
1827 
1832  virtual MapperGraph* GetGraph() const;
1833 
1838  virtual ScanMatcher* GetSequentialScanMatcher() const;
1839 
1844  virtual ScanMatcher* GetLoopScanMatcher() const;
1845 
1851  {
1852  return m_pMapperSensorManager;
1853  }
1854 
1860  inline kt_bool TryCloseLoop(LocalizedRangeScan* pScan, const Name& rSensorName)
1861  {
1862  return m_pGraph->TryCloseLoop(pScan, rSensorName);
1863  }
1864 
1865  private:
1866  void InitializeParameters();
1867 
1875  kt_bool HasMovedEnough(LocalizedRangeScan* pScan, LocalizedRangeScan* pLastScan) const;
1876 
1877  public:
1879  // fire information for listeners!!
1880 
1885  void FireInfo(const std::string& rInfo) const;
1886 
1891  void FireDebug(const std::string& rInfo) const;
1892 
1897  void FireLoopClosureCheck(const std::string& rInfo) const;
1898 
1903  void FireBeginLoopClosure(const std::string& rInfo) const;
1904 
1909  void FireEndLoopClosure(const std::string& rInfo) const;
1910 
1911  // FireRunningScansUpdated
1912 
1913  // FireCovarianceCalculated
1914 
1915  // FireLoopClosureChain
1916 
1917  private:
1921  Mapper(const Mapper&);
1922 
1926  const Mapper& operator=(const Mapper&);
1927 
1928  public:
1929  void SetUseScanMatching(kt_bool val) { m_pUseScanMatching->SetValue(val); }
1930 
1931  private:
1933 
1935 
1937 
1940 
1941  std::vector<MapperListener*> m_Listeners;
1942 
1943 
1953 
1958 
1971 
1981 
1991 
2001 
2008 
2014 
2021 
2027 
2034 
2042 
2049 
2055 
2061 
2063  // CorrelationParameters correlationParameters;
2064 
2070 
2076 
2082 
2083 
2085  // CorrelationParameters loopCorrelationParameters;
2086 
2092 
2098 
2104 
2106  // ScanMatcherParameters;
2107 
2108  // Variance of penalty for deviating from odometry when scan-matching.
2109  // The penalty is a multiplier (less than 1.0) is a function of the
2110  // delta of the scan position being tested and the odometric pose
2113 
2114  // The range of angles to search during a coarse search and a finer search
2117 
2118  // Resolution of angles to search during a coarse search
2120 
2121  // Minimum value of the penalty multiplier so scores do not
2122  // become too small
2125 
2126  // whether to increase the search space if no good matches are initially found
2128 
2129  public:
2130  /* Abstract methods for parameter setters and getters */
2131 
2132  /* Getters */
2133  // General Parameters
2134  bool getParamUseScanMatching();
2135  bool getParamUseScanBarycenter();
2136  double getParamMinimumTimeInterval();
2137  double getParamMinimumTravelDistance();
2138  double getParamMinimumTravelHeading();
2139  int getParamScanBufferSize();
2140  double getParamScanBufferMaximumScanDistance();
2141  double getParamLinkMatchMinimumResponseFine();
2142  double getParamLinkScanMaximumDistance();
2143  double getParamLoopSearchMaximumDistance();
2144  bool getParamDoLoopClosing();
2145  int getParamLoopMatchMinimumChainSize();
2146  double getParamLoopMatchMaximumVarianceCoarse();
2147  double getParamLoopMatchMinimumResponseCoarse();
2148  double getParamLoopMatchMinimumResponseFine();
2149 
2150  // Correlation Parameters - Correlation Parameters
2151  double getParamCorrelationSearchSpaceDimension();
2152  double getParamCorrelationSearchSpaceResolution();
2153  double getParamCorrelationSearchSpaceSmearDeviation();
2154 
2155  // Correlation Parameters - Loop Closure Parameters
2156  double getParamLoopSearchSpaceDimension();
2157  double getParamLoopSearchSpaceResolution();
2158  double getParamLoopSearchSpaceSmearDeviation();
2159 
2160  // Scan Matcher Parameters
2161  double getParamDistanceVariancePenalty();
2162  double getParamAngleVariancePenalty();
2163  double getParamFineSearchAngleOffset();
2164  double getParamCoarseSearchAngleOffset();
2165  double getParamCoarseAngleResolution();
2166  double getParamMinimumAnglePenalty();
2167  double getParamMinimumDistancePenalty();
2168  bool getParamUseResponseExpansion();
2169 
2170  /* Setters */
2171  // General Parameters
2172  void setParamUseScanMatching(bool b);
2173  void setParamUseScanBarycenter(bool b);
2174  void setParamMinimumTimeInterval(double d);
2175  void setParamMinimumTravelDistance(double d);
2176  void setParamMinimumTravelHeading(double d);
2177  void setParamScanBufferSize(int i);
2178  void setParamScanBufferMaximumScanDistance(double d);
2179  void setParamLinkMatchMinimumResponseFine(double d);
2180  void setParamLinkScanMaximumDistance(double d);
2181  void setParamLoopSearchMaximumDistance(double d);
2182  void setParamDoLoopClosing(bool b);
2183  void setParamLoopMatchMinimumChainSize(int i);
2184  void setParamLoopMatchMaximumVarianceCoarse(double d);
2185  void setParamLoopMatchMinimumResponseCoarse(double d);
2186  void setParamLoopMatchMinimumResponseFine(double d);
2187 
2188  // Correlation Parameters - Correlation Parameters
2189  void setParamCorrelationSearchSpaceDimension(double d);
2190  void setParamCorrelationSearchSpaceResolution(double d);
2191  void setParamCorrelationSearchSpaceSmearDeviation(double d);
2192 
2193  // Correlation Parameters - Loop Closure Parameters
2194  void setParamLoopSearchSpaceDimension(double d);
2195  void setParamLoopSearchSpaceResolution(double d);
2196  void setParamLoopSearchSpaceSmearDeviation(double d);
2197 
2198  // Scan Matcher Parameters
2199  void setParamDistanceVariancePenalty(double d);
2200  void setParamAngleVariancePenalty(double d);
2201  void setParamFineSearchAngleOffset(double d);
2202  void setParamCoarseSearchAngleOffset(double d);
2203  void setParamCoarseAngleResolution(double d);
2204  void setParamMinimumAnglePenalty(double d);
2205  void setParamMinimumDistancePenalty(double d);
2206  void setParamUseResponseExpansion(bool b);
2207  };
2208 } // namespace karto
2209 
2210 #endif // OPEN_KARTO_MAPPER_H
CorrelationGrid(kt_int32u width, kt_int32u height, kt_int32u borderSize, kt_double resolution, kt_double smearDeviation)
Definition: Mapper.h:1014
std::map< Name, ScanManager * > ScanManagerMap
Definition: Mapper.h:1420
virtual ~ScanSolver()
Definition: Mapper.h:841
EdgeLabel * m_pLabel
Definition: Mapper.h:368
ScanMatcher * m_pSequentialScanMatcher
Definition: Mapper.h:1934
T * m_pObject
Definition: Mapper.h:284
int32_t kt_int32s
Definition: Types.h:51
GraphTraversal(Graph< T > *pGraph)
Definition: Mapper.h:408
Matrix3 m_Covariance
Definition: Mapper.h:194
virtual ~CorrelationGrid()
Definition: Mapper.h:904
Vertex< T > * m_pTarget
Definition: Mapper.h:367
EdgeLabel * GetLabel()
Definition: Mapper.h:351
Parameter< kt_double > * m_pLinkScanMaximumDistance
Definition: Mapper.h:2020
virtual void Info(const std::string &)
Definition: Mapper.h:41
kt_double Round(kt_double value)
Definition: Math.h:87
kt_bool TryCloseLoop(LocalizedRangeScan *pScan, const Name &rSensorName)
Definition: Mapper.h:1860
Mapper * m_pMapper
Definition: Mapper.h:1276
virtual void AddNode(Vertex< LocalizedRangeScan > *)
Definition: Mapper.h:860
void SetUniqueId(kt_int32u uniqueId)
Definition: Karto.h:4884
Parameter< kt_double > * m_pCoarseAngleResolution
Definition: Mapper.h:2119
kt_int32s GetStateId() const
Definition: Karto.h:4857
NearScanVisitor(LocalizedRangeScan *pScan, kt_double maxDistance, kt_bool useScanBarycenter)
Definition: Mapper.h:620
Parameter< kt_double > * m_pLoopMatchMaximumVarianceCoarse
Definition: Mapper.h:2048
std::vector< Vector2< kt_double > > PointVectorDouble
Definition: Karto.h:1204
Parameter< kt_double > * m_pMinimumTravelHeading
Definition: Mapper.h:1990
virtual void EndLoopClosure(const std::string &)
Definition: Mapper.h:75
#define forEachAs(listtype, list, iter)
Definition: Macros.h:69
void AddEdge(Edge< T > *pEdge)
Definition: Mapper.h:482
Parameter< kt_double > * m_pMinimumAnglePenalty
Definition: Mapper.h:2123
Matrix3 Transpose() const
Definition: Karto.h:2430
std::vector< MapperListener * > m_Listeners
Definition: Mapper.h:1941
LocalizedRangeScanVector & GetScans()
Definition: Mapper.h:1352
virtual void Clear()
Definition: Mapper.h:888
kt_bool m_UseScanBarycenter
Definition: Mapper.h:640
virtual void RemoveNode(kt_int32s)
Definition: Mapper.h:867
const Vector2< kt_double > & GetPosition() const
Definition: Karto.h:2046
Rectangle2< kt_int32s > m_Roi
Definition: Mapper.h:1117
uint8_t kt_int8u
Definition: Types.h:46
virtual void RemoveConstraint(kt_int32s, kt_int32s)
Definition: Mapper.h:881
virtual ~GraphTraversal()
Definition: Mapper.h:416
std::vector< Name > GetSensorNames()
Definition: Mapper.h:1461
virtual void LoopClosureCheck(const std::string &)
Definition: Mapper.h:65
Parameter< kt_double > * m_pLoopSearchSpaceSmearDeviation
Definition: Mapper.h:2103
void Update(const Pose2 &rPose1, const Pose2 &rPose2, const Matrix3 &rCovariance)
Definition: Mapper.h:138
const std::vector< Edge< T > * > & GetEdges() const
Definition: Mapper.h:513
virtual kt_bool Visit(Vertex< LocalizedRangeScan > *pVertex)
Definition: Mapper.h:627
const Matrix3 & GetCovariance()
Definition: Mapper.h:185
Parameter< kt_int32u > * m_pLoopMatchMinimumChainSize
Definition: Mapper.h:2041
Parameter< kt_double > * m_pCorrelationSearchSpaceResolution
Definition: Mapper.h:2075
void Clear()
Definition: Mapper.h:490
virtual kt_int32s GridIndex(const Vector2< kt_int32s > &rGrid, kt_bool boundaryCheck=true) const
Definition: Mapper.h:939
Parameter< kt_double > * m_pMinimumDistancePenalty
Definition: Mapper.h:2124
void AddVertex(const Name &rName, Vertex< T > *pVertex)
Definition: Mapper.h:473
virtual void AddConstraint(Edge< LocalizedRangeScan > *)
Definition: Mapper.h:874
virtual ~Edge()
Definition: Mapper.h:316
Parameter< kt_double > * m_pDistanceVariancePenalty
Definition: Mapper.h:2111
void SetStateId(kt_int32s stateId)
Definition: Karto.h:4866
MapperSensorManager * GetMapperSensorManager() const
Definition: Mapper.h:1850
Parameter< kt_bool > * m_pUseScanMatching
Definition: Mapper.h:1952
Vertex< T > * GetTarget() const
Definition: Mapper.h:342
#define forEach(listtype, list)
Definition: Macros.h:66
kt_double m_SmearDeviation
Definition: Mapper.h:1108
virtual ~BreadthFirstTraversal()
Definition: Mapper.h:558
LocalizedRangeScan * GetLastScan()
Definition: Mapper.h:1334
T * GetObject() const
Definition: Mapper.h:242
void SetLastScan(LocalizedRangeScan *pScan)
Definition: Mapper.h:1488
Graph< T > * m_pGraph
Definition: Mapper.h:432
void SetROI(const Rectangle2< kt_int32s > &roi)
Definition: Mapper.h:960
LocalizedRangeScanVector m_RunningScans
Definition: Mapper.h:1404
LocalizedRangeScanVector & GetScans(const Name &rSensorName)
Definition: Mapper.h:1525
MapperSensorManager * m_pMapperSensorManager
Definition: Mapper.h:1936
kt_int32u m_RunningBufferMaximumSize
Definition: Mapper.h:1580
GraphTraversal< LocalizedRangeScan > * m_pTraversal
Definition: Mapper.h:813
Parameter< kt_bool > * m_pDoLoopClosing
Definition: Mapper.h:2026
virtual kt_bool Visit(Vertex< T > *pVertex)=0
BreadthFirstTraversal(Graph< T > *pGraph)
Definition: Mapper.h:550
Parameter< kt_double > * m_pFineSearchAngleOffset
Definition: Mapper.h:2115
kt_int32u m_RunningBufferMaximumSize
Definition: Mapper.h:1407
Parameter< kt_double > * m_pScanBufferMaximumScanDistance
Definition: Mapper.h:2007
ScanSolver * m_pScanOptimizer
Definition: Mapper.h:1939
const Pose2 & GetPose2()
Definition: Mapper.h:167
virtual void Debug(const std::string &)
Definition: Mapper.h:53
Parameter< kt_double > * m_pLoopSearchSpaceDimension
Definition: Mapper.h:2091
kt_double SquaredDistance(const Vector2 &rOther) const
Definition: Karto.h:1031
void SetLastScan(LocalizedRangeScan *pScan)
Definition: Mapper.h:1343
virtual kt_int32s GridIndex(const Vector2< kt_int32s > &rGrid, kt_bool boundaryCheck=true) const
Definition: Karto.h:4497
const Name & GetSensorName() const
Definition: Karto.h:4911
void SmearPoint(const Vector2< kt_int32s > &rGridPoint)
Definition: Mapper.h:969
LocalizedRangeScan * GetLastScan(const Name &rSensorName)
Definition: Mapper.h:1477
CorrelationGrid * GetCorrelationGrid() const
Definition: Mapper.h:1226
Pose2 m_Pose2
Definition: Mapper.h:192
ScanManager(kt_int32u runningBufferMaximumSize, kt_double runningBufferMaximumDistance)
Definition: Mapper.h:1297
Parameter< kt_double > * m_pMinimumTravelDistance
Definition: Mapper.h:1980
std::vector< Edge< T > * > m_Edges
Definition: Mapper.h:536
void AddRunningScan(LocalizedRangeScan *pScan)
Definition: Mapper.h:1515
void AddRunningScan(LocalizedRangeScan *pScan)
Definition: Mapper.h:1370
Mapper * m_pMapper
Definition: Mapper.h:803
kt_int8u * m_pKernel
Definition: Mapper.h:1114
LocalizedRangeScanVector & GetRunningScans()
Definition: Mapper.h:1361
void AddEdge(Edge< T > *pEdge)
Definition: Mapper.h:279
void SetUseScanMatching(kt_bool val)
Definition: Mapper.h:1929
std::vector< Pose2 > Pose2Vector
Definition: Karto.h:2174
ScanMatcher * GetLoopScanMatcher() const
Definition: Mapper.h:712
virtual ~Vertex()
Definition: Mapper.h:225
virtual ~MapperSensorManager()
Definition: Mapper.h:1436
Vertex< T > * GetSource() const
Definition: Mapper.h:333
ScanMatcher(Mapper *pMapper)
Definition: Mapper.h:1267
kt_bool InRange(const T &value, const T &a, const T &b)
Definition: Math.h:172
void AddScan(LocalizedRangeScan *pScan, kt_int32s uniqueId)
Definition: Mapper.h:1317
kt_double m_RunningBufferMaximumDistance
Definition: Mapper.h:1581
Pose2 m_PoseDifference
Definition: Mapper.h:193
const kt_double KT_TOLERANCE
Definition: Math.h:41
const T & GetX() const
Definition: Karto.h:957
#define const_forEach(listtype, list)
Definition: Macros.h:72
VertexMap m_Vertices
Definition: Mapper.h:531
Vertex< T > * m_pSource
Definition: Mapper.h:366
virtual void BeginLoopClosure(const std::string &)
Definition: Mapper.h:70
Pose2 TransformPose(const Pose2 &rSourcePose)
Definition: Karto.h:2890
std::vector< Vertex< T > * > GetAdjacentVertices() const
Definition: Mapper.h:251
GridIndexLookup< kt_int8u > * m_pGridLookup
Definition: Mapper.h:1281
Pose2 GetReferencePose(kt_bool useBarycenter) const
Definition: Karto.h:5277
bool kt_bool
Definition: Types.h:64
virtual ~Graph()
Definition: Mapper.h:462
static CorrelationGrid * CreateGrid(kt_int32s width, kt_int32s height, kt_double resolution, kt_double smearDeviation)
Definition: Mapper.h:918
CorrelationGrid * m_pCorrelationGrid
Definition: Mapper.h:1278
Parameter< kt_double > * m_pLoopSearchSpaceResolution
Definition: Mapper.h:2097
kt_bool m_Initialized
Definition: Mapper.h:1932
Parameter< kt_double > * m_pCorrelationSearchSpaceDimension
Definition: Mapper.h:2069
MapperSensorManager(kt_int32u runningBufferMaximumSize, kt_double runningBufferMaximumDistance)
Definition: Mapper.h:1426
const std::vector< Edge< T > * > & GetEdges() const
Definition: Mapper.h:233
LocalizedRangeScan * GetScan(kt_int32s id)
Definition: Mapper.h:1498
kt_int32s m_KernelSize
Definition: Mapper.h:1111
std::vector< std::pair< kt_int32s, Pose2 > > IdPoseVector
Definition: Mapper.h:829
Parameter< kt_double > * m_pLinkMatchMinimumResponseFine
Definition: Mapper.h:2013
LocalizedRangeScanVector & GetRunningScans(const Name &rSensorName)
Definition: Mapper.h:1535
Vertex< LocalizedRangeScan > * GetVertex(LocalizedRangeScan *pScan)
Definition: Mapper.h:723
const Pose2 & GetPose1()
Definition: Mapper.h:158
virtual ~EdgeLabel()
Definition: Mapper.h:98
T Square(T value)
Definition: Math.h:77
Pose2 m_Pose1
Definition: Mapper.h:191
virtual ~ScanManager()
Definition: Mapper.h:1307
ScanMatcher * m_pLoopScanMatcher
Definition: Mapper.h:808
Vertex(T *pObject)
Definition: Mapper.h:217
void SetLabel(EdgeLabel *pLabel)
Definition: Mapper.h:360
ScanManagerMap m_ScanManagers
Definition: Mapper.h:1578
Grid< kt_double > * m_pSearchSpaceProbs
Definition: Mapper.h:1279
std::map< Name, std::vector< Vertex< T > * > > VertexMap
Definition: Mapper.h:449
static kt_int32s GetHalfKernelSize(kt_double smearDeviation, kt_double resolution)
Definition: Mapper.h:1096
Edge(Vertex< T > *pSource, Vertex< T > *pTarget)
Definition: Mapper.h:304
virtual ~LinkInfo()
Definition: Mapper.h:127
double kt_double
Definition: Types.h:67
Parameter< kt_double > * m_pCorrelationSearchSpaceSmearDeviation
Definition: Mapper.h:2081
virtual std::vector< T * > Traverse(Vertex< T > *pStartVertex, Visitor< T > *pVisitor)
Definition: Mapper.h:569
Definition: Karto.h:73
const T & GetY() const
Definition: Karto.h:975
MapperGraph * m_pGraph
Definition: Mapper.h:1938
Parameter< kt_double > * m_pLoopMatchMinimumResponseCoarse
Definition: Mapper.h:2054
LocalizedRangeScan * m_pLastScan
Definition: Mapper.h:1405
std::vector< LocalizedRangeScan * > m_Scans
Definition: Mapper.h:1585
const Rectangle2< kt_int32s > & GetROI() const
Definition: Mapper.h:951
kt_double m_RunningBufferMaximumDistance
Definition: Mapper.h:1408
LinkInfo(const Pose2 &rPose1, const Pose2 &rPose2, const Matrix3 &rCovariance)
Definition: Mapper.h:119
const VertexMap & GetVertices() const
Definition: Mapper.h:522
Parameter< kt_double > * m_pCoarseSearchAngleOffset
Definition: Mapper.h:2116
Parameter< kt_double > * m_pLoopSearchMaximumDistance
Definition: Mapper.h:2033
Parameter< kt_double > * m_pAngleVariancePenalty
Definition: Mapper.h:2112
uint32_t kt_int32u
Definition: Types.h:52
virtual void CalculateKernel()
Definition: Mapper.h:1032
Parameter< kt_double > * m_pMinimumTimeInterval
Definition: Mapper.h:1970
Parameter< kt_bool > * m_pUseResponseExpansion
Definition: Mapper.h:2127
Parameter< kt_int32u > * m_pScanBufferSize
Definition: Mapper.h:2000
#define KARTO_EXPORT
Definition: Macros.h:56
kt_bool IsUpTo(const T &value, const T &maximum)
Definition: Math.h:147
std::vector< Edge< T > * > m_Edges
Definition: Mapper.h:285
ScanManager * GetScanManager(LocalizedRangeScan *pScan)
Definition: Mapper.h:1556
std::vector< LocalizedRangeScan * > LocalizedRangeScanVector
Definition: Karto.h:5490
ScanManager * GetScanManager(const Name &rSensorName)
Definition: Mapper.h:1566
Parameter< kt_bool > * m_pUseScanBarycenter
Definition: Mapper.h:1957
LocalizedRangeScanVector m_Scans
Definition: Mapper.h:1403
const Pose2 & GetPoseDifference()
Definition: Mapper.h:176
Parameter< kt_double > * m_pLoopMatchMinimumResponseFine
Definition: Mapper.h:2060
kt_double GetHeading() const
Definition: Karto.h:2064
void FromAxisAngle(kt_double x, kt_double y, kt_double z, const kt_double radians)
Definition: Karto.h:2395
kt_double m_MaxDistanceSquared
Definition: Mapper.h:639


open_karto
Author(s):
autogenerated on Mon Feb 28 2022 23:00:17