00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
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>());
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>());
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
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
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
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
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
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
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
00221 cv::Mat RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
00222
00223 cv::Mat RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
00224
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
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
00233 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP laserScanToPointCloud(const LaserScan & laserScan, const Transform & transform = Transform());
00234
00235 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP laserScanToPointCloudNormal(const LaserScan & laserScan, const Transform & transform = Transform());
00236
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
00239 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP laserScanToPointCloudI(const LaserScan & laserScan, const Transform & transform = Transform(), float intensity = 0.0f);
00240
00241
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
00244
00245 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP laserScanToPointCloudINormal(const LaserScan & laserScan, const Transform & transform = Transform(), float intensity = 0.0f);
00246
00247
00248 pcl::PointXYZ RTABMAP_EXP laserScanToPoint(const LaserScan & laserScan, int index);
00249
00250 pcl::PointNormal RTABMAP_EXP laserScanToPointNormal(const LaserScan & laserScan, int index);
00251
00252 pcl::PointXYZRGB RTABMAP_EXP laserScanToPointRGB(const LaserScan & laserScan, int index, unsigned char r = 255, unsigned char g = 255, unsigned char b = 255);
00253
00254 pcl::PointXYZI RTABMAP_EXP laserScanToPointI(const LaserScan & laserScan, int index, float intensity);
00255
00256
00257 pcl::PointXYZRGBNormal RTABMAP_EXP laserScanToPointRGBNormal(const LaserScan & laserScan, int index, unsigned char r, unsigned char g, unsigned char b);
00258
00259
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
00276 cv::Mat RTABMAP_EXP projectCloudToCamera(
00277 const cv::Size & imageSize,
00278 const cv::Mat & cameraMatrixK,
00279 const cv::Mat & laserScan,
00280 const rtabmap::Transform & cameraTransform);
00281
00282
00283 cv::Mat RTABMAP_EXP projectCloudToCamera(
00284 const cv::Size & imageSize,
00285 const cv::Mat & cameraMatrixK,
00286 const pcl::PointCloud<pcl::PointXYZ>::Ptr laserScan,
00287 const rtabmap::Transform & cameraTransform);
00288
00289
00290 cv::Mat RTABMAP_EXP projectCloudToCamera(
00291 const cv::Size & imageSize,
00292 const cv::Mat & cameraMatrixK,
00293 const pcl::PCLPointCloud2::Ptr laserScan,
00294 const rtabmap::Transform & cameraTransform);
00295
00296
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
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 }
00363 }
00364
00365 #endif