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 maxZError = 0.02f);
00076 
00077 RTABMAP_DEPRECATED (pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromDepth(
00078                 const cv::Mat & imageDepth,
00079                 float cx, float cy,
00080                 float fx, float fy,
00081                 int decimation = 1,
00082                 float maxDepth = 0.0f,
00083                 float minDepth = 0.0f,
00084                 std::vector<int> * validIndices = 0), "Use cloudFromDepth with CameraModel interface.");
00085 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromDepth(
00086                 const cv::Mat & imageDepth,
00087                 const CameraModel & model,
00088                 int decimation = 1,
00089                 float maxDepth = 0.0f,
00090                 float minDepth = 0.0f,
00091                 std::vector<int> * validIndices = 0);
00092 
00093 RTABMAP_DEPRECATED (pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromDepthRGB(
00094                 const cv::Mat & imageRgb,
00095                 const cv::Mat & imageDepth,
00096                 float cx, float cy,
00097                 float fx, float fy,
00098                 int decimation = 1,
00099                 float maxDepth = 0.0f,
00100                 float minDepth = 0.0f,
00101                 std::vector<int> * validIndices = 0), "Use cloudFromDepthRGB with CameraModel interface.");
00102 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromDepthRGB(
00103                 const cv::Mat & imageRgb,
00104                 const cv::Mat & imageDepth,
00105                 const CameraModel & model,
00106                 int decimation = 1,
00107                 float maxDepth = 0.0f,
00108                 float minDepth = 0.0f,
00109                 std::vector<int> * validIndices = 0);
00110 
00111 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromDisparity(
00112                 const cv::Mat & imageDisparity,
00113                 const StereoCameraModel & model,
00114                 int decimation = 1,
00115                 float maxDepth = 0.0f,
00116                 float minDepth = 0.0f,
00117                 std::vector<int> * validIndices = 0);
00118 
00119 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromDisparityRGB(
00120                 const cv::Mat & imageRgb,
00121                 const cv::Mat & imageDisparity,
00122                 const StereoCameraModel & model,
00123                 int decimation = 1,
00124                 float maxDepth = 0.0f,
00125                 float minDepth = 0.0f,
00126                 std::vector<int> * validIndices = 0);
00127 
00128 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromStereoImages(
00129                 const cv::Mat & imageLeft,
00130                 const cv::Mat & imageRight,
00131                 const StereoCameraModel & model,
00132                 int decimation = 1,
00133                 float maxDepth = 0.0f,
00134                 float minDepth = 0.0f,
00135                 std::vector<int> * validIndices = 0,
00136                 const ParametersMap & parameters = ParametersMap());
00137 
00138 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromSensorData(
00139                 const SensorData & sensorData,
00140                 int decimation = 1,
00141                 float maxDepth = 0.0f,
00142                 float minDepth = 0.0f,
00143                 std::vector<int> * validIndices = 0,
00144                 const ParametersMap & parameters = ParametersMap());
00145 
00159 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudRGBFromSensorData(
00160                 const SensorData & sensorData,
00161                 int decimation = 1,
00162                 float maxDepth = 0.0f,
00163                 float minDepth = 0.0f,
00164                 std::vector<int> * validIndices = 0,
00165                 const ParametersMap & parameters = ParametersMap());
00166 
00167 pcl::PointCloud<pcl::PointXYZ> RTABMAP_EXP laserScanFromDepthImage(
00168                                         const cv::Mat & depthImage,
00169                                         float fx,
00170                                         float fy,
00171                                         float cx,
00172                                         float cy,
00173                                         float maxDepth = 0,
00174                                         float minDepth = 0,
00175                                         const Transform & localTransform = Transform::getIdentity());
00176 
00177 // return CV_32FC3
00178 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const Transform & transform = Transform());
00179 // return CV_32FC6
00180 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointNormal> & cloud, const Transform & transform = Transform());
00181 // return CV_32FC2
00182 cv::Mat RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const Transform & transform = Transform());
00183 // For laserScan of type CV_32FC2, z is set to null.
00184 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP laserScanToPointCloud(const cv::Mat & laserScan, const Transform & transform = Transform());
00185 // For laserScan of type CV_32FC2 or CV_32FC3, normals are set to null.
00186 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP laserScanToPointCloudNormal(const cv::Mat & laserScan, const Transform & transform = Transform());
00187 
00188 cv::Point3f RTABMAP_EXP projectDisparityTo3D(
00189                 const cv::Point2f & pt,
00190                 float disparity,
00191                 const StereoCameraModel & model);
00192 
00193 cv::Point3f RTABMAP_EXP projectDisparityTo3D(
00194                 const cv::Point2f & pt,
00195                 const cv::Mat & disparity,
00196                 const StereoCameraModel & model);
00197 
00198 // Register point cloud to camera (return registered depth image)
00199 cv::Mat RTABMAP_EXP projectCloudToCamera(
00200                 const cv::Size & imageSize,
00201                 const cv::Mat & cameraMatrixK,  
00202                 const cv::Mat & laserScan,                   // assuming points are already in /base_link coordinate
00203                 const rtabmap::Transform & cameraTransform); // /base_link -> /camera_link
00204 
00205 // Register point cloud to camera (return registered depth image)
00206 cv::Mat RTABMAP_EXP projectCloudToCamera(
00207                 const cv::Size & imageSize,
00208                 const cv::Mat & cameraMatrixK,                       
00209                 const pcl::PointCloud<pcl::PointXYZ>::Ptr laserScan, // assuming points are already in /base_link coordinate
00210                 const rtabmap::Transform & cameraTransform);         // /base_link -> /camera_link
00211 
00212 // Direction vertical (>=0), horizontal (<0)
00213 void RTABMAP_EXP fillProjectedCloudHoles(
00214                 cv::Mat & depthRegistered,
00215                 bool verticalDirection,
00216                 bool fillToBorder);
00217 
00218 bool RTABMAP_EXP isFinite(const cv::Point3f & pt);
00219 
00220 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP concatenateClouds(
00221                 const std::list<pcl::PointCloud<pcl::PointXYZ>::Ptr> & clouds);
00222 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP concatenateClouds(
00223                 const std::list<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> & clouds);
00224 
00225 pcl::TextureMesh::Ptr RTABMAP_EXP concatenateTextureMeshes(
00226                 const std::list<pcl::TextureMesh::Ptr> & meshes);
00227 
00237 pcl::IndicesPtr RTABMAP_EXP concatenate(
00238                 const std::vector<pcl::IndicesPtr> & indices);
00239 
00250 pcl::IndicesPtr RTABMAP_EXP concatenate(
00251                 const pcl::IndicesPtr & indicesA,
00252                 const pcl::IndicesPtr & indicesB);
00253 
00254 void RTABMAP_EXP savePCDWords(
00255                 const std::string & fileName,
00256                 const std::multimap<int, pcl::PointXYZ> & words,
00257                 const Transform & transform = Transform::getIdentity());
00258 
00259 void RTABMAP_EXP savePCDWords(
00260                 const std::string & fileName,
00261                 const std::multimap<int, cv::Point3f> & words,
00262                 const Transform & transform = Transform::getIdentity());
00263 
00264 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP loadBINCloud(const std::string & fileName, int dim);
00265 
00266 // Load *.pcd, *.ply or *.bin (KITTI format) with optional filtering.
00267 // If normals are computed (normalsK>0), the returned scan type is CV_32FC6 instead of CV_32FC3
00268 cv::Mat RTABMAP_EXP loadScan(
00269                 const std::string & path,
00270                 const Transform & transform = Transform::getIdentity(),
00271                 int downsampleStep = 1,
00272                 float voxelSize = 0.0f,
00273                 int normalsK = 0);
00274 
00275 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP loadCloud(
00276                 const std::string & path,
00277                 const Transform & transform = Transform::getIdentity(),
00278                 int downsampleStep = 1,
00279                 float voxelSize = 0.0f);
00280 
00281 } // namespace util3d
00282 } // namespace rtabmap
00283 
00284 #endif /* UTIL3D_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:28