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 CObservation3DRangeScan_H 00029 #define CObservation3DRangeScan_H 00030 00031 #include <mrpt/utils/CSerializable.h> 00032 #include <mrpt/utils/CImage.h> 00033 #include <mrpt/slam/CObservation.h> 00034 #include <mrpt/poses/CPose3D.h> 00035 #include <mrpt/poses/CPose2D.h> 00036 #include <mrpt/math/CPolygon.h> 00037 #include <mrpt/utils/adapters.h> 00038 00039 00040 namespace mrpt 00041 { 00042 namespace slam 00043 { 00044 DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE( CObservation3DRangeScan, CObservation,OBS_IMPEXP ) 00045 00046 namespace detail { 00047 // Implemented in CObservation3DRangeScan_project3D_impl.h 00048 template <class POINTMAP> 00049 void project3DPointsFromDepthImageInto(CObservation3DRangeScan & src_obs,POINTMAP & dest_pointcloud,const bool takeIntoAccountSensorPoseOnRobot,const mrpt::poses::CPose3D * robotPoseInTheWorld,const bool PROJ3D_USE_LUT); 00050 } 00051 00052 /** Declares a class derived from "CObservation" that 00053 * encapsules a 3D range scan measurement (e.g. from a time of flight range camera). 00054 * This kind of observations can carry one or more of these data fields: 00055 * - 3D point cloud (as float's). 00056 * - 2D range image (as a matrix): Each entry in the matrix "rangeImage(ROW,COLUMN)" contains a distance or a depth (in meters), depending on \a range_is_depth. 00057 * - 2D intensity (grayscale or RGB) image (as a mrpt::utils::CImage): For SwissRanger cameras, a logarithmic A-law compression is used to convert the original 16bit intensity to a more standard 8bit graylevel. 00058 * - 2D confidence image (as a mrpt::utils::CImage): For each pixel, a 0x00 and a 0xFF mean the lowest and highest confidence levels, respectively. 00059 * 00060 * The coordinates of the 3D point cloud are in meters with respect to the depth camera origin of coordinates 00061 * (in SwissRanger, the front face of the camera: a small offset ~1cm in front of the physical focal point), 00062 * with the +X axis pointing forward, +Y pointing left-hand and +Z pointing up. 00063 * The field CObservation3DRangeScan::relativePoseIntensityWRTDepth describes the change of coordinates from 00064 * the depth camera to the intensity (RGB or grayscale) camera. In a SwissRanger camera both cameras coincide, 00065 * so this pose is just a rotation (0,0,0,-90deg,0,-90deg). But in 00066 * Microsoft Kinect there is also an offset, as shown in this figure: 00067 * 00068 * <div align=center> 00069 * <img src="CObservation3DRangeScan_figRefSystem.png"> 00070 * </div> 00071 * 00072 * In any case, check the field \a relativePoseIntensityWRTDepth, or the method \a doDepthAndIntensityCamerasCoincide() 00073 * to determine if both frames of reference coincide, since even for Kinect cameras both can coincide if the images 00074 * have been rectified. 00075 * 00076 * The 2D images and matrices are stored as common images, with an up->down rows order and left->right, as usual. 00077 * Optionally, the intensity and confidence channels can be set to delayed-load images for off-rawlog storage so it saves 00078 * memory by having loaded in memory just the needed images. See the methods load() and unload(). 00079 * Due to the intensive storage requirements of this kind of observations, this observation is the only one in MRPT 00080 * for which it's recommended to always call "load()" and "unload()" before and after using the observation, *ONLY* when 00081 * the observation was read from a rawlog dataset, in order to make sure that all the externally stored data fields are 00082 * loaded and ready in memory. 00083 * 00084 * Classes that grab observations of this type are: 00085 * - mrpt::hwdrivers::CSwissRanger3DCamera 00086 * - mrpt::hwdrivers::CKinect 00087 * 00088 * There are two sets of calibration parameters: 00089 * - cameraParams: Projection parameters of the depth camera. 00090 * - cameraParamsIntensity: Projection parameters of the intensity (gray-level or RGB) camera. 00091 * 00092 * In some cameras, like SwissRanger, both are the same. It is possible in Kinect to rectify the range images such both cameras 00093 * seem to coincide and then both sets of camera parameters will be identical. 00094 * 00095 * Range data can be interpreted in two different ways depending on the 3D camera (this field is already set to the 00096 * correct setting when grabbing observations from an mrpt::hwdrivers sensor): 00097 * - range_is_depth=true -> Kinect-like ranges: entries of \a rangeImage are distances along the +X axis 00098 * - range_is_depth=false -> Ranges in \a rangeImage are actual distances in 3D. 00099 * 00100 * The "intensity" channel may come from different channels in sesnsors as Kinect. Look at field \a intensityImageChannel to 00101 * find out if the image was grabbed from the visible (RGB) or IR channels. 00102 * 00103 * 3D point clouds can be generated at any moment after grabbing with CObservation3DRangeScan::project3DPointsFromDepthImage(), provided the correct 00104 * calibration parameters. 00105 * 00106 * \note Starting at serialization version 2 (MRPT 0.9.1+), the confidence channel is stored as an image instead of a matrix to optimize memory and disk space. 00107 * \note Starting at serialization version 3 (MRPT 0.9.1+), the 3D point cloud and the rangeImage can both be stored externally to save rawlog space. 00108 * \note Starting at serialization version 5 (MRPT 0.9.5+), the new field \a range_is_depth 00109 * \note Starting at serialization version 6 (MRPT 0.9.5+), the new field \a intensityImageChannel 00110 * 00111 * \sa mrpt::hwdrivers::CSwissRanger3DCamera, mrpt::hwdrivers::CKinect, CObservation 00112 * \ingroup mrpt_obs_grp 00113 */ 00114 class OBS_IMPEXP CObservation3DRangeScan : public CObservation 00115 { 00116 // This must be added to any CSerializable derived class: 00117 DEFINE_SERIALIZABLE( CObservation3DRangeScan ) 00118 00119 protected: 00120 bool m_points3D_external_stored; //!< If set to true, m_points3D_external_file is valid. 00121 std::string m_points3D_external_file; //!< 3D points are in CImage::IMAGES_PATH_BASE+<this_file_name> 00122 00123 bool m_rangeImage_external_stored; //!< If set to true, m_rangeImage_external_file is valid. 00124 std::string m_rangeImage_external_file; //!< rangeImage is in CImage::IMAGES_PATH_BASE+<this_file_name> 00125 00126 public: 00127 CObservation3DRangeScan( ); //!< Default constructor 00128 virtual ~CObservation3DRangeScan( ); //!< Destructor 00129 00130 /** @name Delayed-load manual control methods. 00131 @{ */ 00132 /** Makes sure all images and other fields which may be externally stored are loaded in memory. 00133 * Note that for all CImages, calling load() is not required since the images will be automatically loaded upon first access, so load() shouldn't be needed to be called in normal cases by the user. 00134 * If all the data were alredy loaded or this object has no externally stored data fields, calling this method has no effects. 00135 * \sa unload 00136 */ 00137 virtual void load() const; 00138 /** Unload all images, for the case they being delayed-load images stored in external files (othewise, has no effect). 00139 * \sa load 00140 */ 00141 virtual void unload(); 00142 /** @} */ 00143 00144 /** Project the RGB+D images into a 3D point cloud (with color if the target map supports it) and optionally at a given 3D pose. 00145 * The 3D point coordinates are computed from the depth image (\a rangeImage) and the depth camera camera parameters (\a cameraParams). 00146 * There exist two set of formulas for projecting the i'th point, depending on the value of "range_is_depth". 00147 * In all formulas below, "rangeImage" is the matrix of ranges and the pixel coordinates are (r,c). 00148 * 00149 * 1) [range_is_depth=true] With "range equals depth" or "Kinect-like depth mode": the range values 00150 * are in fact distances along the "+X" axis, not real 3D ranges (this is the way Kinect reports ranges): 00151 * 00152 * \code 00153 * x(i) = rangeImage(r,c) 00154 * y(i) = (r_cx - c) * x(i) / r_fx 00155 * z(i) = (r_cy - r) * x(i) / r_fy 00156 * \endcode 00157 * 00158 * 00159 * 2) [range_is_depth=false] With "normal ranges": range means distance in 3D. This must be set when 00160 * processing data from the SwissRange 3D camera, among others. 00161 * 00162 * \code 00163 * Ky = (r_cx - c)/r_fx 00164 * Kz = (r_cy - r)/r_fy 00165 * 00166 * x(i) = rangeImage(r,c) / sqrt( 1 + Ky^2 + Kz^2 ) 00167 * y(i) = Ky * x(i) 00168 * z(i) = Kz * x(i) 00169 * \endcode 00170 * 00171 * The color of each point is determined by projecting the 3D local point into the RGB image using \a cameraParamsIntensity. 00172 * 00173 * By default the local coordinates of points are directly stored into the local map, but if indicated so in \a takeIntoAccountSensorPoseOnRobot 00174 * the points are transformed with \a sensorPose. Furthermore, if provided, those coordinates are transformed with \a robotPoseInTheWorld 00175 * 00176 * \param[in] PROJ3D_USE_LUT (Only when range_is_depth=true) Whether to use a Look-up-table (LUT) to speed up the conversion. It's thread safe in all situations <b>except</b> when you call this method from different threads <b>and</b> with different camera parameter matrices. In all other cases, it's a good idea to left it enabled. 00177 * \tparam POINTMAP Supported maps are all those covered by mrpt::utils::PointCloudAdapter (mrpt::slam::CPointsMap and derived, mrpt::opengl::CPointCloudColoured, PCL point clouds,...) 00178 * 00179 * \note In MRPT < 0.9.5, this method always assumes that ranges were in Kinect-like format. 00180 */ 00181 template <class POINTMAP> 00182 inline void project3DPointsFromDepthImageInto( 00183 POINTMAP & dest_pointcloud, 00184 const bool takeIntoAccountSensorPoseOnRobot, 00185 const mrpt::poses::CPose3D *robotPoseInTheWorld=NULL, 00186 const bool PROJ3D_USE_LUT=true) 00187 { 00188 detail::project3DPointsFromDepthImageInto<POINTMAP>(*this,dest_pointcloud,takeIntoAccountSensorPoseOnRobot,robotPoseInTheWorld,PROJ3D_USE_LUT); 00189 } 00190 00191 /** This method is equivalent to \c project3DPointsFromDepthImageInto() storing the projected 3D points (without color, in local coordinates) in this same class. 00192 * For new code it's recommended to use instead \c project3DPointsFromDepthImageInto() which is much more versatile. 00193 */ 00194 inline void project3DPointsFromDepthImage(const bool PROJ3D_USE_LUT=true) { 00195 this->project3DPointsFromDepthImageInto(*this,false,NULL,PROJ3D_USE_LUT); 00196 } 00197 00198 bool hasPoints3D; //!< true means the field points3D contains valid data. 00199 std::vector<float> points3D_x; //!< If hasPoints3D=true, the X coordinates of the 3D point cloud detected by the camera. \sa resizePoints3DVectors 00200 std::vector<float> points3D_y; //!< If hasPoints3D=true, the Y coordinates of the 3D point cloud detected by the camera. \sa resizePoints3DVectors 00201 std::vector<float> points3D_z; //!< If hasPoints3D=true, the Z coordinates of the 3D point cloud detected by the camera. \sa resizePoints3DVectors 00202 00203 /** Use this method instead of resizing all three \a points3D_x, \a points3D_y & \a points3D_z to allow the usage of the internal memory pool. */ 00204 void resizePoints3DVectors(const size_t nPoints); 00205 00206 // 3D points external storage functions --------- 00207 inline bool points3D_isExternallyStored() const { return m_points3D_external_stored; } 00208 inline std::string points3D_getExternalStorageFile() const { return m_points3D_external_file; } 00209 void points3D_getExternalStorageFileAbsolutePath(std::string &out_path) const; 00210 inline std::string points3D_getExternalStorageFileAbsolutePath() const { 00211 std::string tmp; 00212 points3D_getExternalStorageFileAbsolutePath(tmp); 00213 return tmp; 00214 } 00215 void points3D_convertToExternalStorage( const std::string &fileName, const std::string &use_this_base_dir ); //!< Users won't normally want to call this, it's only used from internal MRPT programs. 00216 // --------- 00217 00218 bool hasRangeImage; //!< true means the field rangeImage contains valid data 00219 mrpt::math::CMatrix rangeImage; //!< If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters) \sa range_is_depth 00220 bool range_is_depth; //!< true: Kinect-like ranges: entries of \a rangeImage are distances along the +X axis; false: Ranges in \a rangeImage are actual distances in 3D. 00221 00222 void rangeImage_setSize(const int HEIGHT, const int WIDTH); //!< Similar to calling "rangeImage.setSize(H,W)" but this method provides memory pooling to speed-up the memory allocation. 00223 00224 // Range Matrix external storage functions --------- 00225 inline bool rangeImage_isExternallyStored() const { return m_rangeImage_external_stored; } 00226 inline std::string rangeImage_getExternalStorageFile() const { return m_rangeImage_external_file; } 00227 void rangeImage_getExternalStorageFileAbsolutePath(std::string &out_path) const; 00228 inline std::string rangeImage_getExternalStorageFileAbsolutePath() const { 00229 std::string tmp; 00230 rangeImage_getExternalStorageFileAbsolutePath(tmp); 00231 return tmp; 00232 } 00233 void rangeImage_convertToExternalStorage( const std::string &fileName, const std::string &use_this_base_dir ); //!< Users won't normally want to call this, it's only used from internal MRPT programs. 00234 /** Forces marking this observation as non-externally stored - it doesn't anything else apart from reseting the corresponding flag (Users won't normally want to call this, it's only used from internal MRPT programs) */ 00235 void rangeImage_forceResetExternalStorage() { m_rangeImage_external_stored=false; } 00236 // --------- 00237 00238 /** Enum type for intensityImageChannel */ 00239 enum TIntensityChannelID 00240 { 00241 CH_VISIBLE = 0, //!< Grayscale or RGB visible channel of the camera sensor. 00242 CH_IR = 1 //!< Infrarred (IR) channel 00243 }; 00244 00245 bool hasIntensityImage; //!< true means the field intensityImage contains valid data 00246 mrpt::utils::CImage intensityImage; //!< If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage" 00247 TIntensityChannelID intensityImageChannel; //!< The source of the intensityImage; typically the visible channel \sa TIntensityChannelID 00248 00249 bool hasConfidenceImage; //!< true means the field confidenceImage contains valid data 00250 mrpt::utils::CImage confidenceImage; //!< If hasConfidenceImage=true, an image with the "confidence" value [range 0-255] as estimated by the capture drivers. 00251 00252 mrpt::utils::TCamera cameraParams; //!< Projection parameters of the depth camera. 00253 mrpt::utils::TCamera cameraParamsIntensity; //!< Projection parameters of the intensity (graylevel or RGB) camera. 00254 00255 /** Relative pose of the intensity camera wrt the depth camera (which is the coordinates origin for this observation). 00256 * In a SwissRanger camera, this will be (0,0,0,-90deg,0,-90deg) since both cameras coincide. 00257 * In a Kinect, this will include a small lateral displacement and a rotation, according to the drawing on the top of this page. 00258 * \sa doDepthAndIntensityCamerasCoincide 00259 */ 00260 mrpt::poses::CPose3D relativePoseIntensityWRTDepth; 00261 00262 /** Return true if \a relativePoseIntensityWRTDepth equals the pure rotation (0,0,0,-90deg,0,-90deg) (with a small comparison epsilon) 00263 * \sa relativePoseIntensityWRTDepth 00264 */ 00265 bool doDepthAndIntensityCamerasCoincide() const; 00266 00267 00268 float maxRange; //!< The maximum range allowed by the device, in meters (e.g. 8.0m, 5.0m,...) 00269 CPose3D sensorPose; //!< The 6D pose of the sensor on the robot. 00270 float stdError; //!< The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid. 00271 00272 00273 /** A general method to retrieve the sensor pose on the robot. 00274 * Note that most sensors will return a full (6D) CPose3D, but see the derived classes for more details or special cases. 00275 * \sa setSensorPose 00276 */ 00277 void getSensorPose( CPose3D &out_sensorPose ) const { out_sensorPose = sensorPose; } 00278 00279 /** A general method to change the sensor pose on the robot. 00280 * Note that most sensors will use the full (6D) CPose3D, but see the derived classes for more details or special cases. 00281 * \sa getSensorPose 00282 */ 00283 void setSensorPose( const CPose3D &newSensorPose ) { sensorPose = newSensorPose; } 00284 00285 void swap(CObservation3DRangeScan &o); //!< Very efficient method to swap the contents of two observations. 00286 00287 void getZoneAsObs( CObservation3DRangeScan &obs, const unsigned int &r1, const unsigned int &r2, const unsigned int &c1, const unsigned int &c2 ); 00288 00289 /** A Levenberg-Marquart-based optimizer to recover the calibration parameters of a 3D camera given a range (depth) image and the corresponding 3D point cloud. 00290 * \param camera_offset The offset (in meters) in the +X direction of the point cloud. It's 1cm for SwissRanger SR4000. 00291 * \return The final average reprojection error per pixel (typ <0.05 px) 00292 */ 00293 static double recoverCameraCalibrationParameters( 00294 const CObservation3DRangeScan &in_obs, 00295 mrpt::utils::TCamera &out_camParams, 00296 const double camera_offset = 0.01 ); 00297 00298 /** Look-up-table struct for project3DPointsFromDepthImageInto() */ 00299 struct TCached3DProjTables 00300 { 00301 mrpt::vector_float Kzs,Kys; 00302 TCamera prev_camParams; 00303 }; 00304 static TCached3DProjTables m_3dproj_lut; //!< 3D point cloud projection look-up-table \sa project3DPointsFromDepthImage 00305 00306 }; // End of class def. 00307 00308 00309 } // End of namespace 00310 00311 namespace utils 00312 { 00313 using namespace ::mrpt::slam; 00314 // Specialization must occur in the same namespace 00315 MRPT_DECLARE_TTYPENAME_PTR(CObservation3DRangeScan) 00316 00317 // Enum <-> string converter: 00318 template <> 00319 struct TEnumTypeFiller<slam::CObservation3DRangeScan::TIntensityChannelID> 00320 { 00321 typedef slam::CObservation3DRangeScan::TIntensityChannelID enum_t; 00322 static void fill(bimap<enum_t,std::string> &m_map) 00323 { 00324 m_map.insert(slam::CObservation3DRangeScan::CH_VISIBLE, "CH_VISIBLE"); 00325 m_map.insert(slam::CObservation3DRangeScan::CH_IR, "CH_IR"); 00326 } 00327 }; 00328 } 00329 00330 namespace utils 00331 { 00332 using mrpt::slam::CObservation3DRangeScan; 00333 00334 /** Specialization mrpt::utils::PointCloudAdapter<CObservation3DRangeScan> \ingroup mrpt_adapters_grp */ 00335 template <> 00336 class PointCloudAdapter<CObservation3DRangeScan> : public detail::PointCloudAdapterHelperNoRGB<CObservation3DRangeScan,float> 00337 { 00338 private: 00339 CObservation3DRangeScan &m_obj; 00340 public: 00341 typedef float coords_t; //!< The type of each point XYZ coordinates 00342 static const int HAS_RGB = 0; //!< Has any color RGB info? 00343 static const int HAS_RGBf = 0; //!< Has native RGB info (as floats)? 00344 static const int HAS_RGBu8 = 0; //!< Has native RGB info (as uint8_t)? 00345 00346 /** Constructor (accept a const ref for convenience) */ 00347 inline PointCloudAdapter(const CObservation3DRangeScan &obj) : m_obj(*const_cast<CObservation3DRangeScan*>(&obj)) { } 00348 /** Get number of points */ 00349 inline size_t size() const { return m_obj.points3D_x.size(); } 00350 /** Set number of points (to uninitialized values) */ 00351 inline void resize(const size_t N) { 00352 if (N) m_obj.hasPoints3D = true; 00353 m_obj.resizePoints3DVectors(N); 00354 } 00355 00356 /** Get XYZ coordinates of i'th point */ 00357 template <typename T> 00358 inline void getPointXYZ(const size_t idx, T &x,T &y, T &z) const { 00359 x=m_obj.points3D_x[idx]; 00360 y=m_obj.points3D_y[idx]; 00361 z=m_obj.points3D_z[idx]; 00362 } 00363 /** Set XYZ coordinates of i'th point */ 00364 inline void setPointXYZ(const size_t idx, const coords_t x,const coords_t y, const coords_t z) { 00365 m_obj.points3D_x[idx]=x; 00366 m_obj.points3D_y[idx]=y; 00367 m_obj.points3D_z[idx]=z; 00368 } 00369 }; // end of PointCloudAdapter<CObservation3DRangeScan> 00370 } 00371 } // End of namespace 00372 00373 #include "CObservation3DRangeScan_project3D_impl.h" 00374 00375 #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: |