Main MRPT website > C++ reference for MRPT 1.9.9
CMetricMapBuilder.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #include "slam-precomp.h" // Precompiled headers
11 
12 #include <mrpt/system/filesystem.h>
19 
20 using namespace mrpt::slam;
21 using namespace mrpt::maps;
22 using namespace mrpt::poses;
23 using namespace mrpt::utils;
24 
26  : mrpt::utils::COutputLogger("CMetricMapBuilder"),
27  options(this->m_min_verbosity_level)
28 {
29  MRPT_LOG_DEBUG("CMetricMapBuilder ctor.");
30 }
31 
33 {
34  MRPT_LOG_DEBUG("CMetricMapBuilder dtor.");
35 }
36 
37 /*---------------------------------------------------------------
38  clear
39 Clear all elements of the maps, and reset localization to (0,0,0deg).
40  ---------------------------------------------------------------*/
42 {
43  MRPT_LOG_DEBUG("CMetricMapBuilder::clear() called.");
44  CSimpleMap dummyMap;
45  CPosePDFGaussian dummyPose;
46 
47  // Initialize with an empty map and pose to (0,0,0)
48  initialize(dummyMap, &dummyPose);
49 }
50 
51 /*---------------------------------------------------------------
52  loadCurrentMapFromFile
53  ---------------------------------------------------------------*/
55 {
56  CSimpleMap map;
57 
58  // New file??
59  if (mrpt::system::fileExists(fileName))
60  {
62  "[CMetricMapBuilder::loadCurrentMapFromFile] Loading current map "
63  "from '"
64  << fileName << "' ..." << std::endl);
65  CFileGZInputStream f(fileName);
66 
67  // Load from file:
68  f >> map;
69  }
70  else
71  { // Is a new file, start with an empty map:
73  "[CMetricMapBuilder::loadCurrentMapFromFile] Loading current map "
74  "from '"
75  << fileName << "' ..." << std::endl);
76  map.clear();
77  }
78 
79  // Initialize the map builder with this map
80  initialize(map);
81 }
82 
83 /*---------------------------------------------------------------
84  saveCurrentMapToFile
85  ---------------------------------------------------------------*/
87  const std::string& fileName, bool compressGZ) const
88 {
89  // get current map:
90  CSimpleMap curmap;
91  getCurrentlyBuiltMap(curmap);
92 
94  "[CMetricMapBuilder::saveCurrentMapToFile] Saving current map to '"
95  << fileName << "' ..." << std::endl);
96 
97  // Save to file:
98  if (compressGZ)
99  CFileGZOutputStream(fileName) << curmap;
100  else
101  CFileOutputStream(fileName) << curmap;
102 }
void saveCurrentMapToFile(const std::string &fileName, bool compressGZ=true) const
Save map (mrpt::maps::CSimpleMap) to a ".simplemap" file.
void clear()
Clear all elements of the maps, and reset localization to (0,0,0deg).
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...
Definition: CSimpleMap.h:35
bool fileExists(const std::string &fileName)
Test if a given file (or directory) exists.
Definition: filesystem.cpp:127
Declares a class that represents a Probability Density function (PDF) of a 2D pose ...
This CStream derived class allow using a file as a write-only, binary stream.
Transparently opens a compressed "gz" file and reads uncompressed data from it.
#define MRPT_LOG_WARN_STREAM(__CONTENTS)
#define MRPT_LOG_DEBUG(_STRING)
void loadCurrentMapFromFile(const std::string &fileName)
Load map (mrpt::maps::CSimpleMap) from a ".simplemap" file.
GLsizei const GLchar ** string
Definition: glext.h:4101
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Definition: CPoint.h:17
virtual void getCurrentlyBuiltMap(mrpt::maps::CSimpleMap &out_map) const =0
Fills "out_map" with the set of "poses"-"sensory-frames", thus the so far built map.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define MRPT_LOG_INFO_STREAM(__CONTENTS)
#define CFileGZOutputStream
Saves data to a file and transparently compress the data using the given compression level...
virtual void initialize(const mrpt::maps::CSimpleMap &initialMap=mrpt::maps::CSimpleMap(), const mrpt::poses::CPosePDF *x0=nullptr)=0
Initialize the method, starting with a known location PDF "x0"(if supplied, set to nullptr to left un...
virtual ~CMetricMapBuilder()
Destructor.
void clear()
Remove all stored pairs.
Definition: CSimpleMap.cpp:70



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019