00001 /* +---------------------------------------------------------------------------+ 00002 | The Mobile Robot Programming Toolkit (MRPT) C++ library | 00003 | | 00004 | http://mrpt.sourceforge.net/ | 00005 | | 00006 | Copyright (C) 2005-2009 University of Malaga | 00007 | | 00008 | This software was written by the Machine Perception and Intelligent | 00009 | Robotics Lab, University of Malaga (Spain). | 00010 | Contact: Jose-Luis Blanco <jlblanco@ctima.uma.es> | 00011 | | 00012 | This file is part of the MRPT project. | 00013 | | 00014 | MRPT is free software: you can redistribute it and/or modify | 00015 | it under the terms of the GNU General Public License as published by | 00016 | the Free Software Foundation, either version 3 of the License, or | 00017 | (at your option) any later version. | 00018 | | 00019 | MRPT is distributed in the hope that it will be useful, | 00020 | but WITHOUT ANY WARRANTY; without even the implied warranty of | 00021 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the | 00022 | GNU General Public License for more details. | 00023 | | 00024 | You should have received a copy of the GNU General Public License | 00025 | along with MRPT. If not, see <http://www.gnu.org/licenses/>. | 00026 | | 00027 +---------------------------------------------------------------------------+ */ 00028 #ifndef CMultiMetricMap_H 00029 #define CMultiMetricMap_H 00030 00031 #include <mrpt/slam/COccupancyGridMap2D.h> 00032 #include <mrpt/slam/CGasConcentrationGridMap2D.h> 00033 #include <mrpt/slam/CHeightGridMap2D.h> 00034 #include <mrpt/slam/CSimplePointsMap.h> 00035 #include <mrpt/slam/CColouredPointsMap.h> 00036 #include <mrpt/slam/CLandmarksMap.h> 00037 #include <mrpt/slam/CBeaconMap.h> 00038 #include <mrpt/slam/CMetricMap.h> 00039 #include <mrpt/utils/CSerializable.h> 00040 #include <mrpt/utils/CLoadableOptions.h> 00041 00042 namespace mrpt 00043 { 00044 namespace slam 00045 { 00046 class TSetOfMetricMapInitializers; 00047 00048 DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE( CMultiMetricMap , CMetricMap ) 00049 00050 /** This class stores any customizable set of metric maps. 00051 * The internal metric maps can be accessed directly by the user. 00052 * If some kind of map is not desired, it can be just ignored, but if this fact is specified in the 00053 * "CMultiMetricMap::mapsUsage" member some methods (as the observation insertion) will be more 00054 * efficient since it will be invoked on desired maps only.<br><br> 00055 * <b>Currently these metric maps are supported for being kept internally:</b>: 00056 * - mrpt::slam::CPointsMap: For laser 2D range scans, and posibly for IR ranges,... (It keeps the full 3D structure of scans) 00057 * - mrpt::slam::COccupancyGridMap2D: Exclusively for 2D, <b>horizontal</b> laser range scans, at different altitudes. 00058 * - mrpt::slam::CLandmarksMap: For visual landmarks,etc... 00059 * - mrpt::slam::CGasConcentrationGridMap2D: For gas concentration maps. 00060 * - mrpt::slam::CBeaconMap: For range-only SLAM. 00061 * - mrpt::slam::CHeightGridMap2D: For maps of height for each (x,y) location. 00062 * - mrpt::slam::CColouredPointsMap: For points map with color. 00063 * 00064 * See CMultiMetricMap::setListOfMaps() for the method for initializing this class. 00065 * 00066 * \sa CMetricMap 00067 */ 00068 class MRPTDLLIMPEXP CMultiMetricMap : public CMetricMap 00069 { 00070 // This must be added to any CSerializable derived class: 00071 DEFINE_SERIALIZABLE( CMultiMetricMap ) 00072 00073 protected: 00074 /** Deletes all maps and clears the internal lists of maps. 00075 */ 00076 void deleteAllMaps(); 00077 00078 public: 00079 typedef std::pair<CPoint3D,unsigned int> TPairIdBeacon; 00080 00081 /** Returns true if the map is empty/no observation has been inserted. 00082 */ 00083 bool isEmpty() const; 00084 00085 /** Some options for this class: 00086 */ 00087 struct MRPTDLLIMPEXP TOptions : public utils::CLoadableOptions 00088 { 00089 TOptions() : likelihoodMapSelection(mapFuseAll), 00090 enableInsertion_pointsMap(true), 00091 enableInsertion_landmarksMap(true), 00092 enableInsertion_gridMaps(true), 00093 enableInsertion_gasGridMaps(true), 00094 enableInsertion_beaconMap(true), 00095 enableInsertion_heightMaps(true), 00096 enableInsertion_colourPointsMaps(true) 00097 { 00098 } 00099 00100 /** Load parameters from configuration source 00101 */ 00102 void loadFromConfigFile( 00103 const mrpt::utils::CConfigFileBase &source, 00104 const std::string §ion); 00105 00106 /** This method must display clearly all the contents of the structure in textual form, sending it to a CStream. 00107 */ 00108 void dumpToTextStream(CStream &out) const; 00109 00110 /** This selects the map to be used when computing the likelihood of an observation. 00111 * \sa computeObservationLikelihood 00112 */ 00113 enum TMapSelectionForLikelihood 00114 { 00115 mapFuseAll = -1, 00116 mapGrid = 0, 00117 mapPoints, 00118 mapLandmarks, 00119 mapGasGrid, 00120 mapBeacon, 00121 mapHeight, 00122 mapColourPoints 00123 } likelihoodMapSelection; 00124 00125 /** Default = true (set to false to avoid "insertObservation" to update a given map) 00126 */ 00127 bool enableInsertion_pointsMap; 00128 00129 /** Default = true (set to false to avoid "insertObservation" to update a given map) 00130 */ 00131 bool enableInsertion_landmarksMap; 00132 00133 /** Default = true (set to false to avoid "insertObservation" to update a given map) 00134 */ 00135 bool enableInsertion_gridMaps; 00136 00137 /** Default = true (set to false to avoid "insertObservation" to update a given map) 00138 */ 00139 bool enableInsertion_gasGridMaps; 00140 00141 /** Default = true (set to false to avoid "insertObservation" to update a given map) 00142 */ 00143 bool enableInsertion_beaconMap; 00144 00145 /** Default = true (set to false to avoid "insertObservation" to update a given map) 00146 */ 00147 bool enableInsertion_heightMaps; 00148 00149 /** Default = true (set to false to avoid "insertObservation" to update a given map) 00150 */ 00151 bool enableInsertion_colourPointsMaps; 00152 00153 00154 } options; 00155 00156 /** Some of the internal metric maps (the number of point-maps depends on the the TSetOfMetricMapInitializers passed to the constructor of this class) 00157 */ 00158 std::deque<CSimplePointsMapPtr> m_pointsMaps; 00159 00160 /** One of the internal metric map (will be NULL if not used, what comes from the TSetOfMetricMapInitializers passed to the constructor of this class) 00161 */ 00162 CLandmarksMapPtr m_landmarksMap; 00163 00164 /** One of the internal metric map (will be NULL if not used, what comes from the TSetOfMetricMapInitializers passed to the constructor of this class) 00165 */ 00166 CBeaconMapPtr m_beaconMap; 00167 00168 /** Some of the internal metric maps (the number of gridmaps depends on the the TSetOfMetricMapInitializers passed to the constructor of this class) 00169 */ 00170 std::deque<COccupancyGridMap2DPtr> m_gridMaps; 00171 00172 /** Some of the internal metric maps (the number of gas gridmaps depends on the the TSetOfMetricMapInitializers passed to the constructor of this class) 00173 */ 00174 std::deque<CGasConcentrationGridMap2DPtr> m_gasGridMaps; 00175 00176 /** Some of the internal metric maps (the number of gas gridmaps depends on the the TSetOfMetricMapInitializers passed to the constructor of this class) 00177 */ 00178 std::deque<CHeightGridMap2DPtr> m_heightMaps; 00179 00180 /** One of the internal metric map (will be NULL if not used, what comes from the TSetOfMetricMapInitializers passed to the constructor of this class) 00181 */ 00182 CColouredPointsMapPtr m_colourPointsMap; 00183 00184 /** Constructor. 00185 * \param initializers One internal map will be created for each entry in this "TSetOfMetricMapInitializers" struct, and each map will be initialized with the corresponding options. 00186 * \param opts If provided (not NULL), the member "options" will be initialized with those values. 00187 * If initializers is NULL, no internal map will be created. 00188 */ 00189 CMultiMetricMap( 00190 const mrpt::slam::TSetOfMetricMapInitializers *initializers = NULL, 00191 const TOptions *opts = NULL ); 00192 00193 /** Sets the list of internal map according to the passed list of map initializers (Current maps' content will be deleted!) 00194 */ 00195 void setListOfMaps( const mrpt::slam::TSetOfMetricMapInitializers *initializers ); 00196 00197 /** Copy constructor */ 00198 CMultiMetricMap(const mrpt::slam::CMultiMetricMap &other ); 00199 00200 /** Copy operator from "other" object. 00201 */ 00202 mrpt::slam::CMultiMetricMap &operator = ( const mrpt::slam::CMultiMetricMap &other ); 00203 00204 /** Destructor. 00205 */ 00206 virtual ~CMultiMetricMap( ); 00207 00208 /** Clear all elements of the map. 00209 */ 00210 void clear(); 00211 00212 /** Computes the likelihood that a given observation was taken from a given pose in the world being modeled with this map. 00213 * 00214 * \param takenFrom The robot's pose the observation is supposed to be taken from. 00215 * \param obs The observation. 00216 * \return This method returns a likelihood in the range [0,1]. 00217 * 00218 * \sa likelihoodMapSelection, Used in particle filter algorithms, see: CMultiMetricMapPDF::update 00219 */ 00220 double computeObservationLikelihood( const CObservation *obs, const CPose3D &takenFrom ); 00221 00222 /** Returns the ratio of points in a map which are new to the points map while falling into yet static cells of gridmap. 00223 * \param points The set of points to check. 00224 * \param takenFrom The pose for the reference system of points, in global coordinates of this hybrid map. 00225 */ 00226 float getNewStaticPointsRatio( 00227 CPointsMap *points, 00228 CPose2D &takenFrom ); 00229 00230 /** Insert the observation information into this map (see options) 00231 * \param obs The observation 00232 * \param robotPose The 3D pose of the robot mobile base in the map reference system, or NULL (default) if you want to use CPose2D(0,0,deg) 00233 * 00234 * \sa CObservation::insertObservationInto 00235 */ 00236 bool insertObservation( const CObservation *obs, const CPose3D *robotPose = NULL ); 00237 00238 /** See the definition in the base class: In this class calls to this method are passed to the inner points map. 00239 * 00240 * \sa computeMatching3DWith 00241 */ 00242 void computeMatchingWith2D( 00243 const CMetricMap *otherMap, 00244 const CPose2D &otherMapPose, 00245 float maxDistForCorrespondence, 00246 float maxAngularDistForCorrespondence, 00247 const CPose2D &angularDistPivotPoint, 00248 TMatchingPairList &correspondences, 00249 float &correspondencesRatio, 00250 float *sumSqrDist = NULL, 00251 bool onlyKeepTheClosest = false, 00252 bool onlyUniqueRobust = false ) const; 00253 00254 /** Computes the ratio in [0,1] of correspondences between "this" and the "otherMap" map, whose 6D pose relative to "this" is "otherMapPose" 00255 * In the case of a multi-metric map, this returns the average between the maps. This method always return 0 for grid maps. 00256 * \param otherMap [IN] The other map to compute the matching with. 00257 * \param otherMapPose [IN] The 6D pose of the other map as seen from "this". 00258 * \param minDistForCorr [IN] The minimum distance between 2 non-probabilistic map elements for counting them as a correspondence. 00259 * \param minMahaDistForCorr [IN] The minimum Mahalanobis distance between 2 probabilistic map elements for counting them as a correspondence. 00260 * 00261 * \return The matching ratio [0,1] 00262 * \sa computeMatchingWith2D 00263 */ 00264 float compute3DMatchingRatio( 00265 const CMetricMap *otherMap, 00266 const CPose3D &otherMapPose, 00267 float minDistForCorr = 0.10f, 00268 float minMahaDistForCorr = 2.0f 00269 ) const; 00270 00271 /** The implementation in this class just calls all the corresponding method of the contained metric maps. 00272 */ 00273 void saveMetricMapRepresentationToFile( 00274 const std::string &filNamePrefix 00275 ) const; 00276 00277 /** This method is called at the end of each "prediction-update-map insertion" cycle within "mrpt::slam::CMetricMapBuilderRBPF::processActionObservation". 00278 * This method should normally do nothing, but in some cases can be used to free auxiliary cached variables. 00279 */ 00280 void auxParticleFilterCleanUp(); 00281 00282 /** Returns a 3D object representing the map. 00283 */ 00284 void getAs3DObject ( mrpt::opengl::CSetOfObjectsPtr &outObj ) const; 00285 00286 /** Returns true if this map is able to compute a sensible likelihood function for this observation (i.e. an occupancy grid map cannot with an image). 00287 * \param obs The observation. 00288 * \sa computeObservationLikelihood 00289 */ 00290 bool canComputeObservationLikelihood( const CObservation *obs ); 00291 00292 /** An auxiliary variable that can be used freely by the users (this will be copied to other maps using the copy constructor, copy operator, streaming,etc) The default value is 0. 00293 */ 00294 unsigned int m_ID; 00295 00296 }; // End of class def. 00297 00298 /** Each structure of this kind will determine the kind (and initial configuration) of one map to be build into a CMultiMetricMap object. 00299 * See "mrpt::slam::TSetOfMetricMapInitializers::loadFromConfigFile" as an easy way of initialize this object. 00300 * \sa TSetOfMetricMapInitializers, CMultiMetricMap::CMultiMetricMap 00301 */ 00302 struct MRPTDLLIMPEXP TMetricMapInitializer 00303 { 00304 /** Initialization (sets 'metricMapClassType' to NULL, an invalid value -> it must be set correctly before use!) 00305 */ 00306 TMetricMapInitializer(); 00307 00308 /** Set this to CLASS_ID(< class >) where < class > is any CMetricMap derived class. 00309 */ 00310 TRuntimeClassIdPtr metricMapClassType; 00311 00312 /** This value will be copied to the member with the same value in the map, see mrpt::slam::CMetricMap::m_disableSaveAs3DObject 00313 */ 00314 bool m_disableSaveAs3DObject; 00315 00316 /** Especific options for grid maps (mrpt::slam::COccupancyGridMap2D) 00317 */ 00318 struct MRPTDLLIMPEXP TOccGridMap2DOptions 00319 { 00320 /** Default values loader 00321 */ 00322 TOccGridMap2DOptions(); 00323 00324 /** See COccupancyGridMap2D::COccupancyGridMap2D 00325 */ 00326 float min_x,max_x,min_y,max_y,resolution; 00327 00328 /** Customizable initial options. 00329 */ 00330 COccupancyGridMap2D::TInsertionOptions insertionOpts; 00331 00332 /** Customizable initial options. 00333 */ 00334 COccupancyGridMap2D::TLikelihoodOptions likelihoodOpts; 00335 00336 } occupancyGridMap2D_options; 00337 00338 /** Especific options for points maps (mrpt::slam::CPointsMap) 00339 */ 00340 struct MRPTDLLIMPEXP CPointsMapOptions 00341 { 00342 /** Default values loader 00343 */ 00344 CPointsMapOptions(); 00345 00346 /** Customizable initial options for loading the class' own defaults. 00347 */ 00348 CPointsMap::TInsertionOptions insertionOpts; 00349 00350 } pointsMapOptions_options; 00351 00352 /** Especific options for gas grid maps (mrpt::slam::CGasConcentrationGridMap2D) 00353 */ 00354 struct MRPTDLLIMPEXP CGasConcentrationGridMap2DOptions 00355 { 00356 /** Default values loader 00357 */ 00358 CGasConcentrationGridMap2DOptions(); 00359 00360 /** See CGasConcentrationGridMap2D::CGasConcentrationGridMap2D 00361 */ 00362 float min_x,max_x,min_y,max_y,resolution; 00363 00364 /** The kind of map representation (see CGasConcentrationGridMap2D::CGasConcentrationGridMap2D) 00365 */ 00366 CGasConcentrationGridMap2D::TMapRepresentation mapType; 00367 00368 /** Customizable initial options. 00369 */ 00370 CGasConcentrationGridMap2D::TInsertionOptions insertionOpts; 00371 00372 } gasGridMap_options; 00373 00374 /** Especific options for landmarks maps (mrpt::slam::CLandmarksMap) 00375 */ 00376 struct MRPTDLLIMPEXP CLandmarksMapOptions 00377 { 00378 /** Default values loader 00379 */ 00380 CLandmarksMapOptions(); 00381 00382 /** Initial contents of the map, especified by a set of 3D Beacons with associated IDs 00383 */ 00384 std::deque<CMultiMetricMap::TPairIdBeacon> initialBeacons; 00385 00386 /** Customizable initial options. 00387 */ 00388 CLandmarksMap::TInsertionOptions insertionOpts; 00389 00390 /** Customizable initial options. 00391 */ 00392 CLandmarksMap::TLikelihoodOptions likelihoodOpts; 00393 00394 } landmarksMap_options; 00395 00396 00397 /** Especific options for landmarks maps (mrpt::slam::CBeaconMap) 00398 */ 00399 struct MRPTDLLIMPEXP CBeaconMapOptions 00400 { 00401 /** Default values loader 00402 */ 00403 CBeaconMapOptions(); 00404 00405 /** Customizable initial options. 00406 */ 00407 CBeaconMap::TLikelihoodOptions likelihoodOpts; 00408 CBeaconMap::TInsertionOptions insertionOpts; 00409 00410 } beaconMap_options; 00411 00412 /** Especific options for height grid maps (mrpt::slam::CHeightGridMap2D) 00413 */ 00414 struct MRPTDLLIMPEXP CHeightGridMap2DOptions 00415 { 00416 /** Default values loader 00417 */ 00418 CHeightGridMap2DOptions(); 00419 00420 /** See CHeightGridMap2D::CHeightGridMap2D 00421 */ 00422 float min_x,max_x,min_y,max_y,resolution; 00423 00424 /** The kind of map representation (see CHeightGridMap2D::CHeightGridMap2D) 00425 */ 00426 CHeightGridMap2D::TMapRepresentation mapType; 00427 00428 /** Customizable initial options. 00429 */ 00430 CHeightGridMap2D::TInsertionOptions insertionOpts; 00431 00432 } heightMap_options; 00433 00434 /** Especific options for coloured points maps (mrpt::slam::CPointsMap) 00435 */ 00436 struct MRPTDLLIMPEXP CColouredPointsMapOptions 00437 { 00438 /** Default values loader 00439 */ 00440 CColouredPointsMapOptions(); 00441 00442 /** Customizable initial options for loading the class' own defaults. 00443 */ 00444 CPointsMap::TInsertionOptions insertionOpts; 00445 00446 /** Customizable initial options for loading the class' own defaults. */ 00447 CColouredPointsMap::TColourOptions colourOpts; 00448 00449 } colouredPointsMapOptions_options; 00450 00451 }; 00452 00453 /** A set of TMetricMapInitializer structures, passed to the constructor CMultiMetricMap::CMultiMetricMap 00454 * See the comments for TSetOfMetricMapInitializers::loadFromConfigFile, and "CMultiMetricMap::setListOfMaps" for 00455 * effectively creating the list of desired maps. 00456 * \sa CMultiMetricMap::CMultiMetricMap, utils::CLoadableOptions 00457 */ 00458 class MRPTDLLIMPEXP TSetOfMetricMapInitializers : public utils::CLoadableOptions 00459 { 00460 protected: 00461 std::deque<TMetricMapInitializer> m_list; 00462 00463 public: 00464 size_t size() const { return m_list.size(); } 00465 void push_back( const TMetricMapInitializer &o ) { m_list.push_back(o); } 00466 00467 typedef std::deque<TMetricMapInitializer>::iterator iterator; 00468 typedef std::deque<TMetricMapInitializer>::const_iterator const_iterator; 00469 00470 iterator begin() { return m_list.begin(); } 00471 const_iterator begin() const { return m_list.begin(); } 00472 00473 iterator end() { return m_list.end(); } 00474 const_iterator end() const { return m_list.end(); } 00475 00476 void clear() { m_list.clear(); } 00477 00478 00479 TSetOfMetricMapInitializers() : m_list(), options() 00480 {} 00481 00482 00483 /** This options will be loaded when creating the set of maps in CMultiMetricMap (See CMultiMetricMap::TOptions) 00484 */ 00485 CMultiMetricMap::TOptions options; 00486 00487 /** Loads the configuration for the set of internal maps from a textual definition in an INI-like file. 00488 * The format of the ini file is defined in utils::CConfigFile. The list of maps and their options 00489 * will be loaded from a handle of sections: 00490 * 00491 * \code 00492 * [<sectionName>] 00493 * ; Creation of maps: 00494 * occupancyGrid_count=<Number of mrpt::slam::COccupancyGridMap2D maps> 00495 * gasGrid_count=<Number of mrpt::slam::CGasConcentrationGridMap2D maps> 00496 * landmarksMap_count=<0 or 1, for creating a mrpt::slam::CLandmarksMap map> 00497 * beaconMap_count=<0 or 1, for creating a mrpt::slam::CBeaconMap map> 00498 * pointsMap_count=<Number of mrpt::slam::CSimplePointsMap map> 00499 * heightMap_count=<Number of mrpt::slam::CHeightGridMap2D maps> 00500 * colourPointsMap_count=<0 or 1, for creating a mrpt::slam::CColouredPointsMap map> 00501 * 00502 * ; Selection of map for likelihood: (fuseAll=-1, occGrid=0, points=1,landmarks=2,gasGrid=3,4=landmarks SOG, 5=beacon map, 6=height map) 00503 * likelihoodMapSelection=[-1, 6] 00504 * 00505 * ; Enables (1) / Disables (0) insertion into specific maps: 00506 * enableInsertion_pointsMap=<0/1> 00507 * enableInsertion_landmarksMap=<0/1> 00508 * enableInsertion_gridMaps=<0/1> 00509 * enableInsertion_gasGridMaps=<0/1> 00510 * enableInsertion_beaconMap=<0/1> 00511 * enableInsertion_heightMap=<0/1> 00512 * enableInsertion_colourPointsMap=<0/1> 00513 * 00514 * ; Creation Options for OccupancyGridMap ##: 00515 * [<sectionName>+"_occupancyGrid_##_creationOpts"] 00516 * min_x=<value> 00517 * max_x=<value> 00518 * min_y=<value> 00519 * max_y=<value> 00520 * resolution=<value> 00521 * 00522 * ; Insertion Options for OccupancyGridMap ##: 00523 * [<sectionName>+"_occupancyGrid_##_insertOpts"] 00524 * <See COccupancyGridMap2D::TInsertionOptions> 00525 * 00526 * ; Likelihood Options for OccupancyGridMap ##: 00527 * [<sectionName>+"_occupancyGrid_##_likelihoodOpts"] 00528 * <See COccupancyGridMap2D::TLikelihoodOptions> 00529 * 00530 * 00531 * 00532 * ; Insertion Options for CSimplePointsMap ##: 00533 * [<sectionName>+"_pointsMap_##_insertOpts"] 00534 * <See CPointsMap::TInsertionOptions> 00535 * 00536 * 00537 * ; Creation Options for CGasConcentrationGridMap2D ##: 00538 * [<sectionName>+"_gasGrid_##_creationOpts"] 00539 * mapType= <0-1> ; See CGasConcentrationGridMap2D::CGasConcentrationGridMap2D 00540 * min_x=<value> 00541 * max_x=<value> 00542 * min_y=<value> 00543 * max_y=<value> 00544 * resolution=<value> 00545 * 00546 * ; Insertion Options for CGasConcentrationGridMap2D ##: 00547 * [<sectionName>+"_gasGrid_##_insertOpts"] 00548 * <See CGasConcentrationGridMap2D::TInsertionOptions> 00549 * 00550 * 00551 * ; Creation Options for CLandmarksMap ##: 00552 * [<sectionName>+"_landmarksMap_##_creationOpts"] 00553 * nBeacons=<# of beacons> 00554 * beacon_001_ID=67 ; The ID and 3D coordinates of each beacon 00555 * beacon_001_X=<x> 00556 * beacon_001_Y=<x> 00557 * beacon_001_Z=<x> 00558 * 00559 * ; Insertion Options for CLandmarksMap ##: 00560 * [<sectionName>+"_landmarksMap_##_insertOpts"] 00561 * <See CLandmarksMap::TInsertionOptions> 00562 * 00563 * ; Likelihood Options for CLandmarksMap ##: 00564 * [<sectionName>+"_landmarksMap_##_likelihoodOpts"] 00565 * <See CLandmarksMap::TLikelihoodOptions> 00566 * 00567 * 00568 * ; Insertion Options for CBeaconMap ##: 00569 * [<sectionName>+"_beaconMap_##_insertOpts"] 00570 * <See CBeaconMap::TInsertionOptions> 00571 * 00572 * ; Likelihood Options for CBeaconMap ##: 00573 * [<sectionName>+"_beaconMap_##_likelihoodOpts"] 00574 * <See CBeaconMap::TLikelihoodOptions> 00575 * 00576 * ; Creation Options for HeightGridMap ##: 00577 * [<sectionName>+"_heightGrid_##_creationOpts"] 00578 * mapType= <0-1> ; See CHeightGridMap2D::CHeightGridMap2D 00579 * min_x=<value> 00580 * max_x=<value> 00581 * min_y=<value> 00582 * max_y=<value> 00583 * resolution=<value> 00584 * 00585 * ; Insertion Options for HeightGridMap ##: 00586 * [<sectionName>+"_heightGrid_##_insertOpts"] 00587 * <See CHeightGridMap2D::TInsertionOptions> 00588 * 00589 * 00590 * ; Insertion Options for CColouredPointsMap ##: 00591 * [<sectionName>+"_colourPointsMap_##_insertOpts"] 00592 * <See CPointsMap::TInsertionOptions> 00593 * 00594 * 00595 * ; Color Options for CColouredPointsMap ##: 00596 * [<sectionName>+"_colourPointsMap_##_colorOpts"] 00597 * <See CColouredPointsMap::TColourOptions> 00598 * 00599 * 00600 * \endcode 00601 * 00602 * Where: 00603 * - ##: Represents the index of the map (e.g. "00","01",...) 00604 * - By default, the variables into each "TOptions" structure of the maps are defined in textual form by the same name of the corresponding C++ variable (e.g. "float resolution;" -> "resolution=0.10") 00605 */ 00606 void loadFromConfigFile( 00607 const mrpt::utils::CConfigFileBase &source, 00608 const std::string §ionName); 00609 00610 /** This method dumps the options of the multi-metric map AND those of every internal map. 00611 */ 00612 void dumpToTextStream(CStream &out) const; 00613 }; 00614 00615 00616 } // End of namespace 00617 } // End of namespace 00618 00619 #endif
Page generated by Doxygen 1.5.9 for MRPT 0.7.1 SVN: at Mon Aug 17 22:32:05 EDT 2009 |