util3d.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef UTIL3D_H_
29 #define UTIL3D_H_
30 
32 
33 #include <pcl/point_cloud.h>
34 #include <pcl/point_types.h>
35 #include <pcl/pcl_base.h>
36 #include <pcl/TextureMesh.h>
37 #include <rtabmap/core/Transform.h>
40 #include <opencv2/core/core.hpp>
41 #include <map>
42 #include <list>
43 
44 namespace rtabmap
45 {
46 
47 namespace util3d
48 {
49 
51  const pcl::PointCloud<pcl::PointXYZRGBA> & cloud,
52  bool bgrOrder = true);
53 
55  const pcl::PointCloud<pcl::PointXYZRGBA> & cloud,
56  float & fx,
57  float & fy,
58  bool depth16U = true);
59 
61  const pcl::PointCloud<pcl::PointXYZRGBA> & cloud,
62  cv::Mat & rgb,
63  cv::Mat & depth,
64  float & fx,
65  float & fy,
66  bool bgrOrder = true,
67  bool depth16U = true);
68 
69 pcl::PointXYZ RTABMAP_EXP projectDepthTo3D(
70  const cv::Mat & depthImage,
71  float x, float y,
72  float cx, float cy,
73  float fx, float fy,
74  bool smoothing,
75  float depthErrorRatio = 0.02f);
76 
77 Eigen::Vector3f RTABMAP_EXP projectDepthTo3DRay(
78  const cv::Size & imageSize,
79  float x, float y,
80  float cx, float cy,
81  float fx, float fy);
82 
83 RTABMAP_DEPRECATED (pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromDepth(
84  const cv::Mat & imageDepth,
85  float cx, float cy,
86  float fx, float fy,
87  int decimation = 1,
88  float maxDepth = 0.0f,
89  float minDepth = 0.0f,
90  std::vector<int> * validIndices = 0), "Use cloudFromDepth with CameraModel interface.");
91 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromDepth(
92  const cv::Mat & imageDepth,
93  const CameraModel & model,
94  int decimation = 1,
95  float maxDepth = 0.0f,
96  float minDepth = 0.0f,
97  std::vector<int> * validIndices = 0);
98 
99 RTABMAP_DEPRECATED (pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromDepthRGB(
100  const cv::Mat & imageRgb,
101  const cv::Mat & imageDepth,
102  float cx, float cy,
103  float fx, float fy,
104  int decimation = 1,
105  float maxDepth = 0.0f,
106  float minDepth = 0.0f,
107  std::vector<int> * validIndices = 0), "Use cloudFromDepthRGB with CameraModel interface.");
108 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromDepthRGB(
109  const cv::Mat & imageRgb,
110  const cv::Mat & imageDepth,
111  const CameraModel & model,
112  int decimation = 1,
113  float maxDepth = 0.0f,
114  float minDepth = 0.0f,
115  std::vector<int> * validIndices = 0);
116 
117 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromDisparity(
118  const cv::Mat & imageDisparity,
119  const StereoCameraModel & model,
120  int decimation = 1,
121  float maxDepth = 0.0f,
122  float minDepth = 0.0f,
123  std::vector<int> * validIndices = 0);
124 
125 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromDisparityRGB(
126  const cv::Mat & imageRgb,
127  const cv::Mat & imageDisparity,
128  const StereoCameraModel & model,
129  int decimation = 1,
130  float maxDepth = 0.0f,
131  float minDepth = 0.0f,
132  std::vector<int> * validIndices = 0);
133 
134 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromStereoImages(
135  const cv::Mat & imageLeft,
136  const cv::Mat & imageRight,
137  const StereoCameraModel & model,
138  int decimation = 1,
139  float maxDepth = 0.0f,
140  float minDepth = 0.0f,
141  std::vector<int> * validIndices = 0,
142  const ParametersMap & parameters = ParametersMap());
143 
144 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromSensorData(
145  const SensorData & sensorData,
146  int decimation = 1,
147  float maxDepth = 0.0f,
148  float minDepth = 0.0f,
149  std::vector<int> * validIndices = 0,
150  const ParametersMap & stereoParameters = ParametersMap(),
151  const std::vector<float> & roiRatios = std::vector<float>()); // ignored for stereo
152 
167 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudRGBFromSensorData(
168  const SensorData & sensorData,
169  int decimation = 1,
170  float maxDepth = 0.0f,
171  float minDepth = 0.0f,
172  std::vector<int> * validIndices = 0,
173  const ParametersMap & stereoParameters = ParametersMap(),
174  const std::vector<float> & roiRatios = std::vector<float>()); // ignored for stereo
175 
179 pcl::PointCloud<pcl::PointXYZ> RTABMAP_EXP laserScanFromDepthImage(
180  const cv::Mat & depthImage,
181  float fx,
182  float fy,
183  float cx,
184  float cy,
185  float maxDepth = 0,
186  float minDepth = 0,
187  const Transform & localTransform = Transform::getIdentity());
193 pcl::PointCloud<pcl::PointXYZ> RTABMAP_EXP laserScanFromDepthImages(
194  const cv::Mat & depthImages,
195  const std::vector<CameraModel> & cameraModels,
196  float maxDepth,
197  float minDepth);
198 
199 LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PCLPointCloud2 & cloud, bool filterNaNs = true);
200 // return CV_32FC3 (x,y,z)
201 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
202 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
203 // return CV_32FC6 (x,y,z,normal_x,normal_y,normal_z)
204 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointNormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
205 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointNormal> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
206 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
207 // return CV_32FC4 (x,y,z,rgb)
208 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGB> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
209 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGB> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
210 // return CV_32FC4 (x,y,z,I)
211 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
212 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
213 // return CV_32FC7 (x,y,z,rgb,normal_x,normal_y,normal_z)
214 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGB> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
215 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
216 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
217 // return CV_32FC7 (x,y,z,I,normal_x,normal_y,normal_z)
218 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
219 cv::Mat RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZINormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
220 // return CV_32FC2 (x,y)
221 cv::Mat RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
222 // return CV_32FC3 (x,y,I)
223 cv::Mat RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
224 // return CV_32FC5 (x,y,normal_x, normal_y, normal_z)
225 cv::Mat RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointNormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
226 cv::Mat RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
227 // return CV_32FC6 (x,y,I,normal_x, normal_y, normal_z)
228 cv::Mat RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZINormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
229 cv::Mat RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
230 
231 pcl::PCLPointCloud2::Ptr RTABMAP_EXP laserScanToPointCloud2(const LaserScan & laserScan, const Transform & transform = Transform());
232 // For 2d laserScan, z is set to null.
233 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP laserScanToPointCloud(const LaserScan & laserScan, const Transform & transform = Transform());
234 // For laserScan without normals, normals are set to null.
235 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP laserScanToPointCloudNormal(const LaserScan & laserScan, const Transform & transform = Transform());
236 // For laserScan without rgb, rgb is set to default r,g,b parameters.
237 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);
238 // For laserScan without intensity, intensity is set to intensity parameter.
239 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP laserScanToPointCloudI(const LaserScan & laserScan, const Transform & transform = Transform(), float intensity = 0.0f);
240 // For laserScan without rgb, rgb is set to default r,g,b parameters.
241 // For laserScan without normals, normals are set to null.
242 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);
243 // For laserScan without intensity, intensity is set to default intensity parameter.
244 // For laserScan without normals, normals are set to null.
245 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP laserScanToPointCloudINormal(const LaserScan & laserScan, const Transform & transform = Transform(), float intensity = 0.0f);
246 
247 // For 2d laserScan, z is set to null.
248 pcl::PointXYZ RTABMAP_EXP laserScanToPoint(const LaserScan & laserScan, int index);
249 // For laserScan without normals, normals are set to null.
250 pcl::PointNormal RTABMAP_EXP laserScanToPointNormal(const LaserScan & laserScan, int index);
251 // For laserScan without rgb, rgb is set to default r,g,b parameters.
252 pcl::PointXYZRGB RTABMAP_EXP laserScanToPointRGB(const LaserScan & laserScan, int index, unsigned char r = 255, unsigned char g = 255, unsigned char b = 255);
253 // For laserScan without intensity, intensity is set to intensity parameter.
254 pcl::PointXYZI RTABMAP_EXP laserScanToPointI(const LaserScan & laserScan, int index, float intensity);
255 // For laserScan without rgb, rgb is set to default r,g,b parameters.
256 // For laserScan without normals, normals are set to null.
257 pcl::PointXYZRGBNormal RTABMAP_EXP laserScanToPointRGBNormal(const LaserScan & laserScan, int index, unsigned char r, unsigned char g, unsigned char b);
258 // For laserScan without intensity, intensity is set to default intensity parameter.
259 // For laserScan without normals, normals are set to null.
260 pcl::PointXYZINormal RTABMAP_EXP laserScanToPointINormal(const LaserScan & laserScan, int index, float intensity);
261 
262 void RTABMAP_EXP getMinMax3D(const cv::Mat & laserScan, cv::Point3f & min, cv::Point3f & max);
263 void RTABMAP_EXP getMinMax3D(const cv::Mat & laserScan, pcl::PointXYZ & min, pcl::PointXYZ & max);
264 
266  const cv::Point2f & pt,
267  float disparity,
268  const StereoCameraModel & model);
269 
271  const cv::Point2f & pt,
272  const cv::Mat & disparity,
273  const StereoCameraModel & model);
274 
275 // Register point cloud to camera (return registered depth image 32FC1)
277  const cv::Size & imageSize,
278  const cv::Mat & cameraMatrixK,
279  const cv::Mat & laserScan, // assuming points are already in /base_link coordinate
280  const rtabmap::Transform & cameraTransform); // /base_link -> /camera_link
281 
282 // Register point cloud to camera (return registered depth image 32FC1)
284  const cv::Size & imageSize,
285  const cv::Mat & cameraMatrixK,
286  const pcl::PointCloud<pcl::PointXYZ>::Ptr laserScan, // assuming points are already in /base_link coordinate
287  const rtabmap::Transform & cameraTransform); // /base_link -> /camera_link
288 
289 // Register point cloud to camera (return registered depth image 32FC1)
291  const cv::Size & imageSize,
292  const cv::Mat & cameraMatrixK,
293  const pcl::PCLPointCloud2::Ptr laserScan, // assuming points are already in /base_link coordinate
294  const rtabmap::Transform & cameraTransform); // /base_link -> /camera_link
295 
296 // Direction vertical (>=0), horizontal (<0)
298  cv::Mat & depthRegistered,
299  bool verticalDirection,
300  bool fillToBorder);
301 
302 bool RTABMAP_EXP isFinite(const cv::Point3f & pt);
303 
304 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP concatenateClouds(
305  const std::list<pcl::PointCloud<pcl::PointXYZ>::Ptr> & clouds);
306 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP concatenateClouds(
307  const std::list<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> & clouds);
308 
318 pcl::IndicesPtr RTABMAP_EXP concatenate(
319  const std::vector<pcl::IndicesPtr> & indices);
320 
331 pcl::IndicesPtr RTABMAP_EXP concatenate(
332  const pcl::IndicesPtr & indicesA,
333  const pcl::IndicesPtr & indicesB);
334 
336  const std::string & fileName,
337  const std::multimap<int, pcl::PointXYZ> & words,
338  const Transform & transform = Transform::getIdentity());
339 
341  const std::string & fileName,
342  const std::multimap<int, cv::Point3f> & words,
343  const Transform & transform = Transform::getIdentity());
344 
349 cv::Mat RTABMAP_EXP loadBINScan(const std::string & fileName);
350 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP loadBINCloud(const std::string & fileName);
351 RTABMAP_DEPRECATED(pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP loadBINCloud(const std::string & fileName, int dim), "Use interface without dim argument.");
352 
353 // Load *.pcd, *.ply or *.bin (KITTI format).
354 LaserScan RTABMAP_EXP loadScan(const std::string & path);
355 
356 RTABMAP_DEPRECATED(pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP loadCloud(
357  const std::string & path,
358  const Transform & transform = Transform::getIdentity(),
359  int downsampleStep = 1,
360  float voxelSize = 0.0f), "Use loadScan() instead.");
361 
362 } // namespace util3d
363 } // namespace rtabmap
364 
365 #endif /* UTIL3D_H_ */
LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PCLPointCloud2 &cloud, bool filterNaNs=true)
Definition: util3d.cpp:1266
bool RTABMAP_EXP isFinite(const cv::Point3f &pt)
Definition: util3d.cpp:3035
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP cloudFromDisparity(const cv::Mat &imageDisparity, const StereoCameraModel &model, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0)
Definition: util3d.cpp:610
pcl::PointNormal RTABMAP_EXP laserScanToPointNormal(const LaserScan &laserScan, int index)
Definition: util3d.cpp:2447
cv::Point3f RTABMAP_EXP projectDisparityTo3D(const cv::Point2f &pt, float disparity, const StereoCameraModel &model)
Definition: util3d.cpp:2633
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
void RTABMAP_EXP getMinMax3D(const cv::Mat &laserScan, cv::Point3f &min, cv::Point3f &max)
Definition: util3d.cpp:2593
static Transform getIdentity()
Definition: Transform.cpp:364
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)
Definition: util3d.cpp:2399
pcl::PointXYZINormal RTABMAP_EXP laserScanToPointINormal(const LaserScan &laserScan, int index, float intensity)
Definition: util3d.cpp:2560
pcl::PCLPointCloud2::Ptr RTABMAP_EXP laserScanToPointCloud2(const LaserScan &laserScan, const Transform &transform=Transform())
Definition: util3d.cpp:2289
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:41
pcl::PointXYZ RTABMAP_EXP laserScanToPoint(const LaserScan &laserScan, int index)
Definition: util3d.cpp:2433
void RTABMAP_EXP savePCDWords(const std::string &fileName, const std::multimap< int, pcl::PointXYZ > &words, const Transform &transform=Transform::getIdentity())
Definition: util3d.cpp:3092
pcl::PointXYZRGBNormal RTABMAP_EXP laserScanToPointRGBNormal(const LaserScan &laserScan, int index, unsigned char r, unsigned char g, unsigned char b)
Definition: util3d.cpp:2522
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP laserScanToPointCloud(const LaserScan &laserScan, const Transform &transform=Transform())
Definition: util3d.cpp:2328
pcl::PointCloud< pcl::PointXYZ > RTABMAP_EXP laserScanFromDepthImages(const cv::Mat &depthImages, const std::vector< CameraModel > &cameraModels, float maxDepth, float minDepth)
Definition: util3d.cpp:1233
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP cloudFromDepth(const cv::Mat &imageDepth, const CameraModel &model, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0)
Definition: util3d.cpp:277
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP cloudFromDepthRGB(const cv::Mat &imageRgb, const cv::Mat &imageDepth, const CameraModel &model, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0)
Definition: util3d.cpp:428
cv::Mat RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud< pcl::PointXYZ > &cloud, const Transform &transform=Transform(), bool filterNaNs=true)
Definition: util3d.cpp:2051
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
pcl::PointXYZ RTABMAP_EXP projectDepthTo3D(const cv::Mat &depthImage, float x, float y, float cx, float cy, float fx, float fy, bool smoothing, float depthErrorRatio=0.02f)
Definition: util3d.cpp:213
RTABMAP_DEPRECATED(pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP cloudFromDepth(const cv::Mat &imageDepth, float cx, float cy, float fx, float fy, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0),"Use cloudFromDepth with CameraModel interface.")
pcl::PointCloud< pcl::PointXYZINormal >::Ptr RTABMAP_EXP laserScanToPointCloudINormal(const LaserScan &laserScan, const Transform &transform=Transform(), float intensity=0.0f)
Definition: util3d.cpp:2416
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP cloudRGBFromSensorData(const SensorData &sensorData, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap &stereoParameters=ParametersMap(), const std::vector< float > &roiRatios=std::vector< float >())
Definition: util3d.cpp:1031
pcl::PointXYZRGB RTABMAP_EXP laserScanToPointRGB(const LaserScan &laserScan, int index, unsigned char r=255, unsigned char g=255, unsigned char b=255)
Definition: util3d.cpp:2468
pcl::PointCloud< pcl::PointXYZ > RTABMAP_EXP laserScanFromDepthImage(const cv::Mat &depthImage, float fx, float fy, float cx, float cy, float maxDepth=0, float minDepth=0, const Transform &localTransform=Transform::getIdentity())
Definition: util3d.cpp:1197
pcl::PointXYZI RTABMAP_EXP laserScanToPointI(const LaserScan &laserScan, int index, float intensity)
Definition: util3d.cpp:2497
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP cloudFromSensorData(const SensorData &sensorData, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap &stereoParameters=ParametersMap(), const std::vector< float > &roiRatios=std::vector< float >())
Definition: util3d.cpp:852
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
Eigen::Vector3f RTABMAP_EXP projectDepthTo3DRay(const cv::Size &imageSize, float x, float y, float cx, float cy, float fx, float fy)
Definition: util3d.cpp:244
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_EXP laserScanToPointCloudNormal(const LaserScan &laserScan, const Transform &transform=Transform())
Definition: util3d.cpp:2346
void RTABMAP_EXP fillProjectedCloudHoles(cv::Mat &depthRegistered, bool verticalDirection, bool fillToBorder)
Definition: util3d.cpp:2952
cv::Mat RTABMAP_EXP projectCloudToCamera(const cv::Size &imageSize, const cv::Mat &cameraMatrixK, const cv::Mat &laserScan, const rtabmap::Transform &cameraTransform)
Definition: util3d.cpp:2672
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP loadBINCloud(const std::string &fileName)
Definition: util3d.cpp:3152
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP cloudFromStereoImages(const cv::Mat &imageLeft, const cv::Mat &imageRight, const StereoCameraModel &model, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap &parameters=ParametersMap())
Definition: util3d.cpp:812
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_EXP laserScanToPointCloudI(const LaserScan &laserScan, const Transform &transform=Transform(), float intensity=0.0f)
Definition: util3d.cpp:2381
pcl::IndicesPtr RTABMAP_EXP concatenate(const std::vector< pcl::IndicesPtr > &indices)
Concatenate a vector of indices to a single vector.
Definition: util3d.cpp:3060
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP cloudFromDisparityRGB(const cv::Mat &imageRgb, const cv::Mat &imageDisparity, const StereoCameraModel &model, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0)
Definition: util3d.cpp:711
LaserScan RTABMAP_EXP loadScan(const std::string &path)
Definition: util3d.cpp:3162
pcl::PointCloud< pcl::PointXYZ >::Ptr loadCloud(const std::string &path, const Transform &transform, int downsampleStep, float voxelSize)
Definition: util3d.cpp:3184
void RTABMAP_EXP rgbdFromCloud(const pcl::PointCloud< pcl::PointXYZRGBA > &cloud, cv::Mat &rgb, cv::Mat &depth, float &fx, float &fy, bool bgrOrder=true, bool depth16U=true)
Definition: util3d.cpp:136
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)
Definition: util3d.cpp:2363
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP concatenateClouds(const std::list< pcl::PointCloud< pcl::PointXYZ >::Ptr > &clouds)
Definition: util3d.cpp:3040
cv::Mat RTABMAP_EXP depthFromCloud(const pcl::PointCloud< pcl::PointXYZRGBA > &cloud, float &fx, float &fy, bool depth16U=true)
Definition: util3d.cpp:76
cv::Mat RTABMAP_EXP rgbFromCloud(const pcl::PointCloud< pcl::PointXYZRGBA > &cloud, bool bgrOrder=true)
cv::Mat RTABMAP_EXP loadBINScan(const std::string &fileName)
Definition: util3d.cpp:3129


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:43:40