Main MRPT website > C++ reference
MRPT logo

CMultiMetricMap.h

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



Page generated by Doxygen 1.7.3 for MRPT 0.9.4 SVN: at Sat Mar 26 06:40:17 UTC 2011