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>
42 #include <map>
43 #include <list>
44 
45 namespace rtabmap
46 {
47 
48 namespace util3d
49 {
50 
52  const pcl::PointCloud<pcl::PointXYZRGBA> & cloud,
53  bool bgrOrder = true);
54 
56  const pcl::PointCloud<pcl::PointXYZRGBA> & cloud,
57  float & fx,
58  float & fy,
59  bool depth16U = true);
60 
62  const pcl::PointCloud<pcl::PointXYZRGBA> & cloud,
63  cv::Mat & rgb,
64  cv::Mat & depth,
65  float & fx,
66  float & fy,
67  bool bgrOrder = true,
68  bool depth16U = true);
69 
70 pcl::PointXYZ RTABMAP_EXP projectDepthTo3D(
71  const cv::Mat & depthImage,
72  float x, float y,
73  float cx, float cy,
74  float fx, float fy,
75  bool smoothing,
76  float depthErrorRatio = 0.02f);
77 
78 Eigen::Vector3f RTABMAP_EXP projectDepthTo3DRay(
79  const cv::Size & imageSize,
80  float x, float y,
81  float cx, float cy,
82  float fx, float fy);
83 
84 RTABMAP_DEPRECATED (pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromDepth(
85  const cv::Mat & imageDepth,
86  float cx, float cy,
87  float fx, float fy,
88  int decimation = 1,
89  float maxDepth = 0.0f,
90  float minDepth = 0.0f,
91  std::vector<int> * validIndices = 0), "Use cloudFromDepth with CameraModel interface.");
92 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromDepth(
93  const cv::Mat & imageDepth,
94  const CameraModel & model,
95  int decimation = 1,
96  float maxDepth = 0.0f,
97  float minDepth = 0.0f,
98  std::vector<int> * validIndices = 0);
99 
100 RTABMAP_DEPRECATED (pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromDepthRGB(
101  const cv::Mat & imageRgb,
102  const cv::Mat & imageDepth,
103  float cx, float cy,
104  float fx, float fy,
105  int decimation = 1,
106  float maxDepth = 0.0f,
107  float minDepth = 0.0f,
108  std::vector<int> * validIndices = 0), "Use cloudFromDepthRGB with CameraModel interface.");
109 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromDepthRGB(
110  const cv::Mat & imageRgb,
111  const cv::Mat & imageDepth,
112  const CameraModel & model,
113  int decimation = 1,
114  float maxDepth = 0.0f,
115  float minDepth = 0.0f,
116  std::vector<int> * validIndices = 0);
117 
118 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromDisparity(
119  const cv::Mat & imageDisparity,
120  const StereoCameraModel & model,
121  int decimation = 1,
122  float maxDepth = 0.0f,
123  float minDepth = 0.0f,
124  std::vector<int> * validIndices = 0);
125 
126 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromDisparityRGB(
127  const cv::Mat & imageRgb,
128  const cv::Mat & imageDisparity,
129  const StereoCameraModel & model,
130  int decimation = 1,
131  float maxDepth = 0.0f,
132  float minDepth = 0.0f,
133  std::vector<int> * validIndices = 0);
134 
135 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromStereoImages(
136  const cv::Mat & imageLeft,
137  const cv::Mat & imageRight,
138  const StereoCameraModel & model,
139  int decimation = 1,
140  float maxDepth = 0.0f,
141  float minDepth = 0.0f,
142  std::vector<int> * validIndices = 0,
143  const ParametersMap & parameters = ParametersMap());
144 
145 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromSensorData(
146  const SensorData & sensorData,
147  int decimation = 1,
148  float maxDepth = 0.0f,
149  float minDepth = 0.0f,
150  std::vector<int> * validIndices = 0,
151  const ParametersMap & stereoParameters = ParametersMap(),
152  const std::vector<float> & roiRatios = std::vector<float>()); // ignored for stereo
153 
168 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudRGBFromSensorData(
169  const SensorData & sensorData,
170  int decimation = 1,
171  float maxDepth = 0.0f,
172  float minDepth = 0.0f,
173  std::vector<int> * validIndices = 0,
174  const ParametersMap & stereoParameters = ParametersMap(),
175  const std::vector<float> & roiRatios = std::vector<float>()); // ignored for stereo
176 
180 pcl::PointCloud<pcl::PointXYZ> RTABMAP_EXP laserScanFromDepthImage(
181  const cv::Mat & depthImage,
182  float fx,
183  float fy,
184  float cx,
185  float cy,
186  float maxDepth = 0,
187  float minDepth = 0,
188  const Transform & localTransform = Transform::getIdentity());
194 pcl::PointCloud<pcl::PointXYZ> RTABMAP_EXP laserScanFromDepthImages(
195  const cv::Mat & depthImages,
196  const std::vector<CameraModel> & cameraModels,
197  float maxDepth,
198  float minDepth);
199 
200 template<typename PointCloud2T>
201 LaserScan laserScanFromPointCloud(const PointCloud2T & cloud, bool filterNaNs = true, bool is2D = false, const Transform & transform = Transform());
202 // return CV_32FC3 (x,y,z)
203 LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
204 LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
205 // return CV_32FC6 (x,y,z,normal_x,normal_y,normal_z)
206 LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointNormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
207 LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointNormal> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
208 LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
209 // return CV_32FC4 (x,y,z,rgb)
210 LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGB> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
211 LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGB> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
212 // return CV_32FC4 (x,y,z,I)
213 LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
214 LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
215 // return CV_32FC7 (x,y,z,rgb,normal_x,normal_y,normal_z)
216 LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGB> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
217 LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
218 LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
219 // return CV_32FC7 (x,y,z,I,normal_x,normal_y,normal_z)
220 LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
221 LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZINormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
222 LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZINormal> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
223 // return CV_32FC2 (x,y)
224 LaserScan RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
225 // return CV_32FC3 (x,y,I)
226 LaserScan RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
227 // return CV_32FC5 (x,y,normal_x, normal_y, normal_z)
228 LaserScan RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointNormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
229 LaserScan RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
230 // return CV_32FC6 (x,y,I,normal_x, normal_y, normal_z)
231 LaserScan RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZINormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
232 LaserScan RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
233 
234 pcl::PCLPointCloud2::Ptr RTABMAP_EXP laserScanToPointCloud2(const LaserScan & laserScan, const Transform & transform = Transform());
235 // For 2d laserScan, z is set to null.
236 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP laserScanToPointCloud(const LaserScan & laserScan, const Transform & transform = Transform());
237 // For laserScan without normals, normals are set to null.
238 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP laserScanToPointCloudNormal(const LaserScan & laserScan, const Transform & transform = Transform());
239 // For laserScan without rgb, rgb is set to default r,g,b parameters.
240 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP laserScanToPointCloudRGB(const LaserScan & laserScan, const Transform & transform = Transform(), unsigned char r = 100, unsigned char g = 100, unsigned char b = 100);
241 // For laserScan without intensity, intensity is set to intensity parameter.
242 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP laserScanToPointCloudI(const LaserScan & laserScan, const Transform & transform = Transform(), float intensity = 0.0f);
243 // For laserScan without rgb, rgb is set to default r,g,b parameters.
244 // For laserScan without normals, normals are set to null.
245 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP laserScanToPointCloudRGBNormal(const LaserScan & laserScan, const Transform & transform = Transform(), unsigned char r = 100, unsigned char g = 100, unsigned char b = 100);
246 // For laserScan without intensity, intensity is set to default intensity parameter.
247 // For laserScan without normals, normals are set to null.
248 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP laserScanToPointCloudINormal(const LaserScan & laserScan, const Transform & transform = Transform(), float intensity = 0.0f);
249 
250 // For 2d laserScan, z is set to null.
251 pcl::PointXYZ RTABMAP_EXP laserScanToPoint(const LaserScan & laserScan, int index);
252 // For laserScan without normals, normals are set to null.
253 pcl::PointNormal RTABMAP_EXP laserScanToPointNormal(const LaserScan & laserScan, int index);
254 // For laserScan without rgb, rgb is set to default r,g,b parameters.
255 pcl::PointXYZRGB RTABMAP_EXP laserScanToPointRGB(const LaserScan & laserScan, int index, unsigned char r = 100, unsigned char g = 100, unsigned char b = 100);
256 // For laserScan without intensity, intensity is set to intensity parameter.
257 pcl::PointXYZI RTABMAP_EXP laserScanToPointI(const LaserScan & laserScan, int index, float intensity);
258 // For laserScan without rgb, rgb is set to default r,g,b parameters.
259 // For laserScan without normals, normals are set to null.
260 pcl::PointXYZRGBNormal RTABMAP_EXP laserScanToPointRGBNormal(const LaserScan & laserScan, int index, unsigned char r, unsigned char g, unsigned char b);
261 // For laserScan without intensity, intensity is set to default intensity parameter.
262 // For laserScan without normals, normals are set to null.
263 pcl::PointXYZINormal RTABMAP_EXP laserScanToPointINormal(const LaserScan & laserScan, int index, float intensity);
264 
265 void RTABMAP_EXP getMinMax3D(const cv::Mat & laserScan, cv::Point3f & min, cv::Point3f & max);
266 void RTABMAP_EXP getMinMax3D(const cv::Mat & laserScan, pcl::PointXYZ & min, pcl::PointXYZ & max);
267 
269  const cv::Point2f & pt,
270  float disparity,
271  const StereoCameraModel & model);
272 
274  const cv::Point2f & pt,
275  const cv::Mat & disparity,
276  const StereoCameraModel & model);
277 
278 // Register point cloud to camera (return registered depth image 32FC1)
280  const cv::Size & imageSize,
281  const cv::Mat & cameraMatrixK,
282  const cv::Mat & laserScan, // assuming points are already in /base_link coordinate
283  const rtabmap::Transform & cameraTransform); // /base_link -> /camera_link
284 
285 // Register point cloud to camera (return registered depth image 32FC1)
287  const cv::Size & imageSize,
288  const cv::Mat & cameraMatrixK,
289  const pcl::PointCloud<pcl::PointXYZ>::Ptr laserScan, // assuming points are already in /base_link coordinate
290  const rtabmap::Transform & cameraTransform); // /base_link -> /camera_link
291 
292 // Register point cloud to camera (return registered depth image 32FC1)
294  const cv::Size & imageSize,
295  const cv::Mat & cameraMatrixK,
296  const pcl::PCLPointCloud2::Ptr laserScan, // assuming points are already in /base_link coordinate
297  const rtabmap::Transform & cameraTransform); // /base_link -> /camera_link
298 
299 // Direction vertical (>=0), horizontal (<0)
301  cv::Mat & depthRegistered,
302  bool verticalDirection,
303  bool fillToBorder);
304 
309 std::vector<std::pair< std::pair<int, int>, pcl::PointXY> > RTABMAP_EXP projectCloudToCameras (
310  const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud,
311  const std::map<int, Transform> & cameraPoses,
312  const std::map<int, std::vector<CameraModel> > & cameraModels,
313  float maxDistance = 0.0f,
314  float maxAngle = 0.0f,
315  const std::vector<float> & roiRatios = std::vector<float>(),
316  const cv::Mat & projMask = cv::Mat(),
317  bool distanceToCamPolicy = false,
318  const ProgressState * state = 0);
323 std::vector<std::pair< std::pair<int, int>, pcl::PointXY> > RTABMAP_EXP projectCloudToCameras (
324  const pcl::PointCloud<pcl::PointXYZINormal> & cloud,
325  const std::map<int, Transform> & cameraPoses,
326  const std::map<int, std::vector<CameraModel> > & cameraModels,
327  float maxDistance = 0.0f,
328  float maxAngle = 0.0f,
329  const std::vector<float> & roiRatios = std::vector<float>(),
330  const cv::Mat & projMask = cv::Mat(),
331  bool distanceToCamPolicy = false,
332  const ProgressState * state = 0);
333 
334 bool RTABMAP_EXP isFinite(const cv::Point3f & pt);
335 
336 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP concatenateClouds(
337  const std::list<pcl::PointCloud<pcl::PointXYZ>::Ptr> & clouds);
338 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP concatenateClouds(
339  const std::list<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> & clouds);
340 
350 pcl::IndicesPtr RTABMAP_EXP concatenate(
351  const std::vector<pcl::IndicesPtr> & indices);
352 
363 pcl::IndicesPtr RTABMAP_EXP concatenate(
364  const pcl::IndicesPtr & indicesA,
365  const pcl::IndicesPtr & indicesB);
366 
368  const std::string & fileName,
369  const std::multimap<int, pcl::PointXYZ> & words,
370  const Transform & transform = Transform::getIdentity());
371 
373  const std::string & fileName,
374  const std::multimap<int, cv::Point3f> & words,
375  const Transform & transform = Transform::getIdentity());
376 
381 cv::Mat RTABMAP_EXP loadBINScan(const std::string & fileName);
382 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP loadBINCloud(const std::string & fileName);
383 RTABMAP_DEPRECATED(pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP loadBINCloud(const std::string & fileName, int dim), "Use interface without dim argument.");
384 
385 // Load *.pcd, *.ply or *.bin (KITTI format).
386 LaserScan RTABMAP_EXP loadScan(const std::string & path);
387 
388 RTABMAP_DEPRECATED(pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP loadCloud(
389  const std::string & path,
390  const Transform & transform = Transform::getIdentity(),
391  int downsampleStep = 1,
392  float voxelSize = 0.0f), "Use loadScan() instead.");
393 
394 } // namespace util3d
395 } // namespace rtabmap
396 
398 
399 #endif /* UTIL3D_H_ */
bool RTABMAP_EXP isFinite(const cv::Point3f &pt)
Definition: util3d.cpp:3194
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:611
pcl::PointNormal RTABMAP_EXP laserScanToPointNormal(const LaserScan &laserScan, int index)
Definition: util3d.cpp:2316
cv::Point3f RTABMAP_EXP projectDisparityTo3D(const cv::Point2f &pt, float disparity, const StereoCameraModel &model)
Definition: util3d.cpp:2521
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:2481
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_EXP laserScanToPointCloudRGBNormal(const LaserScan &laserScan, const Transform &transform=Transform(), unsigned char r=100, unsigned char g=100, unsigned char b=100)
Definition: util3d.cpp:2268
static Transform getIdentity()
Definition: Transform.cpp:401
pcl::PointXYZINormal RTABMAP_EXP laserScanToPointINormal(const LaserScan &laserScan, int index, float intensity)
Definition: util3d.cpp:2448
pcl::PCLPointCloud2::Ptr RTABMAP_EXP laserScanToPointCloud2(const LaserScan &laserScan, const Transform &transform=Transform())
Definition: util3d.cpp:2158
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
pcl::PointXYZ RTABMAP_EXP laserScanToPoint(const LaserScan &laserScan, int index)
Definition: util3d.cpp:2302
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.")
void RTABMAP_EXP savePCDWords(const std::string &fileName, const std::multimap< int, pcl::PointXYZ > &words, const Transform &transform=Transform::getIdentity())
Definition: util3d.cpp:3251
pcl::PointXYZRGBNormal RTABMAP_EXP laserScanToPointRGBNormal(const LaserScan &laserScan, int index, unsigned char r, unsigned char g, unsigned char b)
Definition: util3d.cpp:2401
pcl::PointXYZRGB RTABMAP_EXP laserScanToPointRGB(const LaserScan &laserScan, int index, unsigned char r=100, unsigned char g=100, unsigned char b=100)
Definition: util3d.cpp:2337
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP laserScanToPointCloud(const LaserScan &laserScan, const Transform &transform=Transform())
Definition: util3d.cpp:2197
pcl::PointCloud< pcl::PointXYZ > RTABMAP_EXP laserScanFromDepthImages(const cv::Mat &depthImages, const std::vector< CameraModel > &cameraModels, float maxDepth, float minDepth)
Definition: util3d.cpp:1285
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:278
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:429
#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:214
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP laserScanToPointCloudRGB(const LaserScan &laserScan, const Transform &transform=Transform(), unsigned char r=100, unsigned char g=100, unsigned char b=100)
Definition: util3d.cpp:2232
pcl::PointCloud< pcl::PointXYZINormal >::Ptr RTABMAP_EXP laserScanToPointCloudINormal(const LaserScan &laserScan, const Transform &transform=Transform(), float intensity=0.0f)
Definition: util3d.cpp:2285
std::vector< std::pair< std::pair< int, int >, pcl::PointXY > > RTABMAP_EXP projectCloudToCameras(const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloud, const std::map< int, Transform > &cameraPoses, const std::map< int, std::vector< CameraModel > > &cameraModels, float maxDistance=0.0f, float maxAngle=0.0f, const std::vector< float > &roiRatios=std::vector< float >(), const cv::Mat &projMask=cv::Mat(), bool distanceToCamPolicy=false, const ProgressState *state=0)
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:1056
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:1249
LaserScan laserScanFromPointCloud(const PointCloud2T &cloud, bool filterNaNs, bool is2D, const Transform &transform)
Definition: util3d.hpp:37
pcl::PointXYZI RTABMAP_EXP laserScanToPointI(const LaserScan &laserScan, int index, float intensity)
Definition: util3d.cpp:2376
RecoveryProgressState state
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:853
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:245
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_EXP laserScanToPointCloudNormal(const LaserScan &laserScan, const Transform &transform=Transform())
Definition: util3d.cpp:2215
void RTABMAP_EXP fillProjectedCloudHoles(cv::Mat &depthRegistered, bool verticalDirection, bool fillToBorder)
Definition: util3d.cpp:2794
cv::Mat RTABMAP_EXP projectCloudToCamera(const cv::Size &imageSize, const cv::Mat &cameraMatrixK, const cv::Mat &laserScan, const rtabmap::Transform &cameraTransform)
Definition: util3d.cpp:2560
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP loadBINCloud(const std::string &fileName)
Definition: util3d.cpp:3311
model
Definition: trace.py:4
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:813
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_EXP laserScanToPointCloudI(const LaserScan &laserScan, const Transform &transform=Transform(), float intensity=0.0f)
Definition: util3d.cpp:2250
pcl::IndicesPtr RTABMAP_EXP concatenate(const std::vector< pcl::IndicesPtr > &indices)
Concatenate a vector of indices to a single vector.
Definition: util3d.cpp:3219
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:712
LaserScan RTABMAP_EXP loadScan(const std::string &path)
Definition: util3d.cpp:3321
pcl::PointCloud< pcl::PointXYZ >::Ptr loadCloud(const std::string &path, const Transform &transform, int downsampleStep, float voxelSize)
Definition: util3d.cpp:3379
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:137
LaserScan RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud< pcl::PointXYZ > &cloud, const Transform &transform=Transform(), bool filterNaNs=true)
Definition: util3d.cpp:1920
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP concatenateClouds(const std::list< pcl::PointCloud< pcl::PointXYZ >::Ptr > &clouds)
Definition: util3d.cpp:3199
cv::Mat RTABMAP_EXP depthFromCloud(const pcl::PointCloud< pcl::PointXYZRGBA > &cloud, float &fx, float &fy, bool depth16U=true)
Definition: util3d.cpp:77
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:3288


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:38:58