33 #include <pcl/point_cloud.h> 34 #include <pcl/point_types.h> 35 #include <pcl/pcl_base.h> 36 #include <pcl/TextureMesh.h> 40 #include <opencv2/core/core.hpp> 51 const pcl::PointCloud<pcl::PointXYZRGBA> & cloud,
52 bool bgrOrder =
true);
55 const pcl::PointCloud<pcl::PointXYZRGBA> & cloud,
58 bool depth16U =
true);
61 const pcl::PointCloud<pcl::PointXYZRGBA> & cloud,
67 bool depth16U =
true);
70 const cv::Mat & depthImage,
75 float depthErrorRatio = 0.02f);
78 const cv::Size & imageSize,
84 const cv::Mat & imageDepth,
88 float maxDepth = 0.0f,
89 float minDepth = 0.0f,
90 std::vector<int> * validIndices = 0),
"Use cloudFromDepth with CameraModel interface.");
92 const cv::Mat & imageDepth,
93 const CameraModel & model,
95 float maxDepth = 0.0f,
96 float minDepth = 0.0f,
97 std::vector<int> * validIndices = 0);
100 const cv::Mat & imageRgb,
101 const cv::Mat & imageDepth,
105 float maxDepth = 0.0f,
106 float minDepth = 0.0f,
107 std::vector<int> * validIndices = 0),
"Use cloudFromDepthRGB with CameraModel interface.");
109 const cv::Mat & imageRgb,
110 const cv::Mat & imageDepth,
111 const CameraModel & model,
113 float maxDepth = 0.0f,
114 float minDepth = 0.0f,
115 std::vector<int> * validIndices = 0);
118 const cv::Mat & imageDisparity,
119 const StereoCameraModel & model,
121 float maxDepth = 0.0f,
122 float minDepth = 0.0f,
123 std::vector<int> * validIndices = 0);
126 const cv::Mat & imageRgb,
127 const cv::Mat & imageDisparity,
128 const StereoCameraModel & model,
130 float maxDepth = 0.0f,
131 float minDepth = 0.0f,
132 std::vector<int> * validIndices = 0);
135 const cv::Mat & imageLeft,
136 const cv::Mat & imageRight,
137 const StereoCameraModel & model,
139 float maxDepth = 0.0f,
140 float minDepth = 0.0f,
141 std::vector<int> * validIndices = 0,
145 const SensorData & sensorData,
147 float maxDepth = 0.0f,
148 float minDepth = 0.0f,
149 std::vector<int> * validIndices = 0,
151 const std::vector<float> & roiRatios = std::vector<float>());
168 const SensorData & sensorData,
170 float maxDepth = 0.0f,
171 float minDepth = 0.0f,
172 std::vector<int> * validIndices = 0,
174 const std::vector<float> & roiRatios = std::vector<float>());
180 const cv::Mat & depthImage,
194 const cv::Mat & depthImages,
195 const std::vector<CameraModel> & cameraModels,
202 cv::Mat
RTABMAP_EXP laserScanFromPointCloud(
const pcl::PointCloud<pcl::PointXYZ> & cloud,
const pcl::IndicesPtr & indices,
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);
209 cv::Mat
RTABMAP_EXP laserScanFromPointCloud(
const pcl::PointCloud<pcl::PointXYZRGB> & cloud,
const pcl::IndicesPtr & indices,
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);
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);
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);
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);
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);
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);
239 pcl::PointCloud<pcl::PointXYZI>::Ptr
RTABMAP_EXP laserScanToPointCloudI(
const LaserScan & laserScan,
const Transform & transform = Transform(),
float intensity = 0.0f);
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);
252 pcl::PointXYZRGB
RTABMAP_EXP laserScanToPointRGB(
const LaserScan & laserScan,
int index,
unsigned char r = 255,
unsigned char g = 255,
unsigned char b = 255);
266 const cv::Point2f & pt,
268 const StereoCameraModel & model);
271 const cv::Point2f & pt,
272 const cv::Mat & disparity,
273 const StereoCameraModel & model);
277 const cv::Size & imageSize,
278 const cv::Mat & cameraMatrixK,
279 const cv::Mat & laserScan,
284 const cv::Size & imageSize,
285 const cv::Mat & cameraMatrixK,
286 const pcl::PointCloud<pcl::PointXYZ>::Ptr laserScan,
291 const cv::Size & imageSize,
292 const cv::Mat & cameraMatrixK,
293 const pcl::PCLPointCloud2::Ptr laserScan,
298 cv::Mat & depthRegistered,
299 bool verticalDirection,
305 const std::list<pcl::PointCloud<pcl::PointXYZ>::Ptr> & clouds);
307 const std::list<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> & clouds);
319 const std::vector<pcl::IndicesPtr> & indices);
332 const pcl::IndicesPtr & indicesA,
333 const pcl::IndicesPtr & indicesB);
336 const std::string & fileName,
337 const std::multimap<int, pcl::PointXYZ> & words,
341 const std::string & fileName,
342 const std::multimap<int, cv::Point3f> & words,
357 const std::string & path,
359 int downsampleStep = 1,
360 float voxelSize = 0.0f),
"Use loadScan() instead.");
LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PCLPointCloud2 &cloud, bool filterNaNs=true)
bool RTABMAP_EXP isFinite(const cv::Point3f &pt)
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)
pcl::PointNormal RTABMAP_EXP laserScanToPointNormal(const LaserScan &laserScan, int index)
cv::Point3f RTABMAP_EXP projectDisparityTo3D(const cv::Point2f &pt, float disparity, const StereoCameraModel &model)
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)
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)
pcl::PointXYZINormal RTABMAP_EXP laserScanToPointINormal(const LaserScan &laserScan, int index, float intensity)
pcl::PCLPointCloud2::Ptr RTABMAP_EXP laserScanToPointCloud2(const LaserScan &laserScan, const Transform &transform=Transform())
std::map< std::string, std::string > ParametersMap
pcl::PointXYZ RTABMAP_EXP laserScanToPoint(const LaserScan &laserScan, int index)
void RTABMAP_EXP savePCDWords(const std::string &fileName, const std::multimap< int, pcl::PointXYZ > &words, const Transform &transform=Transform::getIdentity())
pcl::PointXYZRGBNormal RTABMAP_EXP laserScanToPointRGBNormal(const LaserScan &laserScan, int index, unsigned char r, unsigned char g, unsigned char b)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP laserScanToPointCloud(const LaserScan &laserScan, const Transform &transform=Transform())
pcl::PointCloud< pcl::PointXYZ > RTABMAP_EXP laserScanFromDepthImages(const cv::Mat &depthImages, const std::vector< CameraModel > &cameraModels, float maxDepth, float minDepth)
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)
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)
cv::Mat RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud< pcl::PointXYZ > &cloud, const Transform &transform=Transform(), bool filterNaNs=true)
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)
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)
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 >())
pcl::PointXYZRGB RTABMAP_EXP laserScanToPointRGB(const LaserScan &laserScan, int index, unsigned char r=255, unsigned char g=255, unsigned char b=255)
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())
pcl::PointXYZI RTABMAP_EXP laserScanToPointI(const LaserScan &laserScan, int index, float intensity)
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 >())
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)
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_EXP laserScanToPointCloudNormal(const LaserScan &laserScan, const Transform &transform=Transform())
void RTABMAP_EXP fillProjectedCloudHoles(cv::Mat &depthRegistered, bool verticalDirection, bool fillToBorder)
cv::Mat RTABMAP_EXP projectCloudToCamera(const cv::Size &imageSize, const cv::Mat &cameraMatrixK, const cv::Mat &laserScan, const rtabmap::Transform &cameraTransform)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP loadBINCloud(const std::string &fileName)
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 ¶meters=ParametersMap())
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_EXP laserScanToPointCloudI(const LaserScan &laserScan, const Transform &transform=Transform(), float intensity=0.0f)
pcl::IndicesPtr RTABMAP_EXP concatenate(const std::vector< pcl::IndicesPtr > &indices)
Concatenate a vector of indices to a single vector.
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)
LaserScan RTABMAP_EXP loadScan(const std::string &path)
pcl::PointCloud< pcl::PointXYZ >::Ptr loadCloud(const std::string &path, const Transform &transform, int downsampleStep, float voxelSize)
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)
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)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP concatenateClouds(const std::list< pcl::PointCloud< pcl::PointXYZ >::Ptr > &clouds)
cv::Mat RTABMAP_EXP depthFromCloud(const pcl::PointCloud< pcl::PointXYZRGBA > &cloud, float &fx, float &fy, bool depth16U=true)
cv::Mat RTABMAP_EXP rgbFromCloud(const pcl::PointCloud< pcl::PointXYZRGBA > &cloud, bool bgrOrder=true)
cv::Mat RTABMAP_EXP loadBINScan(const std::string &fileName)