util3d.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #ifndef UTIL3D_H_
00029 #define UTIL3D_H_
00030 
00031 #include "rtabmap/core/RtabmapExp.h"
00032 
00033 #include <pcl/point_cloud.h>
00034 #include <pcl/point_types.h>
00035 #include <pcl/pcl_base.h>
00036 #include <pcl/TextureMesh.h>
00037 #include <rtabmap/core/Transform.h>
00038 #include <rtabmap/core/SensorData.h>
00039 #include <rtabmap/core/Parameters.h>
00040 #include <opencv2/core/core.hpp>
00041 #include <map>
00042 #include <list>
00043 
00044 namespace rtabmap
00045 {
00046 
00047 namespace util3d
00048 {
00049 
00050 cv::Mat RTABMAP_EXP rgbFromCloud(
00051                 const pcl::PointCloud<pcl::PointXYZRGBA> & cloud,
00052                 bool bgrOrder = true);
00053 
00054 cv::Mat RTABMAP_EXP depthFromCloud(
00055                 const pcl::PointCloud<pcl::PointXYZRGBA> & cloud,
00056                 float & fx,
00057                 float & fy,
00058                 bool depth16U = true);
00059 
00060 void RTABMAP_EXP rgbdFromCloud(
00061                 const pcl::PointCloud<pcl::PointXYZRGBA> & cloud,
00062                 cv::Mat & rgb,
00063                 cv::Mat & depth,
00064                 float & fx,
00065                 float & fy,
00066                 bool bgrOrder = true,
00067                 bool depth16U = true);
00068 
00069 pcl::PointXYZ RTABMAP_EXP projectDepthTo3D(
00070                 const cv::Mat & depthImage,
00071                 float x, float y,
00072                 float cx, float cy,
00073                 float fx, float fy,
00074                 bool smoothing,
00075                 float depthErrorRatio = 0.02f);
00076 
00077 Eigen::Vector3f RTABMAP_EXP projectDepthTo3DRay(
00078                 const cv::Size & imageSize,
00079                 float x, float y,
00080                 float cx, float cy,
00081                 float fx, float fy);
00082 
00083 RTABMAP_DEPRECATED (pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromDepth(
00084                 const cv::Mat & imageDepth,
00085                 float cx, float cy,
00086                 float fx, float fy,
00087                 int decimation = 1,
00088                 float maxDepth = 0.0f,
00089                 float minDepth = 0.0f,
00090                 std::vector<int> * validIndices = 0), "Use cloudFromDepth with CameraModel interface.");
00091 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromDepth(
00092                 const cv::Mat & imageDepth,
00093                 const CameraModel & model,
00094                 int decimation = 1,
00095                 float maxDepth = 0.0f,
00096                 float minDepth = 0.0f,
00097                 std::vector<int> * validIndices = 0);
00098 
00099 RTABMAP_DEPRECATED (pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromDepthRGB(
00100                 const cv::Mat & imageRgb,
00101                 const cv::Mat & imageDepth,
00102                 float cx, float cy,
00103                 float fx, float fy,
00104                 int decimation = 1,
00105                 float maxDepth = 0.0f,
00106                 float minDepth = 0.0f,
00107                 std::vector<int> * validIndices = 0), "Use cloudFromDepthRGB with CameraModel interface.");
00108 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromDepthRGB(
00109                 const cv::Mat & imageRgb,
00110                 const cv::Mat & imageDepth,
00111                 const CameraModel & model,
00112                 int decimation = 1,
00113                 float maxDepth = 0.0f,
00114                 float minDepth = 0.0f,
00115                 std::vector<int> * validIndices = 0);
00116 
00117 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromDisparity(
00118                 const cv::Mat & imageDisparity,
00119                 const StereoCameraModel & model,
00120                 int decimation = 1,
00121                 float maxDepth = 0.0f,
00122                 float minDepth = 0.0f,
00123                 std::vector<int> * validIndices = 0);
00124 
00125 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromDisparityRGB(
00126                 const cv::Mat & imageRgb,
00127                 const cv::Mat & imageDisparity,
00128                 const StereoCameraModel & model,
00129                 int decimation = 1,
00130                 float maxDepth = 0.0f,
00131                 float minDepth = 0.0f,
00132                 std::vector<int> * validIndices = 0);
00133 
00134 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromStereoImages(
00135                 const cv::Mat & imageLeft,
00136                 const cv::Mat & imageRight,
00137                 const StereoCameraModel & model,
00138                 int decimation = 1,
00139                 float maxDepth = 0.0f,
00140                 float minDepth = 0.0f,
00141                 std::vector<int> * validIndices = 0,
00142                 const ParametersMap & parameters = ParametersMap());
00143 
00144 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromSensorData(
00145                 const SensorData & sensorData,
00146                 int decimation = 1,
00147                 float maxDepth = 0.0f,
00148                 float minDepth = 0.0f,
00149                 std::vector<int> * validIndices = 0,
00150                 const ParametersMap & stereoParameters = ParametersMap(),
00151                 const std::vector<float> & roiRatios = std::vector<float>()); // ignored for stereo
00152 
00167 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudRGBFromSensorData(
00168                 const SensorData & sensorData,
00169                 int decimation = 1,
00170                 float maxDepth = 0.0f,
00171                 float minDepth = 0.0f,
00172                 std::vector<int> * validIndices = 0,
00173                 const ParametersMap & stereoParameters = ParametersMap(),
00174                 const std::vector<float> & roiRatios = std::vector<float>()); // ignored for stereo
00175 
00179 pcl::PointCloud<pcl::PointXYZ> RTABMAP_EXP laserScanFromDepthImage(
00180                                         const cv::Mat & depthImage,
00181                                         float fx,
00182                                         float fy,
00183                                         float cx,
00184                                         float cy,
00185                                         float maxDepth = 0,
00186                                         float minDepth = 0,
00187                                         const Transform & localTransform = Transform::getIdentity());
00193 pcl::PointCloud<pcl::PointXYZ> RTABMAP_EXP laserScanFromDepthImages(
00194                 const cv::Mat & depthImages,
00195                 const std::vector<CameraModel> & cameraModels,
00196                 float maxDepth,
00197                 float minDepth);
00198 
00199 LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PCLPointCloud2 & cloud, bool filterNaNs = true);
00200 // return CV_32FC3  (x,y,z)
00201 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
00202 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
00203 // return CV_32FC6 (x,y,z,normal_x,normal_y,normal_z)
00204 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointNormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
00205 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointNormal> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
00206 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
00207 // return CV_32FC4 (x,y,z,rgb)
00208 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGB> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
00209 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGB> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
00210 // return CV_32FC4 (x,y,z,I)
00211 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
00212 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
00213 // return CV_32FC7 (x,y,z,rgb,normal_x,normal_y,normal_z)
00214 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGB> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
00215 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
00216 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
00217 // return CV_32FC7 (x,y,z,I,normal_x,normal_y,normal_z)
00218 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
00219 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZINormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
00220 // return CV_32FC2  (x,y)
00221 cv::Mat RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
00222 // return CV_32FC3  (x,y,I)
00223 cv::Mat RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
00224 // return CV_32FC5  (x,y,normal_x, normal_y, normal_z)
00225 cv::Mat RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointNormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
00226 cv::Mat RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
00227 // return CV_32FC6  (x,y,I,normal_x, normal_y, normal_z)
00228 cv::Mat RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZINormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
00229 cv::Mat RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
00230 
00231 pcl::PCLPointCloud2::Ptr RTABMAP_EXP laserScanToPointCloud2(const LaserScan & laserScan, const Transform & transform = Transform());
00232 // For 2d laserScan, z is set to null.
00233 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP laserScanToPointCloud(const LaserScan & laserScan, const Transform & transform = Transform());
00234 // For laserScan without normals, normals are set to null.
00235 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP laserScanToPointCloudNormal(const LaserScan & laserScan, const Transform & transform = Transform());
00236 // For laserScan without rgb, rgb is set to default r,g,b parameters.
00237 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP laserScanToPointCloudRGB(const LaserScan & laserScan, const Transform & transform = Transform(), unsigned char r = 255, unsigned char g = 255, unsigned char b = 255);
00238 // For laserScan without intensity, intensity is set to intensity parameter.
00239 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP laserScanToPointCloudI(const LaserScan & laserScan, const Transform & transform = Transform(), float intensity = 0.0f);
00240 // For laserScan without rgb, rgb is set to default r,g,b parameters.
00241 // For laserScan without normals, normals are set to null.
00242 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP laserScanToPointCloudRGBNormal(const LaserScan & laserScan, const Transform & transform = Transform(), unsigned char r = 255, unsigned char g = 255, unsigned char b = 255);
00243 // For laserScan without intensity, intensity is set to default intensity parameter.
00244 // For laserScan without normals, normals are set to null.
00245 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP laserScanToPointCloudINormal(const LaserScan & laserScan, const Transform & transform = Transform(), float intensity = 0.0f);
00246 
00247 // For 2d laserScan, z is set to null.
00248 pcl::PointXYZ RTABMAP_EXP laserScanToPoint(const LaserScan & laserScan, int index);
00249 // For laserScan without normals, normals are set to null.
00250 pcl::PointNormal RTABMAP_EXP laserScanToPointNormal(const LaserScan & laserScan, int index);
00251 // For laserScan without rgb, rgb is set to default r,g,b parameters.
00252 pcl::PointXYZRGB RTABMAP_EXP laserScanToPointRGB(const LaserScan & laserScan, int index, unsigned char r = 255, unsigned char g = 255, unsigned char b = 255);
00253 // For laserScan without intensity, intensity is set to intensity parameter.
00254 pcl::PointXYZI RTABMAP_EXP laserScanToPointI(const LaserScan & laserScan, int index, float intensity);
00255 // For laserScan without rgb, rgb is set to default r,g,b parameters.
00256 // For laserScan without normals, normals are set to null.
00257 pcl::PointXYZRGBNormal RTABMAP_EXP laserScanToPointRGBNormal(const LaserScan & laserScan, int index, unsigned char r, unsigned char g, unsigned char b);
00258 // For laserScan without intensity, intensity is set to default intensity parameter.
00259 // For laserScan without normals, normals are set to null.
00260 pcl::PointXYZINormal RTABMAP_EXP laserScanToPointINormal(const LaserScan & laserScan, int index, float intensity);
00261 
00262 void RTABMAP_EXP getMinMax3D(const cv::Mat & laserScan, cv::Point3f & min, cv::Point3f & max);
00263 void RTABMAP_EXP getMinMax3D(const cv::Mat & laserScan, pcl::PointXYZ & min, pcl::PointXYZ & max);
00264 
00265 cv::Point3f RTABMAP_EXP projectDisparityTo3D(
00266                 const cv::Point2f & pt,
00267                 float disparity,
00268                 const StereoCameraModel & model);
00269 
00270 cv::Point3f RTABMAP_EXP projectDisparityTo3D(
00271                 const cv::Point2f & pt,
00272                 const cv::Mat & disparity,
00273                 const StereoCameraModel & model);
00274 
00275 // Register point cloud to camera (return registered depth image 32FC1)
00276 cv::Mat RTABMAP_EXP projectCloudToCamera(
00277                 const cv::Size & imageSize,
00278                 const cv::Mat & cameraMatrixK,  
00279                 const cv::Mat & laserScan,                   // assuming points are already in /base_link coordinate
00280                 const rtabmap::Transform & cameraTransform); // /base_link -> /camera_link
00281 
00282 // Register point cloud to camera (return registered depth image 32FC1)
00283 cv::Mat RTABMAP_EXP projectCloudToCamera(
00284                 const cv::Size & imageSize,
00285                 const cv::Mat & cameraMatrixK,
00286                 const pcl::PointCloud<pcl::PointXYZ>::Ptr laserScan, // assuming points are already in /base_link coordinate
00287                 const rtabmap::Transform & cameraTransform);         // /base_link -> /camera_link
00288 
00289 // Register point cloud to camera (return registered depth image 32FC1)
00290 cv::Mat RTABMAP_EXP projectCloudToCamera(
00291                 const cv::Size & imageSize,
00292                 const cv::Mat & cameraMatrixK,                       
00293                 const pcl::PCLPointCloud2::Ptr laserScan,                        // assuming points are already in /base_link coordinate
00294                 const rtabmap::Transform & cameraTransform);         // /base_link -> /camera_link
00295 
00296 // Direction vertical (>=0), horizontal (<0)
00297 void RTABMAP_EXP fillProjectedCloudHoles(
00298                 cv::Mat & depthRegistered,
00299                 bool verticalDirection,
00300                 bool fillToBorder);
00301 
00302 bool RTABMAP_EXP isFinite(const cv::Point3f & pt);
00303 
00304 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP concatenateClouds(
00305                 const std::list<pcl::PointCloud<pcl::PointXYZ>::Ptr> & clouds);
00306 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP concatenateClouds(
00307                 const std::list<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> & clouds);
00308 
00318 pcl::IndicesPtr RTABMAP_EXP concatenate(
00319                 const std::vector<pcl::IndicesPtr> & indices);
00320 
00331 pcl::IndicesPtr RTABMAP_EXP concatenate(
00332                 const pcl::IndicesPtr & indicesA,
00333                 const pcl::IndicesPtr & indicesB);
00334 
00335 void RTABMAP_EXP savePCDWords(
00336                 const std::string & fileName,
00337                 const std::multimap<int, pcl::PointXYZ> & words,
00338                 const Transform & transform = Transform::getIdentity());
00339 
00340 void RTABMAP_EXP savePCDWords(
00341                 const std::string & fileName,
00342                 const std::multimap<int, cv::Point3f> & words,
00343                 const Transform & transform = Transform::getIdentity());
00344 
00349 cv::Mat RTABMAP_EXP loadBINScan(const std::string & fileName);
00350 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP loadBINCloud(const std::string & fileName);
00351 RTABMAP_DEPRECATED(pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP loadBINCloud(const std::string & fileName, int dim), "Use interface without dim argument.");
00352 
00353 // Load *.pcd, *.ply or *.bin (KITTI format).
00354 LaserScan RTABMAP_EXP loadScan(const std::string & path);
00355 
00356 RTABMAP_DEPRECATED(pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP loadCloud(
00357                 const std::string & path,
00358                 const Transform & transform = Transform::getIdentity(),
00359                 int downsampleStep = 1,
00360                 float voxelSize = 0.0f), "Use loadScan() instead.");
00361 
00362 } // namespace util3d
00363 } // namespace rtabmap
00364 
00365 #endif /* UTIL3D_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:32