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 CBeaconMap_H 00029 #define CBeaconMap_H 00030 00031 #include <mrpt/slam/CMetricMap.h> 00032 #include <mrpt/slam/CBeacon.h> 00033 #include <mrpt/utils/CSerializable.h> 00034 #include <mrpt/math/CMatrix.h> 00035 #include <mrpt/utils/CDynamicGrid.h> 00036 #include <mrpt/utils/CLoadableOptions.h> 00037 00038 namespace mrpt 00039 { 00040 namespace slam 00041 { 00042 using namespace mrpt::utils; 00043 using namespace mrpt::math; 00044 00045 class CObservationBeaconRanges; 00046 00047 00048 DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE( CBeaconMap, CMetricMap ) 00049 00050 /** A class for storing a map of 3D probabilistic beacons, using a Montecarlo, Gaussian, or Sum of Gaussians (SOG) representation (for range-only SLAM). 00051 * <br> 00052 * The individual beacons are defined as mrpt::slam::CBeacon objects. 00053 * <br> 00054 * When invoking CBeaconMap::insertObservation(), landmarks will be extracted and fused into the map. 00055 * The only currently supported observation type is mrpt::slam::CObservationBeaconRanges. 00056 * See insertionOptions and likelihoodOptions for parameters used when creating and fusing beacon landmarks. 00057 * <br> 00058 * Use "TInsertionOptions::insertAsMonteCarlo" to select between 2 different behaviors: 00059 * - Initial PDF of beacons: MonteCarlo, after convergence, pass to Gaussians; or 00060 * - Initial PDF of beacons: SOG, after convergence, a single Gaussian. 00061 * 00062 * Refer to the papers: [] 00063 * 00064 * \sa CMetricMap 00065 */ 00066 class MRPTDLLIMPEXP CBeaconMap : public CMetricMap 00067 { 00068 // This must be added to any CSerializable derived class: 00069 DEFINE_SERIALIZABLE( CBeaconMap ) 00070 00071 public: 00072 typedef std::deque<CBeacon> TSequenceBeacons; 00073 typedef std::deque<CBeacon>::iterator iterator; 00074 typedef std::deque<CBeacon>::const_iterator const_iterator; 00075 00076 protected: 00077 /** The individual beacons */ 00078 TSequenceBeacons m_beacons; 00079 public: 00080 /** Constructor */ 00081 CBeaconMap(); 00082 00083 void resize(const size_t N); //!< Resize the number of SOG modes 00084 00085 /** Access to individual beacons */ 00086 const CBeacon& operator [](size_t i) const { 00087 ASSERT_(i<m_beacons.size()) 00088 return m_beacons[i]; 00089 } 00090 /** Access to individual beacons */ 00091 const CBeacon& get(size_t i) const{ 00092 ASSERT_(i<m_beacons.size()) 00093 return m_beacons[i]; 00094 } 00095 /** Access to individual beacons */ 00096 CBeacon& operator [](size_t i) { 00097 ASSERT_(i<m_beacons.size()) 00098 return m_beacons[i]; 00099 } 00100 /** Access to individual beacons */ 00101 CBeacon& get(size_t i) { 00102 ASSERT_(i<m_beacons.size()) 00103 return m_beacons[i]; 00104 } 00105 00106 iterator begin() { return m_beacons.begin(); } 00107 const_iterator begin() const { return m_beacons.begin(); } 00108 iterator end() { return m_beacons.end(); } 00109 const_iterator end() const { return m_beacons.end(); } 00110 00111 /** Inserts a copy of the given mode into the SOG */ 00112 void push_back(const CBeacon& m) { 00113 m_beacons.push_back( m ); 00114 } 00115 00116 /** Computes the ratio in [0,1] of correspondences between "this" and the "otherMap" map, whose 6D pose relative to "this" is "otherMapPose" 00117 * In the case of a multi-metric map, this returns the average between the maps. This method always return 0 for grid maps. 00118 * \param otherMap [IN] The other map to compute the matching with. 00119 * \param otherMapPose [IN] The 6D pose of the other map as seen from "this". 00120 * \param minDistForCorr [IN] The minimum distance between 2 non-probabilistic map elements for counting them as a correspondence. 00121 * \param minMahaDistForCorr [IN] The minimum Mahalanobis distance between 2 probabilistic map elements for counting them as a correspondence. 00122 * 00123 * \return The matching ratio [0,1] 00124 * \sa computeMatchingWith2D 00125 */ 00126 float compute3DMatchingRatio( 00127 const CMetricMap *otherMap, 00128 const CPose3D &otherMapPose, 00129 float minDistForCorr = 0.10f, 00130 float minMahaDistForCorr = 2.0f 00131 ) const; 00132 00133 /** With this struct options are provided to the likelihood computations. 00134 */ 00135 struct MRPTDLLIMPEXP TLikelihoodOptions : public utils::CLoadableOptions 00136 { 00137 public: 00138 /** Initilization of default parameters 00139 */ 00140 TLikelihoodOptions(); 00141 00142 /** See utils::CLoadableOptions 00143 */ 00144 void loadFromConfigFile( 00145 const mrpt::utils::CConfigFileBase &source, 00146 const std::string §ion); 00147 00148 /** See utils::CLoadableOptions 00149 */ 00150 void dumpToTextStream(CStream &out) const; 00151 00152 /** The standard deviation used for Beacon ranges likelihood (default=0.08m). 00153 */ 00154 float rangeStd; 00155 00156 } likelihoodOptions; 00157 00158 /** This struct contains data for choosing the method by which new beacons are inserted in the map. 00159 */ 00160 struct MRPTDLLIMPEXP TInsertionOptions : public utils::CLoadableOptions 00161 { 00162 public: 00163 /** Initilization of default parameters 00164 */ 00165 TInsertionOptions(); 00166 00167 /** See utils::CLoadableOptions 00168 */ 00169 void loadFromConfigFile( 00170 const mrpt::utils::CConfigFileBase &source, 00171 const std::string §ion); 00172 00173 /** See utils::CLoadableOptions 00174 */ 00175 void dumpToTextStream(CStream &out) const; 00176 00177 /** Insert a new beacon as a set of montecarlo samples (default=true), or, if false, as a sum of gaussians (see mrpt::slam::CBeacon). 00178 * \sa MC_performResampling 00179 */ 00180 bool insertAsMonteCarlo; 00181 00182 /** Minimum and maximum elevation angles (in degrees) for inserting new beacons at the first observation: the default values (both 0), makes the beacons to be in the same horizontal plane that the sensors, that is, 2D SLAM - the min/max values are -90/90. 00183 */ 00184 float maxElevation_deg,minElevation_deg; 00185 00186 /** Number of particles per meter of range, i.e. per meter of the "radius of the ring". 00187 */ 00188 unsigned int MC_numSamplesPerMeter; 00189 00190 /** The threshold for the maximum std (X,Y,and Z) before colapsing the particles into a Gaussian PDF (default=0,4). 00191 */ 00192 float MC_maxStdToGauss; 00193 00194 /** Threshold for the maximum difference from the maximun (log) weight in the set of samples for erasing a given sample (default=5). 00195 */ 00196 float MC_thresholdNegligible; 00197 00198 /** If set to false (default), the samples will be generated the first time a beacon is observed, and their weights just updated subsequently - if set to "true", fewer samples will be required since the particles will be resamples when necessary, and a small "noise" will be added to avoid depletion. 00199 */ 00200 bool MC_performResampling; 00201 00202 /** The std.dev. of the Gaussian noise to be added to each sample after resampling, only if MC_performResampling=true. 00203 */ 00204 float MC_afterResamplingNoise; 00205 00206 /** Threshold for the maximum difference from the maximun (log) weight in the SOG for erasing a given mode (default=20). 00207 */ 00208 float SOG_thresholdNegligible; 00209 00210 /** A parameter for initializing 2D/3D SOGs 00211 */ 00212 float SOG_maxDistBetweenGaussians; 00213 00214 /** Constant used to compute the std. dev. int the tangent direction when creating the Gaussians. 00215 */ 00216 float SOG_separationConstant; 00217 00218 } insertionOptions; 00219 00220 /** Save to a MATLAB script which displays 3D error ellipses for the map. 00221 * \param file The name of the file to save the script to. 00222 * \param style The MATLAB-like string for the style of the lines (see 'help plot' in MATLAB for posibilities) 00223 * \param stdCount The ellipsoids will be drawn from the center to a given confidence interval in [0,1], e.g. 2 sigmas=0.95 (default is 2std = 0.95 confidence intervals) 00224 * 00225 * \return Returns false if any error occured, true elsewere. 00226 */ 00227 bool saveToMATLABScript3D( 00228 std::string file, 00229 const char *style="b", 00230 float confInterval = 0.95f ) const; 00231 00232 /** Clear the map, erasing all landmarks. 00233 */ 00234 void clear(); 00235 00236 /** Returns the stored landmarks count. 00237 */ 00238 size_t size() const; 00239 00240 /** Insert the observation information into this map. This method must be implemented 00241 * in derived classes. 00242 * \param obs The observation 00243 * \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) 00244 * 00245 * \sa CObservation::insertObservationInto 00246 */ 00247 bool insertObservation( const CObservation *obs, const CPose3D *robotPose = NULL ); 00248 00249 /** Computes the (logarithmic) likelihood that a given observation was taken from a given pose in the world being modeled with this map. 00250 * 00251 * In the current implementation, this method behaves in a different way according to the nature of 00252 * the observation's class: 00253 * - "mrpt::slam::CObservation2DRangeScan": This calls "computeLikelihood_RSLC_2007". 00254 * - "mrpt::slam::CObservationStereoImages": This calls "computeLikelihood_SIFT_LandmarkMap". 00255 * 00256 * \param takenFrom The robot's pose the observation is supposed to be taken from. 00257 * \param obs The observation. 00258 * \return This method returns a likelihood value > 0. 00259 * 00260 * \sa Used in particle filter algorithms, see: CMultiMetricMapPDF::update 00261 */ 00262 double computeObservationLikelihood( const CObservation *obs, const CPose3D &takenFrom ); 00263 00264 /** Computes the matchings between this and another 2D points map. 00265 This includes finding: 00266 - The set of points pairs in each map 00267 - The mean squared distance between corresponding pairs. 00268 This method is the most time critical one into the ICP algorithm. 00269 00270 * \param otherMap [IN] The other map to compute the matching with. 00271 * \param otherMapPose [IN] The pose of the other map as seen from "this". 00272 * \param maxDistForCorrespondence [IN] Maximum 2D linear distance between two points to be matched. 00273 * \param maxAngularDistForCorrespondence [IN] In radians: The aim is to allow larger distances to more distant correspondences. 00274 * \param angularDistPivotPoint [IN] The point used to calculate distances from in both maps. 00275 * \param correspondences [OUT] The detected matchings pairs. 00276 * \param correspondencesRatio [OUT] The ratio [0,1] of points in otherMap with at least one correspondence. 00277 * \param sumSqrDist [OUT] The sum of all matched points squared distances.If undesired, set to NULL, as default. 00278 * \param covariance [OUT] The resulting matching covariance 3x3 matrix, or NULL if undesired. 00279 * \param onlyKeepTheClosest [IN] If set to true, only the closest correspondence will be returned. If false (default) all are returned. 00280 * 00281 * \sa compute3DMatchingRatio 00282 */ 00283 void computeMatchingWith2D( 00284 const CMetricMap *otherMap, 00285 const CPose2D &otherMapPose, 00286 float maxDistForCorrespondence, 00287 float maxAngularDistForCorrespondence, 00288 const CPose2D &angularDistPivotPoint, 00289 TMatchingPairList &correspondences, 00290 float &correspondencesRatio, 00291 float *sumSqrDist = NULL, 00292 bool onlyKeepTheClosest = false, 00293 bool onlyUniqueRobust = false ) const; 00294 00295 /** Perform a search for correspondences between "this" and another lansmarks map: 00296 * Firsly, the landmarks' descriptor is used to find correspondences, then inconsistent ones removed by 00297 * looking at their 3D poses. 00298 * \param otherMap [IN] The other map. 00299 * \param correspondences [OUT] The matched pairs between maps. 00300 * \param correspondencesRatio [OUT] This is NumberOfMatchings / NumberOfLandmarksInTheAnotherMap 00301 * \param otherCorrespondences [OUT] Will be returned with a vector containing "true" for the indexes of the other map's landmarks with a correspondence. 00302 */ 00303 void computeMatchingWith3DLandmarks( 00304 const mrpt::slam::CBeaconMap *otherMap, 00305 TMatchingPairList &correspondences, 00306 float &correspondencesRatio, 00307 std::vector<bool> &otherCorrespondences) const; 00308 00309 /** Changes the reference system of the map to a given 3D pose. 00310 */ 00311 void changeCoordinatesReference( const CPose3D &newOrg ); 00312 00313 /** Changes the reference system of the map "otherMap" and save the result in "this" map. 00314 */ 00315 void changeCoordinatesReference( const CPose3D &newOrg, const mrpt::slam::CBeaconMap *otherMap ); 00316 00317 00318 /** Returns true if the map is empty/no observation has been inserted. 00319 */ 00320 bool isEmpty() const; 00321 00322 /** Simulates a reading toward each of the beacons in the landmarks map, if any. 00323 * \param in_robotPose This robot pose is used to simulate the ranges to each beacon. 00324 * \param in_sensorLocationOnRobot The 3D position of the sensor on the robot 00325 * \param out_Observations The results will be stored here. NOTICE that the fields "CObservationBeaconRanges::minSensorDistance","CObservationBeaconRanges::maxSensorDistance" and "CObservationBeaconRanges::stdError" MUST BE FILLED OUT before calling this function. 00326 * An observation will be generated for each beacon in the map, but notice that some of them may be missed if out of the sensor maximum range. 00327 */ 00328 void simulateBeaconReadings( 00329 const CPose3D &in_robotPose, 00330 const CPoint3D &in_sensorLocationOnRobot, 00331 CObservationBeaconRanges &out_Observations ) const; 00332 00333 /** This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >, as an image or in any other applicable way (Notice that other methods to save the map may be implemented in classes implementing this virtual interface). 00334 * In the case of this class, these files are generated: 00335 * - "filNamePrefix"+"_3D.m": A script for MATLAB for drawing landmarks as 3D ellipses. 00336 * - "filNamePrefix"+"_3D.3DScene": A 3D scene with a "ground plane grid" and the set of ellipsoids in 3D. 00337 * - "filNamePrefix"+"_covs.m": A textual representation (see saveToTextFile) 00338 */ 00339 void saveMetricMapRepresentationToFile( 00340 const std::string &filNamePrefix ) const; 00341 00342 /** Save a text file with a row per beacon, containing this 11 elements: 00343 * - X Y Z: Mean values 00344 * - VX VY VZ: Variances of each dimension (C11, C22, C33) 00345 * - DET2D DET3D: Determinant of the 2D and 3D covariance matrixes. 00346 * - C12, C13, C23: Cross covariances 00347 */ 00348 void saveToTextFile(const std::string &fil) const; 00349 00350 /** Returns a 3D object representing the map. 00351 */ 00352 void getAs3DObject ( mrpt::opengl::CSetOfObjectsPtr &outObj ) const; 00353 00354 /** This method is called at the end of each "prediction-update-map insertion" cycle within "mrpt::slam::CMetricMapBuilderRBPF::processActionObservation". 00355 * This method should normally do nothing, but in some cases can be used to free auxiliary cached variables. 00356 */ 00357 void auxParticleFilterCleanUp(); 00358 00359 /** Returns a pointer to the beacon with the given ID, or NULL if it does not exist. 00360 */ 00361 const CBeacon * getBeaconByID( CBeacon::TBeaconID id ) const; 00362 00363 /** Returns a pointer to the beacon with the given ID, or NULL if it does not exist. 00364 */ 00365 CBeacon * getBeaconByID( CBeacon::TBeaconID id ); 00366 00367 }; // End of class def. 00368 00369 00370 } // End of namespace 00371 } // End of namespace 00372 00373 #endif
Page generated by Doxygen 1.5.9 for MRPT 0.7.1 SVN: at Mon Aug 17 22:21:34 EDT 2009 |