00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #ifndef __KARTO_MAPPER__
00019 #define __KARTO_MAPPER__
00020
00021 #include <map>
00022 #include <vector>
00023
00024 #include "Karto.h"
00025
00026 namespace karto
00027 {
00029
00030
00031 class MapperListener
00032 {
00033 public:
00034 virtual void Info(const std::string& ) {};
00035 };
00036
00037 class MapperDebugListener
00038 {
00039 public:
00040 virtual void Debug(const std::string& ) {};
00041 };
00042
00043 class MapperLoopClosureListener : public MapperListener
00044 {
00045 public:
00046 virtual void LoopClosureCheck(const std::string& ) {};
00047 virtual void BeginLoopClosure(const std::string& ) {};
00048 virtual void EndLoopClosure(const std::string& ) {};
00049 };
00050
00054
00055 class EdgeLabel
00056 {
00057 public:
00061 EdgeLabel()
00062 {
00063 }
00064
00068 virtual ~EdgeLabel()
00069 {
00070 }
00071 };
00072
00076
00077
00078
00079
00080 class LinkInfo : public EdgeLabel
00081 {
00082 public:
00089 LinkInfo(const Pose2& rPose1, const Pose2& rPose2, const Matrix3& rCovariance)
00090 {
00091 Update(rPose1, rPose2, rCovariance);
00092 }
00093
00097 virtual ~LinkInfo()
00098 {
00099 }
00100
00101 public:
00108 void Update(const Pose2& rPose1, const Pose2& rPose2, const Matrix3& rCovariance)
00109 {
00110 m_Pose1 = rPose1;
00111 m_Pose2 = rPose2;
00112
00113
00114 Transform transform(rPose1, Pose2());
00115 m_PoseDifference = transform.TransformPose(rPose2);
00116
00117
00118 Matrix3 rotationMatrix;
00119 rotationMatrix.FromAxisAngle(0, 0, 1, -rPose1.GetHeading());
00120
00121 m_Covariance = rotationMatrix * rCovariance * rotationMatrix.Transpose();
00122 }
00123
00128 inline const Pose2& GetPose1()
00129 {
00130 return m_Pose1;
00131 }
00132
00137 inline const Pose2& GetPose2()
00138 {
00139 return m_Pose2;
00140 }
00141
00146 inline const Pose2& GetPoseDifference()
00147 {
00148 return m_PoseDifference;
00149 }
00150
00155 inline const Matrix3& GetCovariance()
00156 {
00157 return m_Covariance;
00158 }
00159
00160 private:
00161 Pose2 m_Pose1;
00162 Pose2 m_Pose2;
00163 Pose2 m_PoseDifference;
00164 Matrix3 m_Covariance;
00165 };
00166
00170
00171 template<typename T>
00172 class Edge;
00173
00177 template<typename T>
00178 class Vertex
00179 {
00180 friend class Edge<T>;
00181
00182 public:
00187 Vertex(T* pObject)
00188 : m_pObject(pObject)
00189 {
00190 }
00191
00195 virtual ~Vertex()
00196 {
00197 }
00198
00203 inline const std::vector<Edge<T>*>& GetEdges() const
00204 {
00205 return m_Edges;
00206 }
00207
00212 inline T* GetObject() const
00213 {
00214 return m_pObject;
00215 }
00216
00221 std::vector<Vertex<T>*> GetAdjacentVertices() const
00222 {
00223 std::vector<Vertex<T>*> vertices;
00224
00225 const_forEach(typename std::vector<Edge<T>*>, &m_Edges)
00226 {
00227 Edge<T>* pEdge = *iter;
00228
00229
00230 if (pEdge->GetSource() != this)
00231 {
00232 vertices.push_back(pEdge->GetSource());
00233 }
00234
00235 if (pEdge->GetTarget() != this)
00236 {
00237 vertices.push_back(pEdge->GetTarget());
00238 }
00239 }
00240
00241 return vertices;
00242 }
00243
00244 private:
00249 inline void AddEdge(Edge<T>* pEdge)
00250 {
00251 m_Edges.push_back(pEdge);
00252 }
00253
00254 T* m_pObject;
00255 std::vector<Edge<T>*> m_Edges;
00256 };
00257
00261
00262 template<typename T>
00263 class Edge
00264 {
00265 public:
00271 Edge(Vertex<T>* pSource, Vertex<T>* pTarget)
00272 : m_pSource(pSource)
00273 , m_pTarget(pTarget)
00274 , m_pLabel(NULL)
00275 {
00276 m_pSource->AddEdge(this);
00277 m_pTarget->AddEdge(this);
00278 }
00279
00283 virtual ~Edge()
00284 {
00285 m_pSource = NULL;
00286 m_pTarget = NULL;
00287
00288 if (m_pLabel != NULL)
00289 {
00290 delete m_pLabel;
00291 m_pLabel = NULL;
00292 }
00293 }
00294
00295 public:
00300 inline Vertex<T>* GetSource() const
00301 {
00302 return m_pSource;
00303 }
00304
00309 inline Vertex<T>* GetTarget() const
00310 {
00311 return m_pTarget;
00312 }
00313
00318 inline EdgeLabel* GetLabel()
00319 {
00320 return m_pLabel;
00321 }
00322
00327 inline void SetLabel(EdgeLabel* pLabel)
00328 {
00329 m_pLabel = pLabel;
00330 }
00331
00332 private:
00333 Vertex<T>* m_pSource;
00334 Vertex<T>* m_pTarget;
00335 EdgeLabel* m_pLabel;
00336 };
00337
00341
00342 template<typename T>
00343 class Visitor
00344 {
00345 public:
00351 virtual kt_bool Visit(Vertex<T>* pVertex) = 0;
00352 };
00353
00357
00358 template<typename T>
00359 class Graph;
00360
00361 template<typename T>
00362 class GraphTraversal
00363 {
00364 public:
00369 GraphTraversal(Graph<T>* pGraph)
00370 : m_pGraph(pGraph)
00371 {
00372 }
00373
00377 virtual ~GraphTraversal()
00378 {
00379 }
00380
00381 public:
00387 virtual std::vector<T*> Traverse(Vertex<T>* pStartVertex, Visitor<T>* pVisitor) = 0;
00388
00389 protected:
00390 Graph<T>* m_pGraph;
00391 };
00392
00396
00397 template<typename T>
00398 class Graph
00399 {
00400 public:
00401 typedef std::map<Name, std::vector<Vertex<T>*> > VertexMap;
00402
00403 public:
00407 Graph()
00408 : m_pTraversal(NULL)
00409 {
00410 }
00411
00415 virtual ~Graph()
00416 {
00417 Clear();
00418 }
00419
00420 public:
00426 inline void AddVertex(const Name& rName, Vertex<T>* pVertex)
00427 {
00428 m_Vertices[rName].push_back(pVertex);
00429 }
00430
00435 inline void AddEdge(Edge<T>* pEdge)
00436 {
00437 m_Edges.push_back(pEdge);
00438 }
00439
00443 void Clear()
00444 {
00445 forEachAs(typename VertexMap, &m_Vertices, indexIter)
00446 {
00447
00448 forEach(typename std::vector<Vertex<T>*>, &(indexIter->second))
00449 {
00450 delete *iter;
00451 }
00452 }
00453 m_Vertices.clear();
00454
00455 const_forEach(typename std::vector<Edge<T>*>, &m_Edges)
00456 {
00457 delete *iter;
00458 }
00459 m_Edges.clear();
00460 }
00461
00466 inline const std::vector<Edge<T>*>& GetEdges() const
00467 {
00468 return m_Edges;
00469 }
00470
00475 inline const VertexMap& GetVertices() const
00476 {
00477 return m_Vertices;
00478 }
00479
00480 protected:
00481 VertexMap m_Vertices;
00482 std::vector<Edge<T>*> m_Edges;
00483 GraphTraversal<T>* m_pTraversal;
00484 };
00485
00489
00490 class Mapper;
00491 class ScanMatcher;
00492
00493 class KARTO_EXPORT MapperGraph : public Graph<LocalizedRangeScan>
00494 {
00495 public:
00502 MapperGraph(Mapper* pMapper, kt_double rangeThreshold);
00503
00507 virtual ~MapperGraph();
00508
00509 public:
00514 void AddVertex(LocalizedRangeScan* pScan);
00515
00524 Edge<LocalizedRangeScan>* AddEdge(LocalizedRangeScan* pSourceScan, LocalizedRangeScan* pTargetScan, kt_bool& rIsNewEdge);
00525
00531 void AddEdges(LocalizedRangeScan* pScan, const Matrix3& rCovariance);
00532
00538 kt_bool TryCloseLoop(LocalizedRangeScan* pScan, const Name& rSensorName);
00539
00545 LocalizedRangeScanVector FindNearLinkedScans(LocalizedRangeScan* pScan, kt_double maxDistance);
00546
00551 inline ScanMatcher* GetLoopScanMatcher() const
00552 {
00553 return m_pLoopScanMatcher;
00554 }
00555
00556 private:
00562 inline Vertex<LocalizedRangeScan>* GetVertex(LocalizedRangeScan* pScan)
00563 {
00564 return m_Vertices[pScan->GetSensorName()][pScan->GetStateId()];
00565 }
00566
00572 LocalizedRangeScan* GetClosestScanToPose(const LocalizedRangeScanVector& rScans, const Pose2& rPose) const;
00573
00581 void LinkScans(LocalizedRangeScan* pFromScan, LocalizedRangeScan* pToScan, const Pose2& rMean, const Matrix3& rCovariance);
00582
00589 void LinkNearChains(LocalizedRangeScan* pScan, Pose2Vector& rMeans, std::vector<Matrix3>& rCovariances);
00590
00598 void LinkChainToScan(const LocalizedRangeScanVector& rChain, LocalizedRangeScan* pScan, const Pose2& rMean, const Matrix3& rCovariance);
00599
00605 std::vector<LocalizedRangeScanVector> FindNearChains(LocalizedRangeScan* pScan);
00606
00613 Pose2 ComputeWeightedMean(const Pose2Vector& rMeans, const std::vector<Matrix3>& rCovariances) const;
00614
00623 LocalizedRangeScanVector FindPossibleLoopClosure(LocalizedRangeScan* pScan, const Name& rSensorName, kt_int32u& rStartNum);
00624
00628 void CorrectPoses();
00629
00630 private:
00631 Mapper* m_pMapper;
00632
00633 ScanMatcher* m_pLoopScanMatcher;
00634 };
00635
00639
00640 class ScanSolver
00641 {
00642 public:
00643 typedef std::vector<std::pair<kt_int32s, Pose2> > IdPoseVector;
00644
00648 ScanSolver()
00649 {
00650 }
00651
00655 virtual ~ScanSolver()
00656 {
00657 }
00658
00659 public:
00663 virtual void Compute() = 0;
00664
00669 virtual const IdPoseVector& GetCorrections() const = 0;
00670
00675 virtual void AddNode(Vertex<LocalizedRangeScan>* )
00676 {
00677 }
00678
00683 virtual void RemoveNode(kt_int32s )
00684 {
00685 }
00686
00691 virtual void AddConstraint(Edge<LocalizedRangeScan>* )
00692 {
00693 }
00694
00700 virtual void RemoveConstraint(kt_int32s , kt_int32s )
00701 {
00702 }
00703
00707 virtual void Clear() {};
00708 };
00709
00713
00717 class CorrelationGrid : public Grid<kt_int8u>
00718 {
00719 public:
00723 virtual ~CorrelationGrid()
00724 {
00725 delete [] m_pKernel;
00726 }
00727
00728 public:
00736 static CorrelationGrid* CreateGrid(kt_int32s width, kt_int32s height, kt_double resolution, kt_double smearDeviation)
00737 {
00738 assert(resolution != 0.0);
00739
00740
00741 kt_int32u borderSize = GetHalfKernelSize(smearDeviation, resolution) + 1;
00742
00743 CorrelationGrid* pGrid = new CorrelationGrid(width, height, borderSize, resolution, smearDeviation);
00744
00745 return pGrid;
00746 }
00747
00754 virtual kt_int32s GridIndex(const Vector2<kt_int32s>& rGrid, kt_bool boundaryCheck = true) const
00755 {
00756 kt_int32s x = rGrid.GetX() + m_Roi.GetX();
00757 kt_int32s y = rGrid.GetY() + m_Roi.GetY();
00758
00759 return Grid<kt_int8u>::GridIndex(Vector2<kt_int32s>(x, y), boundaryCheck);
00760 }
00761
00766 inline const Rectangle2<kt_int32s>& GetROI() const
00767 {
00768 return m_Roi;
00769 }
00770
00775 inline void SetROI(const Rectangle2<kt_int32s>& roi)
00776 {
00777 m_Roi = roi;
00778 }
00779
00784 inline void SmearPoint(const Vector2<kt_int32s>& rGridPoint)
00785 {
00786 assert(m_pKernel != NULL);
00787
00788 int gridIndex = GridIndex(rGridPoint);
00789 if (GetDataPointer()[gridIndex] != GridStates_Occupied)
00790 {
00791 return;
00792 }
00793
00794 kt_int32s halfKernel = m_KernelSize / 2;
00795
00796
00797 for (kt_int32s j = -halfKernel; j <= halfKernel; j++)
00798 {
00799 kt_int8u* pGridAdr = GetDataPointer(Vector2<kt_int32s>(rGridPoint.GetX(), rGridPoint.GetY() + j));
00800
00801 kt_int32s kernelConstant = (halfKernel) + m_KernelSize * (j + halfKernel);
00802
00803
00804
00805
00806 for (kt_int32s i = -halfKernel; i <= halfKernel; i++)
00807 {
00808 kt_int32s kernelArrayIndex = i + kernelConstant;
00809
00810 kt_int8u kernelValue = m_pKernel[kernelArrayIndex];
00811 if (kernelValue > pGridAdr[i])
00812 {
00813
00814 pGridAdr[i] = kernelValue;
00815 }
00816 }
00817 }
00818 }
00819
00820 protected:
00827 CorrelationGrid(kt_int32u width, kt_int32u height, kt_int32u borderSize, kt_double resolution, kt_double smearDeviation)
00828 : Grid<kt_int8u>(width + borderSize * 2, height + borderSize * 2)
00829 , m_SmearDeviation(smearDeviation)
00830 , m_pKernel(NULL)
00831 {
00832 GetCoordinateConverter()->SetScale(1.0 / resolution);
00833
00834
00835 m_Roi = Rectangle2<kt_int32s>(borderSize, borderSize, width, height);
00836
00837
00838 CalculateKernel();
00839 }
00840
00844 virtual void CalculateKernel()
00845 {
00846 kt_double resolution = GetResolution();
00847
00848 assert(resolution != 0.0);
00849 assert(m_SmearDeviation != 0.0);
00850
00851
00852
00853 const kt_double MIN_SMEAR_DISTANCE_DEVIATION = 0.5 * resolution;
00854 const kt_double MAX_SMEAR_DISTANCE_DEVIATION = 10 * resolution;
00855
00856
00857 if (!math::InRange(m_SmearDeviation, MIN_SMEAR_DISTANCE_DEVIATION, MAX_SMEAR_DISTANCE_DEVIATION))
00858 {
00859 std::stringstream error;
00860 error << "Mapper Error: Smear deviation too small: Must be between " << MIN_SMEAR_DISTANCE_DEVIATION << " and " << MAX_SMEAR_DISTANCE_DEVIATION;
00861 throw std::runtime_error(error.str());
00862 }
00863
00864
00865
00866
00867 m_KernelSize = 2 * GetHalfKernelSize(m_SmearDeviation, resolution) + 1;
00868
00869
00870 m_pKernel = new kt_int8u[m_KernelSize * m_KernelSize];
00871 if (m_pKernel == NULL)
00872 {
00873 throw std::runtime_error("Unable to allocate memory for kernel!");
00874 }
00875
00876
00877 kt_int32s halfKernel = m_KernelSize / 2;
00878 for (kt_int32s i = -halfKernel; i <= halfKernel; i++)
00879 {
00880 for (kt_int32s j = -halfKernel; j <= halfKernel; j++)
00881 {
00882 #ifdef WIN32
00883 kt_double distanceFromMean = _hypot(i * resolution, j * resolution);
00884 #else
00885 kt_double distanceFromMean = hypot(i * resolution, j * resolution);
00886 #endif
00887 kt_double z = exp(-0.5 * pow(distanceFromMean / m_SmearDeviation, 2));
00888
00889 kt_int32u kernelValue = static_cast<kt_int32u>(math::Round(z * GridStates_Occupied));
00890 assert(math::IsUpTo(kernelValue, static_cast<kt_int32u>(255)));
00891
00892 int kernelArrayIndex = (i + halfKernel) + m_KernelSize * (j + halfKernel);
00893 m_pKernel[kernelArrayIndex] = static_cast<kt_int8u>(kernelValue);
00894 }
00895 }
00896 }
00897
00904 static kt_int32s GetHalfKernelSize(kt_double smearDeviation, kt_double resolution)
00905 {
00906 assert(resolution != 0.0);
00907
00908 return static_cast<kt_int32s>(math::Round(2.0 * smearDeviation / resolution));
00909 }
00910
00911 private:
00916 kt_double m_SmearDeviation;
00917
00918
00919 kt_int32s m_KernelSize;
00920
00921
00922 kt_int8u* m_pKernel;
00923
00924
00925 Rectangle2<kt_int32s> m_Roi;
00926 };
00927
00931
00932 class KARTO_EXPORT ScanMatcher
00933 {
00934 public:
00938 virtual ~ScanMatcher();
00939
00940 public:
00944 static ScanMatcher* Create(Mapper* pMapper, kt_double searchSize, kt_double resolution, kt_double smearDeviation, kt_double rangeThreshold);
00945
00956 kt_double MatchScan(LocalizedRangeScan* pScan, const LocalizedRangeScanVector& rBaseScans, Pose2& rMean, Matrix3& rCovariance,
00957 kt_bool doPenalize = true, kt_bool doRefineMatch = true);
00958
00975 kt_double CorrelateScan(LocalizedRangeScan* pScan, const Pose2& rSearchCenter, const Vector2<kt_double>& rSearchSpaceOffset, const Vector2<kt_double>& rSearchSpaceResolution,
00976 kt_double searchAngleOffset, kt_double searchAngleResolution, kt_bool doPenalize, Pose2& rMean, Matrix3& rCovariance, kt_bool doingFineMatch);
00977
00988 void ComputePositionalCovariance(const Pose2& rBestPose, kt_double bestResponse, const Pose2& rSearchCenter,
00989 const Vector2<kt_double>& rSearchSpaceOffset, const Vector2<kt_double>& rSearchSpaceResolution,
00990 kt_double searchAngleResolution, Matrix3& rCovariance);
00991
01001 void ComputeAngularCovariance(const Pose2& rBestPose, kt_double bestResponse, const Pose2& rSearchCenter,
01002 kt_double searchAngleOffset, kt_double searchAngleResolution, Matrix3& rCovariance);
01003
01008 inline CorrelationGrid* GetCorrelationGrid() const
01009 {
01010 return m_pCorrelationGrid;
01011 }
01012
01013 private:
01019 void AddScans(const LocalizedRangeScanVector& rScans, Vector2<kt_double> viewPoint);
01020
01027 void AddScan(LocalizedRangeScan* pScan, const Vector2<kt_double>& rViewPoint, kt_bool doSmear = true);
01028
01035 PointVectorDouble FindValidPoints(LocalizedRangeScan* pScan, const Vector2<kt_double>& rViewPoint) const;
01036
01043 kt_double GetResponse(kt_int32u angleIndex, kt_int32s gridPositionIndex) const;
01044
01045 protected:
01049 ScanMatcher(Mapper* pMapper)
01050 : m_pMapper(pMapper)
01051 , m_pCorrelationGrid(NULL)
01052 , m_pSearchSpaceProbs(NULL)
01053 {
01054 }
01055
01056 private:
01057 Mapper* m_pMapper;
01058
01059 CorrelationGrid* m_pCorrelationGrid;
01060 Grid<kt_double>* m_pSearchSpaceProbs;
01061
01062 GridIndexLookup<kt_int8u>* m_pGridLookup;
01063
01064 };
01065
01069
01070 class ScanManager;
01071
01075 class KARTO_EXPORT MapperSensorManager
01076 {
01077 typedef std::map<Name, ScanManager*> ScanManagerMap;
01078
01079 public:
01083 MapperSensorManager(kt_int32u runningBufferMaximumSize, kt_double runningBufferMaximumDistance)
01084 : m_RunningBufferMaximumSize(runningBufferMaximumSize)
01085 , m_RunningBufferMaximumDistance(runningBufferMaximumDistance)
01086 , m_NextScanId(0)
01087 {
01088 }
01089
01093 virtual ~MapperSensorManager()
01094 {
01095 Clear();
01096 }
01097
01098 public:
01104 void RegisterSensor(const Name& rSensorName);
01105
01112 LocalizedRangeScan* GetScan(const Name& rSensorName, kt_int32s scanIndex);
01113
01118 inline std::vector<Name> GetSensorNames()
01119 {
01120 std::vector<Name> deviceNames;
01121 const_forEach(ScanManagerMap, &m_ScanManagers)
01122 {
01123 deviceNames.push_back(iter->first);
01124 }
01125
01126 return deviceNames;
01127 }
01128
01134 LocalizedRangeScan* GetLastScan(const Name& rSensorName);
01135
01140 inline void SetLastScan(LocalizedRangeScan* pScan);
01141
01147 inline LocalizedRangeScan* GetScan(kt_int32s id)
01148 {
01149 assert(math::IsUpTo(id, (kt_int32s)m_Scans.size()));
01150
01151 return m_Scans[id];
01152 }
01153
01158 void AddScan(LocalizedRangeScan* pScan);
01159
01164 void AddRunningScan(LocalizedRangeScan* pScan);
01165
01171 LocalizedRangeScanVector& GetScans(const Name& rSensorName);
01172
01178 LocalizedRangeScanVector& GetRunningScans(const Name& rSensorName);
01179
01184 LocalizedRangeScanVector GetAllScans();
01185
01189 void Clear();
01190
01191 private:
01196 inline ScanManager* GetScanManager(LocalizedRangeScan* pScan)
01197 {
01198 return GetScanManager(pScan->GetSensorName());
01199 }
01200
01206 inline ScanManager* GetScanManager(const Name& rSensorName)
01207 {
01208 if(m_ScanManagers.find(rSensorName) != m_ScanManagers.end())
01209 {
01210 return m_ScanManagers[rSensorName];
01211 }
01212
01213 return NULL;
01214 }
01215
01216 private:
01217
01218 ScanManagerMap m_ScanManagers;
01219
01220 kt_int32u m_RunningBufferMaximumSize;
01221 kt_double m_RunningBufferMaximumDistance;
01222
01223 kt_int32s m_NextScanId;
01224
01225 std::vector<LocalizedRangeScan*> m_Scans;
01226 };
01227
01231
01235 class KARTO_EXPORT Mapper : public Module
01236 {
01237 friend class MapperGraph;
01238 friend class ScanMatcher;
01239
01240 public:
01244 Mapper();
01245
01250 Mapper(const std::string& rName);
01251
01255 virtual ~Mapper();
01256
01257 public:
01262 void Initialize(kt_double rangeThreshold);
01263
01268 void Reset();
01269
01281 virtual kt_bool Process(LocalizedRangeScan* pScan);
01282
01283 virtual kt_bool Process(Object* pObject);
01284
01291 virtual const LocalizedRangeScanVector GetAllProcessedScans() const;
01292
01297 void AddListener(MapperListener* pListener);
01298
01303 void RemoveListener(MapperListener* pListener);
01304
01309 void SetScanSolver(ScanSolver* pSolver);
01310
01315 virtual MapperGraph* GetGraph() const;
01316
01321 virtual ScanMatcher* GetSequentialScanMatcher() const;
01322
01327 virtual ScanMatcher* GetLoopScanMatcher() const;
01328
01333 inline MapperSensorManager* GetMapperSensorManager() const
01334 {
01335 return m_pMapperSensorManager;
01336 }
01337
01344 inline kt_bool TryCloseLoop(LocalizedRangeScan* pScan, const Name& rSensorName)
01345 {
01346 return m_pGraph->TryCloseLoop(pScan, rSensorName);
01347 }
01348
01349 private:
01350 void InitializeParameters();
01351
01359 kt_bool HasMovedEnough(LocalizedRangeScan* pScan, LocalizedRangeScan* pLastScan) const;
01360
01361 public:
01363
01364
01369 void FireInfo(const std::string& rInfo) const;
01370
01375 void FireDebug(const std::string& rInfo) const;
01376
01381 void FireLoopClosureCheck(const std::string& rInfo) const;
01382
01387 void FireBeginLoopClosure(const std::string& rInfo) const;
01388
01393 void FireEndLoopClosure(const std::string& rInfo) const;
01394
01395
01396
01397
01398
01399
01400
01401 private:
01405 Mapper(const Mapper&);
01406
01410 const Mapper& operator=(const Mapper&);
01411
01412 private:
01413 kt_bool m_Initialized;
01414
01415 ScanMatcher* m_pSequentialScanMatcher;
01416
01417 MapperSensorManager* m_pMapperSensorManager;
01418
01419 MapperGraph* m_pGraph;
01420 ScanSolver* m_pScanOptimizer;
01421
01422 std::vector<MapperListener*> m_Listeners;
01423
01424
01433 Parameter<kt_bool>* m_pUseScanMatching;
01434
01438 Parameter<kt_bool>* m_pUseScanBarycenter;
01439
01448 Parameter<kt_double>* m_pMinimumTravelDistance;
01449
01458 Parameter<kt_double>* m_pMinimumTravelHeading;
01459
01468 Parameter<kt_int32u>* m_pScanBufferSize;
01469
01475 Parameter<kt_double>* m_pScanBufferMaximumScanDistance;
01476
01481 Parameter<kt_double>* m_pLinkMatchMinimumResponseFine;
01482
01488 Parameter<kt_double>* m_pLinkScanMaximumDistance;
01489
01495 Parameter<kt_double>* m_pLoopSearchMaximumDistance;
01496
01503 Parameter<kt_int32u>* m_pLoopMatchMinimumChainSize;
01504
01510 Parameter<kt_double>* m_pLoopMatchMaximumVarianceCoarse;
01511
01516 Parameter<kt_double>* m_pLoopMatchMinimumResponseCoarse;
01517
01522 Parameter<kt_double>* m_pLoopMatchMinimumResponseFine;
01523
01525
01526
01531 Parameter<kt_double>* m_pCorrelationSearchSpaceDimension;
01532
01537 Parameter<kt_double>* m_pCorrelationSearchSpaceResolution;
01538
01543 Parameter<kt_double>* m_pCorrelationSearchSpaceSmearDeviation;
01544
01545
01547
01548
01553 Parameter<kt_double>* m_pLoopSearchSpaceDimension;
01554
01559 Parameter<kt_double>* m_pLoopSearchSpaceResolution;
01560
01565 Parameter<kt_double>* m_pLoopSearchSpaceSmearDeviation;
01566
01568
01569
01570
01571
01572
01573 Parameter<kt_double>* m_pDistanceVariancePenalty;
01574 Parameter<kt_double>* m_pAngleVariancePenalty;
01575
01576
01577 Parameter<kt_double>* m_pFineSearchAngleOffset;
01578 Parameter<kt_double>* m_pCoarseSearchAngleOffset;
01579
01580
01581 Parameter<kt_double>* m_pCoarseAngleResolution;
01582
01583
01584
01585 Parameter<kt_double>* m_pMinimumAnglePenalty;
01586 Parameter<kt_double>* m_pMinimumDistancePenalty;
01587
01588
01589 Parameter<kt_bool>* m_pUseResponseExpansion;
01590
01591 };
01592
01593 }
01594
01595 #endif // __KARTO_MAPPER__