MapRepMultiMap.h
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2011, Stefan Kohlbrecher, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Simulation, Systems Optimization and Robotics
13 // group, TU Darmstadt nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 #ifndef _hectormaprepmultimap_h__
30 #define _hectormaprepmultimap_h__
31 
33 #include "MapProcContainer.h"
34 
35 #include "../map/GridMap.h"
36 #include "../map/OccGridMapUtilConfig.h"
37 #include "../matcher/ScanMatcher.h"
38 
39 #include "../util/DrawInterface.h"
40 #include "../util/HectorDebugInfoInterface.h"
41 
42 namespace hectorslam{
43 
45 {
46 
47 public:
48  MapRepMultiMap(float mapResolution, int mapSizeX, int mapSizeY, unsigned int numDepth, const Eigen::Vector2f& startCoords, DrawInterface* drawInterfaceIn, HectorDebugInfoInterface* debugInterfaceIn)
49  {
50  //unsigned int numDepth = 3;
51  Eigen::Vector2i resolution(mapSizeX, mapSizeY);
52 
53  float totalMapSizeX = mapResolution * static_cast<float>(mapSizeX);
54  float mid_offset_x = totalMapSizeX * startCoords.x();
55 
56  float totalMapSizeY = mapResolution * static_cast<float>(mapSizeY);
57  float mid_offset_y = totalMapSizeY * startCoords.y();
58 
59  for (unsigned int i = 0; i < numDepth; ++i){
60  std::cout << "HectorSM map lvl " << i << ": cellLength: " << mapResolution << " res x:" << resolution.x() << " res y: " << resolution.y() << "\n";
61  GridMap* gridMap = new hectorslam::GridMap(mapResolution,resolution, Eigen::Vector2f(mid_offset_x, mid_offset_y));
63  ScanMatcher<OccGridMapUtilConfig<GridMap> >* scanMatcher = new hectorslam::ScanMatcher<OccGridMapUtilConfig<GridMap> >(drawInterfaceIn, debugInterfaceIn);
64 
65  mapContainer.push_back(MapProcContainer(gridMap, gridMapUtil, scanMatcher));
66 
67  resolution /= 2;
68  mapResolution*=2.0f;
69  }
70 
71  dataContainers.resize(numDepth-1);
72  }
73 
74  virtual ~MapRepMultiMap()
75  {
76  unsigned int size = mapContainer.size();
77 
78  for (unsigned int i = 0; i < size; ++i){
79  mapContainer[i].cleanup();
80  }
81  }
82 
83  virtual void reset()
84  {
85  unsigned int size = mapContainer.size();
86 
87  for (unsigned int i = 0; i < size; ++i){
88  mapContainer[i].reset();
89  }
90  }
91 
92  virtual float getScaleToMap() const { return mapContainer[0].getScaleToMap(); };
93 
94  virtual int getMapLevels() const { return mapContainer.size(); };
95  virtual const GridMap& getGridMap(int mapLevel) const { return mapContainer[mapLevel].getGridMap(); };
96 
97  virtual void addMapMutex(int i, MapLockerInterface* mapMutex)
98  {
99  mapContainer[i].addMapMutex(mapMutex);
100  }
101 
103  {
104  return mapContainer[i].getMapMutex();
105  }
106 
107  virtual void onMapUpdated()
108  {
109  unsigned int size = mapContainer.size();
110 
111  for (unsigned int i = 0; i < size; ++i){
112  mapContainer[i].resetCachedData();
113  }
114  }
115 
116  virtual Eigen::Vector3f matchData(const Eigen::Vector3f& beginEstimateWorld, const DataContainer& dataContainer, Eigen::Matrix3f& covMatrix)
117  {
118  size_t size = mapContainer.size();
119 
120  Eigen::Vector3f tmp(beginEstimateWorld);
121 
122  for (int index = size - 1; index >= 0; --index){
123  //std::cout << " m " << i;
124  if (index == 0){
125  tmp = (mapContainer[index].matchData(tmp, dataContainer, covMatrix, 5));
126  }else{
127  dataContainers[index-1].setFrom(dataContainer, static_cast<float>(1.0 / pow(2.0, static_cast<double>(index))));
128  tmp = (mapContainer[index].matchData(tmp, dataContainers[index-1], covMatrix, 3));
129  }
130  }
131  return tmp;
132  }
133 
134  virtual void updateByScan(const DataContainer& dataContainer, const Eigen::Vector3f& robotPoseWorld)
135  {
136  unsigned int size = mapContainer.size();
137 
138  for (unsigned int i = 0; i < size; ++i){
139  //std::cout << " u " << i;
140  if (i==0){
141  mapContainer[i].updateByScan(dataContainer, robotPoseWorld);
142  }else{
143  mapContainer[i].updateByScan(dataContainers[i-1], robotPoseWorld);
144  }
145  }
146  //std::cout << "\n";
147  }
148 
149  virtual void setUpdateFactorFree(float free_factor)
150  {
151  size_t size = mapContainer.size();
152 
153  for (unsigned int i = 0; i < size; ++i){
154  GridMap& map = mapContainer[i].getGridMap();
155  map.setUpdateFreeFactor(free_factor);
156  }
157  }
158 
159  virtual void setUpdateFactorOccupied(float occupied_factor)
160  {
161  size_t size = mapContainer.size();
162 
163  for (unsigned int i = 0; i < size; ++i){
164  GridMap& map = mapContainer[i].getGridMap();
165  map.setUpdateOccupiedFactor(occupied_factor);
166  }
167  }
168 
169 protected:
170  std::vector<MapProcContainer> mapContainer;
171  std::vector<DataContainer> dataContainers;
172 };
173 
174 }
175 
176 #endif
void setUpdateFreeFactor(float factor)
virtual void setUpdateFactorFree(float free_factor)
MapLockerInterface * getMapMutex(int i)
virtual const GridMap & getGridMap(int mapLevel) const
virtual void setUpdateFactorOccupied(float occupied_factor)
std::vector< MapProcContainer > mapContainer
virtual int getMapLevels() const
std::vector< DataContainer > dataContainers
virtual float getScaleToMap() const
void setUpdateOccupiedFactor(float factor)
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
virtual void updateByScan(const DataContainer &dataContainer, const Eigen::Vector3f &robotPoseWorld)
virtual Eigen::Vector3f matchData(const Eigen::Vector3f &beginEstimateWorld, const DataContainer &dataContainer, Eigen::Matrix3f &covMatrix)
OccGridMapBase< LogOddsCell, GridMapLogOddsFunctions > GridMap
Definition: GridMap.h:39
MapRepMultiMap(float mapResolution, int mapSizeX, int mapSizeY, unsigned int numDepth, const Eigen::Vector2f &startCoords, DrawInterface *drawInterfaceIn, HectorDebugInfoInterface *debugInterfaceIn)
virtual void addMapMutex(int i, MapLockerInterface *mapMutex)


hector_mapping
Author(s): Stefan Kohlbrecher
autogenerated on Sun Nov 3 2019 03:18:33