00001 /* +---------------------------------------------------------------------------+ 00002 | The Mobile Robot Programming Toolkit (MRPT) C++ library | 00003 | | 00004 | http://www.mrpt.org/ | 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 CPOINTSMAP_H 00029 #define CPOINTSMAP_H 00030 00031 #include <mrpt/slam/CMetricMap.h> 00032 #include <mrpt/utils/CSerializable.h> 00033 #include <mrpt/math/CMatrix.h> 00034 #include <mrpt/utils/CLoadableOptions.h> 00035 #include <mrpt/utils/safe_pointers.h> 00036 #include <mrpt/math/KDTreeCapable.h> 00037 #include <mrpt/slam/CSinCosLookUpTableFor2DScans.h> 00038 #include <mrpt/poses/CPoint2D.h> 00039 #include <mrpt/math/lightweight_geom_data.h> 00040 #include <mrpt/utils/PLY_import_export.h> 00041 00042 #include <mrpt/maps/link_pragmas.h> 00043 #include <mrpt/utils/adapters.h> 00044 00045 namespace mrpt 00046 { 00047 /** \ingroup mrpt_maps_grp */ 00048 namespace slam 00049 { 00050 // Fordward declarations: 00051 class CSimplePointsMap; 00052 class CObservation2DRangeScan; 00053 class CObservation3DRangeScan; 00054 00055 using namespace mrpt::poses; 00056 using namespace mrpt::math; 00057 00058 DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE( CPointsMap , CMetricMap, MAPS_IMPEXP ) 00059 00060 // Forward decls. needed to make its static methods friends of CPointsMap 00061 namespace detail { 00062 template <class Derived> struct loadFromRangeImpl; 00063 template <class Derived> struct pointmap_traits; 00064 } 00065 00066 00067 /** A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors. 00068 * This is a virtual class, thus only a derived class can be instantiated by the user. The user most usually wants to use CSimplePointsMap. 00069 * 00070 * This class implements generic version of mrpt::slam::CMetric::insertObservation() accepting these types of sensory data: 00071 * - mrpt::slam::CObservation2DRangeScan: 2D range scans 00072 * - mrpt::slam::CObservation3DRangeScan: 3D range scans (Kinect, etc...) 00073 * - mrpt::slam::CObservationRange: IRs, Sonars, etc. 00074 * 00075 * \sa CMetricMap, CPoint, mrpt::utils::CSerializable 00076 * \ingroup mrpt_maps_grp 00077 */ 00078 class MAPS_IMPEXP CPointsMap : 00079 public CMetricMap, 00080 public mrpt::utils::KDTreeCapable<CPointsMap>, 00081 public mrpt::utils::PLY_Importer, 00082 public mrpt::utils::PLY_Exporter 00083 { 00084 // This must be added to any CSerializable derived class: 00085 DEFINE_VIRTUAL_SERIALIZABLE( CPointsMap ) 00086 00087 protected: 00088 /** Helper struct used for \a internal_loadFromRangeScan2D_prepareOneRange() */ 00089 struct MAPS_IMPEXP TLaserRange2DInsertContext { 00090 TLaserRange2DInsertContext(const CObservation2DRangeScan &_rangeScan) : HM(UNINITIALIZED_MATRIX), rangeScan(_rangeScan) 00091 { } 00092 CMatrixDouble44 HM; //!< Homog matrix of the local sensor pose within the robot 00093 const CObservation2DRangeScan &rangeScan; 00094 std::vector<float> fVars; //!< Extra variables to be used as desired by the derived class. 00095 std::vector<unsigned int> uVars; 00096 std::vector<uint8_t> bVars; 00097 }; 00098 00099 /** Helper struct used for \a internal_loadFromRangeScan3D_prepareOneRange() */ 00100 struct MAPS_IMPEXP TLaserRange3DInsertContext { 00101 TLaserRange3DInsertContext(const CObservation3DRangeScan &_rangeScan) : HM(UNINITIALIZED_MATRIX), rangeScan(_rangeScan) 00102 { } 00103 CMatrixDouble44 HM; //!< Homog matrix of the local sensor pose within the robot 00104 const CObservation3DRangeScan &rangeScan; 00105 float scan_x, scan_y,scan_z; //!< In \a internal_loadFromRangeScan3D_prepareOneRange, these are the local coordinates of the scan points being inserted right now. 00106 std::vector<float> fVars; //!< Extra variables to be used as desired by the derived class. 00107 std::vector<unsigned int> uVars; 00108 std::vector<uint8_t> bVars; 00109 }; 00110 00111 public: 00112 CPointsMap(); //!< Ctor 00113 virtual ~CPointsMap(); //!< Virtual destructor. 00114 00115 00116 // -------------------------------------------- 00117 /** @name Pure virtual interfaces to be implemented by any class derived from CPointsMap 00118 @{ */ 00119 00120 /** Reserves memory for a given number of points: the size of the map does not change, it only reserves the memory. 00121 * This is useful for situations where it is approximately known the final size of the map. This method is more 00122 * efficient than constantly increasing the size of the buffers. Refer to the STL C++ library's "reserve" methods. 00123 */ 00124 virtual void reserve(size_t newLength) = 0; 00125 00126 /** Resizes all point buffers so they can hold the given number of points: newly created points are set to default values, 00127 * and old contents are not changed. 00128 * \sa reserve, setPoint, setPointFast, setSize 00129 */ 00130 virtual void resize(size_t newLength) = 0; 00131 00132 /** Resizes all point buffers so they can hold the given number of points, *erasing* all previous contents 00133 * and leaving all points to default values. 00134 * \sa reserve, setPoint, setPointFast, setSize 00135 */ 00136 virtual void setSize(size_t newLength) = 0; 00137 00138 /** Changes the coordinates of the given point (0-based index), *without* checking for out-of-bounds and *without* calling mark_as_modified() \sa setPoint */ 00139 virtual void setPointFast(size_t index,float x, float y, float z)=0; 00140 00141 /** The virtual method for \a insertPoint() *without* calling mark_as_modified() */ 00142 virtual void insertPointFast( float x, float y, float z = 0 ) = 0; 00143 00144 /** Virtual assignment operator, copies as much common data (XYZ, color,...) as possible from the source map into this one. */ 00145 virtual void copyFrom(const CPointsMap &obj) = 0; 00146 00147 /** Get all the data fields for one point as a vector: depending on the implementation class this can be [X Y Z] or [X Y Z R G B], etc... 00148 * Unlike getPointAllFields(), this method does not check for index out of bounds 00149 * \sa getPointAllFields, setPointAllFields, setPointAllFieldsFast 00150 */ 00151 virtual void getPointAllFieldsFast( const size_t index, std::vector<float> & point_data ) const = 0; 00152 00153 /** Set all the data fields for one point as a vector: depending on the implementation class this can be [X Y Z] or [X Y Z R G B], etc... 00154 * Unlike setPointAllFields(), this method does not check for index out of bounds 00155 * \sa setPointAllFields, getPointAllFields, getPointAllFieldsFast 00156 */ 00157 virtual void setPointAllFieldsFast( const size_t index, const std::vector<float> & point_data ) = 0; 00158 00159 protected: 00160 00161 /** Auxiliary method called from within \a addFrom() automatically, to finish the copying of class-specific data */ 00162 virtual void addFrom_classSpecific(const CPointsMap &anotherMap, const size_t nPreviousPoints) = 0; 00163 00164 public: 00165 00166 /** @} */ 00167 // -------------------------------------------- 00168 00169 00170 /** Returns the square distance from the 2D point (x0,y0) to the closest correspondence in the map. 00171 */ 00172 virtual float squareDistanceToClosestCorrespondence( 00173 float x0, 00174 float y0 ) const; 00175 00176 inline float squareDistanceToClosestCorrespondenceT(const TPoint2D &p0) const { 00177 return squareDistanceToClosestCorrespondence(static_cast<float>(p0.x),static_cast<float>(p0.y)); 00178 } 00179 00180 00181 /** With this struct options are provided to the observation insertion process. 00182 * \sa CObservation::insertIntoPointsMap 00183 */ 00184 struct MAPS_IMPEXP TInsertionOptions : public utils::CLoadableOptions 00185 { 00186 /** Initilization of default parameters */ 00187 TInsertionOptions( ); 00188 /** See utils::CLoadableOptions */ 00189 void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source,const std::string §ion); 00190 /** See utils::CLoadableOptions */ 00191 void dumpToTextStream(CStream &out) const; 00192 00193 float minDistBetweenLaserPoints; //!< The minimum distance between points (in 3D): If two points are too close, one of them is not inserted into the map. Default is 0.02 meters. 00194 bool addToExistingPointsMap; //!< Applicable to "loadFromRangeScan" only! If set to false, the points from the scan are loaded, clearing all previous content. Default is false. 00195 bool also_interpolate; //!< If set to true, far points (<1m) are interpolated with samples at "minDistSqrBetweenLaserPoints" intervals (Default is false). 00196 bool disableDeletion; //!< If set to false (default=true) points in the same plane as the inserted scan and inside the free space, are erased: i.e. they don't exist yet. 00197 bool fuseWithExisting; //!< If set to true (default=false), inserted points are "fused" with previously existent ones. This shrink the size of the points map, but its slower. 00198 bool isPlanarMap; //!< If set to true, only HORIZONTAL (in the XY plane) measurements will be inserted in the map (Default value is false, thus 3D maps are generated). \sa horizontalTolerance 00199 float horizontalTolerance; //!< The tolerance in rads in pitch & roll for a laser scan to be considered horizontal, considered only when isPlanarMap=true (default=0). 00200 float maxDistForInterpolatePoints; //!< The maximum distance between two points to interpolate between them (ONLY when also_interpolate=true) 00201 00202 }; 00203 00204 TInsertionOptions insertionOptions; //!< The options used when inserting observations in the map 00205 00206 /** Options used when evaluating "computeObservationLikelihood" in the derived classes. 00207 * \sa CObservation::computeObservationLikelihood 00208 */ 00209 struct MAPS_IMPEXP TLikelihoodOptions: public utils::CLoadableOptions 00210 { 00211 /** Initilization of default parameters 00212 */ 00213 TLikelihoodOptions( ); 00214 virtual ~TLikelihoodOptions() {} 00215 00216 /** See utils::CLoadableOptions */ 00217 void loadFromConfigFile( 00218 const mrpt::utils::CConfigFileBase &source, 00219 const std::string §ion); 00220 00221 /** See utils::CLoadableOptions */ 00222 void dumpToTextStream(CStream &out) const; 00223 00224 void writeToStream(CStream &out) const; //!< Binary dump to stream - for usage in derived classes' serialization 00225 void readFromStream(CStream &in); //!< Binary dump to stream - for usage in derived classes' serialization 00226 00227 double sigma_dist; //!< Sigma (standard deviation, in meters) of the exponential used to model the likelihood (default= 0.5meters) 00228 double max_corr_distance; //!< Maximum distance in meters to consider for the numerator divided by "sigma_dist", so that each point has a minimum (but very small) likelihood to avoid underflows (default=1.0 meters) 00229 uint32_t decimation; //!< Speed up the likelihood computation by considering only one out of N rays (default=10) 00230 }; 00231 00232 TLikelihoodOptions likelihoodOptions; 00233 00234 00235 /** Adds all the points from \a anotherMap to this map, without fusing. 00236 * This operation can be also invoked via the "+=" operator, for example: 00237 * \code 00238 * CSimplePointsMap m1, m2; 00239 * ... 00240 * m1.addFrom( m2 ); // Add all points of m2 to m1 00241 * m1 += m2; // Exactly the same than above 00242 * \endcode 00243 * \note The method in CPointsMap is generic but derived classes may redefine this virtual method to another one more optimized. 00244 */ 00245 virtual void addFrom(const CPointsMap &anotherMap); 00246 00247 /** This operator is synonymous with \a addFrom. \sa addFrom */ 00248 inline void operator +=(const CPointsMap &anotherMap) 00249 { 00250 this->addFrom(anotherMap); 00251 } 00252 00253 /** Insert the contents of another map into this one with some geometric transformation, without fusing close points. 00254 * \param otherMap The other map whose points are to be inserted into this one. 00255 * \param otherPose The pose of the other map in the coordinates of THIS map 00256 * \sa fuseWith, addFrom 00257 */ 00258 void insertAnotherMap( 00259 const CPointsMap *otherMap, 00260 const CPose3D &otherPose); 00261 00262 // -------------------------------------------------- 00263 /** @name File input/output methods 00264 @{ */ 00265 00266 /** Load from a text file. Each line should contain an "X Y" coordinate pair, separated by whitespaces. 00267 * Returns false if any error occured, true elsewere. 00268 */ 00269 inline bool load2D_from_text_file(const std::string &file) { return load2Dor3D_from_text_file(file,false); } 00270 00271 /** Load from a text file. Each line should contain an "X Y Z" coordinate tuple, separated by whitespaces. 00272 * Returns false if any error occured, true elsewere. 00273 */ 00274 inline bool load3D_from_text_file(const std::string &file) { return load2Dor3D_from_text_file(file,true); } 00275 00276 /** 2D or 3D generic implementation of \a load2D_from_text_file and load3D_from_text_file */ 00277 bool load2Dor3D_from_text_file(const std::string &file, const bool is_3D); 00278 00279 /** Save to a text file. Each line will contain "X Y" point coordinates. 00280 * Returns false if any error occured, true elsewere. 00281 */ 00282 bool save2D_to_text_file(const std::string &file) const; 00283 00284 /** Save to a text file. Each line will contain "X Y Z" point coordinates. 00285 * Returns false if any error occured, true elsewere. 00286 */ 00287 bool save3D_to_text_file(const std::string &file)const; 00288 00289 /** 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). 00290 */ 00291 void saveMetricMapRepresentationToFile( 00292 const std::string &filNamePrefix 00293 )const 00294 { 00295 std::string fil( filNamePrefix + std::string(".txt") ); 00296 save3D_to_text_file( fil ); 00297 } 00298 00299 /** Save the point cloud as a PCL PCD file, in either ASCII or binary format (requires MRPT built against PCL) \return false on any error */ 00300 virtual bool savePCDFile(const std::string &filename, bool save_as_binary) const; 00301 00302 /** @} */ // End of: File input/output methods 00303 // -------------------------------------------------- 00304 00305 /** Returns the number of stored points in the map. 00306 */ 00307 inline size_t size() const { return x.size(); } 00308 00309 /** Returns the number of stored points in the map (DEPRECATED, use "size()" instead better) 00310 */ 00311 inline size_t getPointsCount() const { return size(); } 00312 00313 /** Access to a given point from map, as a 2D point. First index is 0. 00314 * \return The return value is the weight of the point (the times it has been fused), or 1 if weights are not used. 00315 * \exception Throws std::exception on index out of bound. 00316 * \sa setPoint, getPointFast 00317 */ 00318 unsigned long getPoint(size_t index,float &x,float &y,float &z) const; 00319 /// \overload 00320 unsigned long getPoint(size_t index,float &x,float &y) const; 00321 /// \overload 00322 unsigned long getPoint(size_t index,double &x,double &y,double &z) const; 00323 /// \overload 00324 unsigned long getPoint(size_t index,double &x,double &y) const; 00325 /// \overload 00326 inline unsigned long getPoint(size_t index,CPoint2D &p) const { return getPoint(index,p.x(),p.y()); } 00327 /// \overload 00328 inline unsigned long getPoint(size_t index,CPoint3D &p) const { return getPoint(index,p.x(),p.y(),p.z()); } 00329 /// \overload 00330 inline unsigned long getPoint(size_t index,mrpt::math::TPoint2D &p) const { return getPoint(index,p.x,p.y); } 00331 /// \overload 00332 inline unsigned long getPoint(size_t index,mrpt::math::TPoint3D &p) const { return getPoint(index,p.x,p.y,p.z); } 00333 00334 /** Access to a given point from map, and its colors, if the map defines them (othersise, R=G=B=1.0). First index is 0. 00335 * \return The return value is the weight of the point (the times it has been fused) 00336 * \exception Throws std::exception on index out of bound. 00337 */ 00338 virtual void getPoint( size_t index, float &x, float &y, float &z, float &R, float &G, float &B ) const 00339 { 00340 getPoint(index,x,y,z); 00341 R=G=B=1; 00342 } 00343 00344 /** Just like \a getPoint() but without checking out-of-bound index and without returning the point weight, just XYZ. 00345 */ 00346 inline void getPointFast(size_t index,float &x,float &y,float &z) const { x=this->x[index]; y=this->y[index]; z=this->z[index]; } 00347 00348 /** Returns true if the point map has a color field for each point */ 00349 virtual bool hasColorPoints() const { return false; } 00350 00351 /** Changes a given point from map, with Z defaulting to 0 if not provided. 00352 * \exception Throws std::exception on index out of bound. 00353 */ 00354 inline void setPoint(size_t index,float x, float y, float z) { 00355 ASSERT_BELOW_(index,this->size()) 00356 setPointFast(index,x,y,z); 00357 mark_as_modified(); 00358 } 00359 /// \overload 00360 inline void setPoint(size_t index,CPoint2D &p) { setPoint(index,p.x(),p.y(),0); } 00361 /// \overload 00362 inline void setPoint(size_t index,CPoint3D &p) { setPoint(index,p.x(),p.y(),p.z()); } 00363 /// \overload 00364 inline void setPoint(size_t index,float x, float y) { setPoint(index,x,y,0); } 00365 /// \overload (RGB data is ignored in classes without color information) 00366 virtual void setPoint(size_t index,float x, float y, float z, float R, float G, float B) { setPoint(index,x,y,z); } 00367 00368 /// Sets the point weight, which is ignored in all classes but those which actually store that field (Note: No checks are done for out-of-bounds index). \sa getPointWeight 00369 virtual void setPointWeight(size_t index,unsigned long w) { } 00370 /// Gets the point weight, which is ignored in all classes (defaults to 1) but in those which actually store that field (Note: No checks are done for out-of-bounds index). \sa setPointWeight 00371 virtual unsigned int getPointWeight(size_t index) const { return 1; } 00372 00373 00374 /** Provides a direct access to points buffer, or NULL if there is no points in the map. 00375 */ 00376 void getPointsBuffer( size_t &outPointsCount, const float *&xs, const float *&ys, const float *&zs ) const; 00377 00378 /** Provides a direct access to a read-only reference of the internal point buffer. \sa getAllPoints */ 00379 inline const std::vector<float> & getPointsBufferRef_x() const { return x; } 00380 /** Provides a direct access to a read-only reference of the internal point buffer. \sa getAllPoints */ 00381 inline const std::vector<float> & getPointsBufferRef_y() const { return y; } 00382 /** Provides a direct access to a read-only reference of the internal point buffer. \sa getAllPoints */ 00383 inline const std::vector<float> & getPointsBufferRef_z() const { return z; } 00384 00385 /** Returns a copy of the 2D/3D points as a std::vector of float coordinates. 00386 * If decimation is greater than 1, only 1 point out of that number will be saved in the output, effectively performing a subsampling of the points. 00387 * \sa getPointsBufferRef_x, getPointsBufferRef_y, getPointsBufferRef_z 00388 * \tparam VECTOR can be std::vector<float or double> or any row/column Eigen::Array or Eigen::Matrix (this includes mrpt::vector_float and mrpt::vector_double). 00389 */ 00390 template <class VECTOR> 00391 void getAllPoints( VECTOR &xs, VECTOR &ys, VECTOR &zs, size_t decimation = 1 ) const 00392 { 00393 MRPT_START 00394 ASSERT_(decimation>0) 00395 const size_t Nout = x.size() / decimation; 00396 xs.resize(Nout); 00397 ys.resize(Nout); 00398 zs.resize(Nout); 00399 size_t idx_in, idx_out; 00400 for (idx_in=0,idx_out=0;idx_out<Nout;idx_in+=decimation,++idx_out) 00401 { 00402 xs[idx_out]=x[idx_in]; 00403 ys[idx_out]=y[idx_in]; 00404 zs[idx_out]=z[idx_in]; 00405 } 00406 MRPT_END 00407 } 00408 00409 inline void getAllPoints(std::vector<TPoint3D> &ps,size_t decimation=1) const { 00410 std::vector<float> dmy1,dmy2,dmy3; 00411 getAllPoints(dmy1,dmy2,dmy3,decimation); 00412 ps.resize(dmy1.size()); 00413 for (size_t i=0;i<dmy1.size();i++) { 00414 ps[i].x=static_cast<double>(dmy1[i]); 00415 ps[i].y=static_cast<double>(dmy2[i]); 00416 ps[i].z=static_cast<double>(dmy3[i]); 00417 } 00418 } 00419 00420 /** Returns a copy of the 2D/3D points as a std::vector of float coordinates. 00421 * If decimation is greater than 1, only 1 point out of that number will be saved in the output, effectively performing a subsampling of the points. 00422 * \sa setAllPoints 00423 */ 00424 void getAllPoints( std::vector<float> &xs, std::vector<float> &ys, size_t decimation = 1 ) const; 00425 00426 inline void getAllPoints(std::vector<TPoint2D> &ps,size_t decimation=1) const { 00427 std::vector<float> dmy1,dmy2; 00428 getAllPoints(dmy1,dmy2,decimation); 00429 ps.resize(dmy1.size()); 00430 for (size_t i=0;i<dmy1.size();i++) { 00431 ps[i].x=static_cast<double>(dmy1[i]); 00432 ps[i].y=static_cast<double>(dmy2[i]); 00433 } 00434 } 00435 00436 /** Provides a way to insert (append) individual points into the map: the missing fields of child 00437 * classes (color, weight, etc) are left to their default values 00438 */ 00439 inline void insertPoint( float x, float y, float z=0 ) { insertPointFast(x,y,z); mark_as_modified(); } 00440 /// \overload of \a insertPoint() 00441 inline void insertPoint( const CPoint3D &p ) { insertPoint(p.x(),p.y(),p.z()); } 00442 /// \overload 00443 inline void insertPoint( const mrpt::math::TPoint3D &p ) { insertPoint(p.x,p.y,p.z); } 00444 /// \overload (RGB data is ignored in classes without color information) 00445 virtual void insertPoint( float x, float y, float z, float R, float G, float B ) { insertPoint(x,y,z); } 00446 00447 /** Set all the points at once from vectors with X,Y and Z coordinates (if Z is not provided, it will be set to all zeros). 00448 * \tparam VECTOR can be mrpt::vector_float or std::vector<float> or any other column or row Eigen::Matrix. 00449 */ 00450 template <typename VECTOR> 00451 inline void setAllPointsTemplate(const VECTOR &X,const VECTOR &Y,const VECTOR &Z = VECTOR()) 00452 { 00453 const size_t N = X.size(); 00454 ASSERT_EQUAL_(X.size(),Y.size()) 00455 ASSERT_(Z.size()==0 || Z.size()==X.size()) 00456 this->setSize(N); 00457 const bool z_valid = !Z.empty(); 00458 if (z_valid) for (size_t i=0;i<N;i++) { this->setPointFast(i,X[i],Y[i],Z[i]); } 00459 else for (size_t i=0;i<N;i++) { this->setPointFast(i,X[i],Y[i],0); } 00460 mark_as_modified(); 00461 } 00462 00463 /** Set all the points at once from vectors with X,Y and Z coordinates. \sa getAllPoints */ 00464 inline void setAllPoints(const std::vector<float> &X,const std::vector<float> &Y,const std::vector<float> &Z) { 00465 setAllPointsTemplate(X,Y,Z); 00466 } 00467 00468 /** Set all the points at once from vectors with X and Y coordinates (Z=0). \sa getAllPoints */ 00469 inline void setAllPoints(const std::vector<float> &X,const std::vector<float> &Y) { 00470 setAllPointsTemplate(X,Y); 00471 } 00472 00473 /** Get all the data fields for one point as a vector: depending on the implementation class this can be [X Y Z] or [X Y Z R G B], etc... 00474 * \sa getPointAllFieldsFast, setPointAllFields, setPointAllFieldsFast 00475 */ 00476 void getPointAllFields( const size_t index, std::vector<float> & point_data ) const { 00477 ASSERT_BELOW_(index,this->size()) 00478 getPointAllFieldsFast(index,point_data); 00479 } 00480 00481 /** Set all the data fields for one point as a vector: depending on the implementation class this can be [X Y Z] or [X Y Z R G B], etc... 00482 * Unlike setPointAllFields(), this method does not check for index out of bounds 00483 * \sa setPointAllFields, getPointAllFields, getPointAllFieldsFast 00484 */ 00485 void setPointAllFields( const size_t index, const std::vector<float> & point_data ){ 00486 ASSERT_BELOW_(index,this->size()) 00487 setPointAllFieldsFast(index,point_data); 00488 } 00489 00490 00491 /** Delete points out of the given "z" axis range have been removed. 00492 */ 00493 void clipOutOfRangeInZ(float zMin, float zMax); 00494 00495 /** Delete points which are more far than "maxRange" away from the given "point". 00496 */ 00497 void clipOutOfRange(const CPoint2D &point, float maxRange); 00498 00499 /** Remove from the map the points marked in a bool's array as "true". 00500 * \exception std::exception If mask size is not equal to points count. 00501 */ 00502 void applyDeletionMask( const std::vector<bool> &mask ); 00503 00504 /** Computes the matchings between this and another 2D/3D points map. 00505 This includes finding: 00506 - The set of points pairs in each map 00507 - The mean squared distance between corresponding pairs. 00508 This method is the most time critical one into the ICP algorithm. 00509 00510 * \param otherMap [IN] The other map to compute the matching with. 00511 * \param otherMapPose [IN] The pose of the other map as seen from "this". 00512 * \param maxDistForCorrespondence [IN] Maximum 2D distance between two points to be matched. 00513 * \param maxAngularDistForCorrespondence [IN] Maximum angular distance in radians to allow far points to be matched. 00514 * \param angularDistPivotPoint [IN] The point from which to measure the "angular distances" 00515 * \param correspondences [OUT] The detected matchings pairs. 00516 * \param correspondencesRatio [OUT] The number of correct correspondences. 00517 * \param sumSqrDist [OUT] The sum of all matched points squared distances.If undesired, set to NULL, as default. 00518 * \param covariance [OUT] The resulting matching covariance 3x3 matrix, or NULL if undesired. 00519 * \param onlyKeepTheClosest [OUT] Returns only the closest correspondence (default=false) 00520 * 00521 * \sa computeMatching3DWith 00522 */ 00523 void computeMatchingWith2D( 00524 const CMetricMap *otherMap, 00525 const CPose2D &otherMapPose, 00526 float maxDistForCorrespondence, 00527 float maxAngularDistForCorrespondence, 00528 const CPose2D &angularDistPivotPoint, 00529 TMatchingPairList &correspondences, 00530 float &correspondencesRatio, 00531 float *sumSqrDist = NULL, 00532 bool onlyKeepTheClosest = false, 00533 bool onlyUniqueRobust = false, 00534 const size_t decimation_other_map_points = 1, 00535 const size_t offset_other_map_points = 0 ) const; 00536 00537 /** Computes the matchings between this and another 3D points map - method used in 3D-ICP. 00538 This method finds the set of point pairs in each map. 00539 00540 The method is the most time critical one into the ICP algorithm. 00541 00542 * \param otherMap [IN] The other map to compute the matching with. 00543 * \param otherMapPose [IN] The pose of the other map as seen from "this". 00544 * \param maxDistForCorrespondence [IN] Maximum 2D linear distance between two points to be matched. 00545 * \param maxAngularDistForCorrespondence [IN] In radians: The aim is to allow larger distances to more distant correspondences. 00546 * \param angularDistPivotPoint [IN] The point used to calculate distances from in both maps. 00547 * \param correspondences [OUT] The detected matchings pairs. 00548 * \param correspondencesRatio [OUT] The ratio [0,1] of points in otherMap with at least one correspondence. 00549 * \param sumSqrDist [OUT] The sum of all matched points squared distances.If undesired, set to NULL, as default. 00550 * \param onlyKeepTheClosest [IN] If set to true, only the closest correspondence will be returned. If false (default) all are returned. 00551 * 00552 * \sa compute3DMatchingRatio 00553 */ 00554 void computeMatchingWith3D( 00555 const CMetricMap *otherMap, 00556 const CPose3D &otherMapPose, 00557 float maxDistForCorrespondence, 00558 float maxAngularDistForCorrespondence, 00559 const CPoint3D &angularDistPivotPoint, 00560 TMatchingPairList &correspondences, 00561 float &correspondencesRatio, 00562 float *sumSqrDist = NULL, 00563 bool onlyKeepTheClosest = true, 00564 bool onlyUniqueRobust = false, 00565 const size_t decimation_other_map_points = 1, 00566 const size_t offset_other_map_points = 0 ) const; 00567 00568 /** Computes the ratio in [0,1] of correspondences between "this" and the "otherMap" map, whose 6D pose relative to "this" is "otherMapPose" 00569 * In the case of a multi-metric map, this returns the average between the maps. This method always return 0 for grid maps. 00570 * \param otherMap [IN] The other map to compute the matching with. 00571 * \param otherMapPose [IN] The 6D pose of the other map as seen from "this". 00572 * \param minDistForCorr [IN] The minimum distance between 2 non-probabilistic map elements for counting them as a correspondence. 00573 * \param minMahaDistForCorr [IN] The minimum Mahalanobis distance between 2 probabilistic map elements for counting them as a correspondence. 00574 * 00575 * \return The matching ratio [0,1] 00576 * \sa computeMatchingWith2D 00577 */ 00578 float compute3DMatchingRatio( 00579 const CMetricMap *otherMap, 00580 const CPose3D &otherMapPose, 00581 float minDistForCorr = 0.10f, 00582 float minMahaDistForCorr = 2.0f 00583 ) const; 00584 00585 /** Transform the range scan into a set of cartessian coordinated 00586 * points. The options in "insertionOptions" are considered in this method. 00587 * \param rangeScan The scan to be inserted into this map 00588 * \param robotPose The robot 3D pose, default to (0,0,0|0deg,0deg,0deg). It is used to compute the sensor pose relative to the robot actual pose. Recall sensor pose is embeded in the observation class. 00589 * 00590 * Only ranges marked as "valid=true" in the observation will be inserted 00591 * 00592 * \note Each derived class may enrich points in different ways (color, weight, etc..), so please refer to the description of the specific 00593 * implementation of mrpt::slam::CPointsMap you are using. 00594 * \note The actual generic implementation of this file lives in <src>/CPointsMap_crtp_common.h, but specific instantiations are generated at each derived class. 00595 * 00596 * \sa CObservation2DRangeScan, CObservation3DRangeScan 00597 */ 00598 virtual void loadFromRangeScan( 00599 const CObservation2DRangeScan &rangeScan, 00600 const CPose3D *robotPose = NULL ) = 0; 00601 00602 /** Overload of \a loadFromRangeScan() for 3D range scans (for example, Kinect observations). 00603 * 00604 * \param rangeScan The scan to be inserted into this map 00605 * \param robotPose The robot 3D pose, default to (0,0,0|0deg,0deg,0deg). It is used to compute the sensor pose relative to the robot actual pose. Recall sensor pose is embeded in the observation class. 00606 * 00607 * \note Each derived class may enrich points in different ways (color, weight, etc..), so please refer to the description of the specific 00608 * implementation of mrpt::slam::CPointsMap you are using. 00609 * \note The actual generic implementation of this file lives in <src>/CPointsMap_crtp_common.h, but specific instantiations are generated at each derived class. 00610 */ 00611 virtual void loadFromRangeScan( 00612 const CObservation3DRangeScan &rangeScan, 00613 const CPose3D *robotPose = NULL ) = 0; 00614 00615 /** Insert the contents of another map into this one, fusing the previous content with the new one. 00616 * This means that points very close to existing ones will be "fused", rather than "added". This prevents 00617 * the unbounded increase in size of these class of maps. 00618 * NOTICE that "otherMap" is neither translated nor rotated here, so if this is desired it must done 00619 * before calling this method. 00620 * \param otherMap The other map whose points are to be inserted into this one. 00621 * \param minDistForFuse Minimum distance (in meters) between two points, each one in a map, to be considered the same one and be fused rather than added. 00622 * \param notFusedPoints If a pointer is supplied, this list will contain at output a list with a "bool" value per point in "this" map. This will be false/true according to that point having been fused or not. 00623 * \sa loadFromRangeScan, addFrom 00624 */ 00625 void fuseWith( 00626 CPointsMap *anotherMap, 00627 float minDistForFuse = 0.02f, 00628 std::vector<bool> *notFusedPoints = NULL); 00629 00630 /** Replace each point \f$ p_i \f$ by \f$ p'_i = b \oplus p_i \f$ (pose compounding operator). 00631 */ 00632 void changeCoordinatesReference(const CPose2D &b); 00633 00634 /** Replace each point \f$ p_i \f$ by \f$ p'_i = b \oplus p_i \f$ (pose compounding operator). 00635 */ 00636 void changeCoordinatesReference(const CPose3D &b); 00637 00638 /** Copy all the points from "other" map to "this", replacing each point \f$ p_i \f$ by \f$ p'_i = b \oplus p_i \f$ (pose compounding operator). 00639 */ 00640 void changeCoordinatesReference(const CPointsMap &other, const CPose3D &b); 00641 00642 /** Returns true if the map is empty/no observation has been inserted. 00643 */ 00644 virtual bool isEmpty() const; 00645 00646 /** STL-like method to check whether the map is empty: */ 00647 inline bool empty() const { return isEmpty(); } 00648 00649 /** Returns a 3D object representing the map. 00650 * The color of the points is given by the static variables: COLOR_3DSCENE_R,COLOR_3DSCENE_G,COLOR_3DSCENE_B 00651 * \sa mrpt::global_settings::POINTSMAPS_3DOBJECT_POINTSIZE 00652 */ 00653 virtual void getAs3DObject ( mrpt::opengl::CSetOfObjectsPtr &outObj ) const; 00654 00655 /** If the map is a simple points map or it's a multi-metric map that contains EXACTLY one simple points map, return it. 00656 * Otherwise, return NULL 00657 */ 00658 virtual const CSimplePointsMap * getAsSimplePointsMap() const { return NULL; } 00659 virtual CSimplePointsMap * getAsSimplePointsMap() { return NULL; } 00660 00661 00662 /** This method returns the largest distance from the origin to any of the points, such as a sphere centered at the origin with this radius cover ALL the points in the map (the results are buffered, such as, if the map is not modified, the second call will be much faster than the first one). */ 00663 float getLargestDistanceFromOrigin() const; 00664 00665 /** Like \a getLargestDistanceFromOrigin() but returns in \a output_is_valid = false if the distance was not already computed, skipping its computation then, unlike getLargestDistanceFromOrigin() */ 00666 float getLargestDistanceFromOriginNoRecompute(bool &output_is_valid) const { 00667 output_is_valid = m_largestDistanceFromOriginIsUpdated; 00668 return m_largestDistanceFromOrigin; 00669 } 00670 00671 /** Computes the bounding box of all the points, or (0,0 ,0,0, 0,0) if there are no points. 00672 * Results are cached unless the map is somehow modified to avoid repeated calculations. 00673 */ 00674 void boundingBox( float &min_x,float &max_x,float &min_y,float &max_y,float &min_z,float &max_z ) const; 00675 00676 inline void boundingBox(TPoint3D &pMin,TPoint3D &pMax) const { 00677 float dmy1,dmy2,dmy3,dmy4,dmy5,dmy6; 00678 boundingBox(dmy1,dmy2,dmy3,dmy4,dmy5,dmy6); 00679 pMin.x=dmy1; 00680 pMin.y=dmy2; 00681 pMin.z=dmy3; 00682 pMax.x=dmy4; 00683 pMax.y=dmy5; 00684 pMax.z=dmy6; 00685 } 00686 00687 void extractCylinder( const CPoint2D ¢er, const double radius, const double zmin, const double zmax, CPointsMap *outMap ); 00688 00689 /** @name Filter-by-height stuff 00690 @{ */ 00691 00692 /** Enable/disable the filter-by-height functionality \sa setHeightFilterLevels \note Default upon construction is disabled. */ 00693 inline void enableFilterByHeight(bool enable=true) { m_heightfilter_enabled=enable; } 00694 /** Return whether filter-by-height is enabled \sa enableFilterByHeight */ 00695 inline bool isFilterByHeightEnabled() const { return m_heightfilter_enabled; } 00696 00697 /** Set the min/max Z levels for points to be actually inserted in the map (only if \a enableFilterByHeight() was called before). */ 00698 inline void setHeightFilterLevels(const double _z_min, const double _z_max) { m_heightfilter_z_min=_z_min; m_heightfilter_z_max=_z_max; } 00699 /** Get the min/max Z levels for points to be actually inserted in the map \sa enableFilterByHeight, setHeightFilterLevels */ 00700 inline void getHeightFilterLevels(double &_z_min, double &_z_max) const { _z_min=m_heightfilter_z_min; _z_max=m_heightfilter_z_max; } 00701 00702 /** @} */ 00703 00704 /** The color [0,1] of points when extracted from getAs3DObject (default=blue) */ 00705 static float COLOR_3DSCENE_R; 00706 static float COLOR_3DSCENE_G; 00707 static float COLOR_3DSCENE_B; 00708 00709 00710 /** Computes the likelihood of taking a given observation from a given pose in the world being modeled with this map. 00711 * \param takenFrom The robot's pose the observation is supposed to be taken from. 00712 * \param obs The observation. 00713 * \return This method returns a likelihood in the range [0,1]. 00714 * 00715 * \sa Used in particle filter algorithms, see: CMultiMetricMapPDF 00716 * \note In CPointsMap this method is virtual so it can be redefined in derived classes, if desired. 00717 */ 00718 virtual double computeObservationLikelihood( const CObservation *obs, const CPose3D &takenFrom ); 00719 00720 /** @name PCL library support 00721 @{ */ 00722 00723 00724 /** Use to convert this MRPT point cloud object into a PCL point cloud object. 00725 * Usage example: 00726 * \code 00727 * mrpt::slam::CPointsCloud pc; 00728 * pcl::PointCloud<pcl::PointXYZ> cloud; 00729 * 00730 * pc.getPCLPointCloud(cloud); 00731 * \endcode 00732 */ 00733 template <class POINTCLOUD> 00734 void getPCLPointCloud(POINTCLOUD &cloud) const 00735 { 00736 const size_t nThis = this->size(); 00737 // Fill in the cloud data 00738 cloud.width = nThis; 00739 cloud.height = 1; 00740 cloud.is_dense = false; 00741 cloud.points.resize(cloud.width * cloud.height); 00742 for (size_t i = 0; i < nThis; ++i) { 00743 cloud.points[i].x =this->x[i]; 00744 cloud.points[i].y =this->y[i]; 00745 cloud.points[i].z =this->z[i]; 00746 } 00747 } 00748 00749 /** @} */ 00750 00751 /** @name Methods that MUST be implemented by children classes of KDTreeCapable 00752 @{ */ 00753 00754 /// Must return the number of data points 00755 inline size_t kdtree_get_point_count() const { return this->size(); } 00756 00757 /// Returns the dim'th component of the idx'th point in the class: 00758 inline float kdtree_get_pt(const size_t idx, int dim) const { 00759 if (dim==0) return this->x[idx]; 00760 else if (dim==1) return this->y[idx]; 00761 else if (dim==2) return this->z[idx]; else return 0; 00762 } 00763 00764 /// Returns the distance between the vector "p1[0:size-1]" and the data point with index "idx_p2" stored in the class: 00765 inline float kdtree_distance(const float *p1, const size_t idx_p2,size_t size) const 00766 { 00767 if (size==2) 00768 { 00769 const float d0 = p1[0]-x[idx_p2]; 00770 const float d1 = p1[1]-y[idx_p2]; 00771 return d0*d0+d1*d1; 00772 } 00773 else 00774 { 00775 const float d0 = p1[0]-x[idx_p2]; 00776 const float d1 = p1[1]-y[idx_p2]; 00777 const float d2 = p1[2]-z[idx_p2]; 00778 return d0*d0+d1*d1+d2*d2; 00779 } 00780 } 00781 00782 // Optional bounding-box computation: return false to default to a standard bbox computation loop. 00783 // Return true if the BBOX was already computed by the class and returned in "bb" so it can be avoided to redo it again. 00784 // Look at bb.size() to find out the expected dimensionality (e.g. 2 or 3 for point clouds) 00785 template <typename BBOX> 00786 bool kdtree_get_bbox(BBOX &bb) const 00787 { 00788 float min_z,max_z; 00789 this->boundingBox( 00790 bb[0].low, bb[0].high, 00791 bb[1].low, bb[1].high, 00792 min_z,max_z); 00793 if (bb.size()==3) { 00794 bb[2].low = min_z; bb[2].high = max_z; 00795 } 00796 return true; 00797 } 00798 00799 00800 /** @} */ 00801 00802 protected: 00803 std::vector<float> x,y,z; //!< The point coordinates 00804 00805 CSinCosLookUpTableFor2DScans m_scans_sincos_cache; //!< Cache of sin/cos values for the latest 2D scan geometries. 00806 00807 /** Auxiliary variables used in "getLargestDistanceFromOrigin" 00808 * \sa getLargestDistanceFromOrigin 00809 */ 00810 mutable float m_largestDistanceFromOrigin; 00811 00812 /** Auxiliary variables used in "getLargestDistanceFromOrigin" 00813 * \sa getLargestDistanceFromOrigin 00814 */ 00815 mutable bool m_largestDistanceFromOriginIsUpdated; 00816 00817 mutable bool m_boundingBoxIsUpdated; 00818 mutable float m_bb_min_x,m_bb_max_x, m_bb_min_y,m_bb_max_y, m_bb_min_z,m_bb_max_z; 00819 00820 00821 /** Called only by this class or children classes, set m_largestDistanceFromOriginIsUpdated=false and such. */ 00822 inline void mark_as_modified() const 00823 { 00824 m_largestDistanceFromOriginIsUpdated=false; 00825 m_boundingBoxIsUpdated = false; 00826 kdtree_mark_as_outdated(); 00827 } 00828 00829 /** This is a common version of CMetricMap::insertObservation() for point maps (actually, CMetricMap::internal_insertObservation), 00830 * so derived classes don't need to worry implementing that method unless something special is really necesary. 00831 * See mrpt::slam::CPointsMap for the enumeration of types of observations which are accepted. 00832 */ 00833 bool internal_insertObservation( 00834 const CObservation *obs, 00835 const CPose3D *robotPose); 00836 00837 /** Helper method for ::copyFrom() */ 00838 void base_copyFrom(const CPointsMap &obj); 00839 00840 00841 /** @name PLY Import virtual methods to implement in base classes 00842 @{ */ 00843 /** In a base class, reserve memory to prepare subsequent calls to PLY_import_set_face */ 00844 virtual void PLY_import_set_face_count(const size_t N) { } 00845 00846 /** In a base class, will be called after PLY_import_set_vertex_count() once for each loaded point. 00847 * \param pt_color Will be NULL if the loaded file does not provide color info. 00848 */ 00849 virtual void PLY_import_set_vertex(const size_t idx, const mrpt::math::TPoint3Df &pt, const mrpt::utils::TColorf *pt_color = NULL); 00850 /** @} */ 00851 00852 /** @name PLY Export virtual methods to implement in base classes 00853 @{ */ 00854 00855 /** In a base class, return the number of vertices */ 00856 virtual size_t PLY_export_get_vertex_count() const; 00857 00858 /** In a base class, return the number of faces */ 00859 virtual size_t PLY_export_get_face_count() const { return 0; } 00860 00861 /** In a base class, will be called after PLY_export_get_vertex_count() once for each exported point. 00862 * \param pt_color Will be NULL if the loaded file does not provide color info. 00863 */ 00864 virtual void PLY_export_get_vertex( 00865 const size_t idx, 00866 mrpt::math::TPoint3Df &pt, 00867 bool &pt_has_color, 00868 mrpt::utils::TColorf &pt_color) const; 00869 00870 /** @} */ 00871 00872 /** The minimum and maximum height for a certain laser scan to be inserted into this map 00873 * \sa m_heightfilter_enabled */ 00874 double m_heightfilter_z_min, m_heightfilter_z_max; 00875 00876 /** Whether or not (default=not) filter the input points by height 00877 * \sa m_heightfilter_z_min, m_heightfilter_z_max */ 00878 bool m_heightfilter_enabled; 00879 00880 00881 // Friend methods: 00882 template <class Derived> friend struct detail::loadFromRangeImpl; 00883 template <class Derived> friend struct detail::pointmap_traits; 00884 00885 00886 }; // End of class def. 00887 00888 } // End of namespace 00889 00890 namespace global_settings 00891 { 00892 /** The size of points when exporting with getAs3DObject() (default=3.0) 00893 * Affects to: 00894 * - mrpt::slam::CPointsMap and all its children classes. 00895 */ 00896 extern MAPS_IMPEXP float POINTSMAPS_3DOBJECT_POINTSIZE; 00897 } 00898 00899 namespace utils 00900 { 00901 /** Specialization mrpt::utils::PointCloudAdapter<mrpt::slam::CPointsMap> \ingroup mrpt_adapters_grp*/ 00902 template <> 00903 class PointCloudAdapter<mrpt::slam::CPointsMap> : public detail::PointCloudAdapterHelperNoRGB<mrpt::slam::CPointsMap,float> 00904 { 00905 private: 00906 mrpt::slam::CPointsMap &m_obj; 00907 public: 00908 typedef float coords_t; //!< The type of each point XYZ coordinates 00909 static const int HAS_RGB = 0; //!< Has any color RGB info? 00910 static const int HAS_RGBf = 0; //!< Has native RGB info (as floats)? 00911 static const int HAS_RGBu8 = 0; //!< Has native RGB info (as uint8_t)? 00912 00913 /** Constructor (accept a const ref for convenience) */ 00914 inline PointCloudAdapter(const mrpt::slam::CPointsMap &obj) : m_obj(*const_cast<mrpt::slam::CPointsMap*>(&obj)) { } 00915 /** Get number of points */ 00916 inline size_t size() const { return m_obj.size(); } 00917 /** Set number of points (to uninitialized values) */ 00918 inline void resize(const size_t N) { m_obj.resize(N); } 00919 00920 /** Get XYZ coordinates of i'th point */ 00921 template <typename T> 00922 inline void getPointXYZ(const size_t idx, T &x,T &y, T &z) const { 00923 m_obj.getPointFast(idx,x,y,z); 00924 } 00925 /** Set XYZ coordinates of i'th point */ 00926 inline void setPointXYZ(const size_t idx, const coords_t x,const coords_t y, const coords_t z) { 00927 m_obj.setPointFast(idx,x,y,z); 00928 } 00929 }; // end of PointCloudAdapter<mrpt::slam::CPointsMap> 00930 00931 } 00932 00933 } // End of namespace 00934 00935 #endif
| Page generated by Doxygen 1.7.4 for MRPT 0.9.5 SVN:2717 at Sun Oct 16 16:08:03 PDT 2011 | Hosted on: |