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> 52 const pcl::PointCloud<pcl::PointXYZRGBA> & cloud,
53 bool bgrOrder =
true);
56 const pcl::PointCloud<pcl::PointXYZRGBA> & cloud,
59 bool depth16U =
true);
62 const pcl::PointCloud<pcl::PointXYZRGBA> & cloud,
68 bool depth16U =
true);
71 const cv::Mat & depthImage,
76 float depthErrorRatio = 0.02f);
79 const cv::Size & imageSize,
85 const cv::Mat & imageDepth,
89 float maxDepth = 0.0f,
90 float minDepth = 0.0f,
91 std::vector<int> * validIndices = 0),
"Use cloudFromDepth with CameraModel interface.");
93 const cv::Mat & imageDepth,
94 const CameraModel &
model,
96 float maxDepth = 0.0f,
97 float minDepth = 0.0f,
98 std::vector<int> * validIndices = 0);
101 const cv::Mat & imageRgb,
102 const cv::Mat & imageDepth,
106 float maxDepth = 0.0f,
107 float minDepth = 0.0f,
108 std::vector<int> * validIndices = 0),
"Use cloudFromDepthRGB with CameraModel interface.");
110 const cv::Mat & imageRgb,
111 const cv::Mat & imageDepth,
112 const CameraModel &
model,
114 float maxDepth = 0.0f,
115 float minDepth = 0.0f,
116 std::vector<int> * validIndices = 0);
119 const cv::Mat & imageDisparity,
120 const StereoCameraModel &
model,
122 float maxDepth = 0.0f,
123 float minDepth = 0.0f,
124 std::vector<int> * validIndices = 0);
127 const cv::Mat & imageRgb,
128 const cv::Mat & imageDisparity,
129 const StereoCameraModel &
model,
131 float maxDepth = 0.0f,
132 float minDepth = 0.0f,
133 std::vector<int> * validIndices = 0);
136 const cv::Mat & imageLeft,
137 const cv::Mat & imageRight,
138 const StereoCameraModel &
model,
140 float maxDepth = 0.0f,
141 float minDepth = 0.0f,
142 std::vector<int> * validIndices = 0,
146 const SensorData & sensorData,
148 float maxDepth = 0.0f,
149 float minDepth = 0.0f,
150 std::vector<int> * validIndices = 0,
152 const std::vector<float> & roiRatios = std::vector<float>());
169 const SensorData & sensorData,
171 float maxDepth = 0.0f,
172 float minDepth = 0.0f,
173 std::vector<int> * validIndices = 0,
175 const std::vector<float> & roiRatios = std::vector<float>());
181 const cv::Mat & depthImage,
195 const cv::Mat & depthImages,
196 const std::vector<CameraModel> & cameraModels,
200 template<
typename Po
intCloud2T>
201 LaserScan
laserScanFromPointCloud(
const PointCloud2T & cloud,
bool filterNaNs =
true,
bool is2D =
false,
const Transform & transform = Transform());
204 LaserScan
RTABMAP_EXP laserScanFromPointCloud(
const pcl::PointCloud<pcl::PointXYZ> & cloud,
const pcl::IndicesPtr & indices,
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);
211 LaserScan
RTABMAP_EXP laserScanFromPointCloud(
const pcl::PointCloud<pcl::PointXYZRGB> & cloud,
const pcl::IndicesPtr & indices,
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);
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);
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);
229 LaserScan
RTABMAP_EXP laserScan2dFromPointCloud(
const pcl::PointCloud<pcl::PointXYZ> & cloud,
const pcl::PointCloud<pcl::Normal> & normals,
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);
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);
242 pcl::PointCloud<pcl::PointXYZI>::Ptr
RTABMAP_EXP laserScanToPointCloudI(
const LaserScan & laserScan,
const Transform & transform = Transform(),
float intensity = 0.0f);
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);
255 pcl::PointXYZRGB
RTABMAP_EXP laserScanToPointRGB(
const LaserScan & laserScan,
int index,
unsigned char r = 100,
unsigned char g = 100,
unsigned char b = 100);
269 const cv::Point2f & pt,
271 const StereoCameraModel & model);
274 const cv::Point2f & pt,
275 const cv::Mat & disparity,
276 const StereoCameraModel & model);
280 const cv::Size & imageSize,
281 const cv::Mat & cameraMatrixK,
282 const cv::Mat & laserScan,
287 const cv::Size & imageSize,
288 const cv::Mat & cameraMatrixK,
289 const pcl::PointCloud<pcl::PointXYZ>::Ptr laserScan,
294 const cv::Size & imageSize,
295 const cv::Mat & cameraMatrixK,
296 const pcl::PCLPointCloud2::Ptr laserScan,
301 cv::Mat & depthRegistered,
302 bool verticalDirection,
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);
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);
337 const std::list<pcl::PointCloud<pcl::PointXYZ>::Ptr> & clouds);
339 const std::list<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> & clouds);
351 const std::vector<pcl::IndicesPtr> & indices);
364 const pcl::IndicesPtr & indicesA,
365 const pcl::IndicesPtr & indicesB);
368 const std::string & fileName,
369 const std::multimap<int, pcl::PointXYZ> & words,
373 const std::string & fileName,
374 const std::multimap<int, cv::Point3f> & words,
389 const std::string & path,
391 int downsampleStep = 1,
392 float voxelSize = 0.0f),
"Use loadScan() instead.");
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=100, unsigned char g=100, unsigned char b=100)
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)
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())
pcl::PointXYZRGBNormal RTABMAP_EXP laserScanToPointRGBNormal(const LaserScan &laserScan, int index, unsigned char r, unsigned char g, unsigned char b)
pcl::PointXYZRGB RTABMAP_EXP laserScanToPointRGB(const LaserScan &laserScan, int index, unsigned char r=100, unsigned char g=100, unsigned char b=100)
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)
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)
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)
pcl::PointCloud< pcl::PointXYZINormal >::Ptr RTABMAP_EXP laserScanToPointCloudINormal(const LaserScan &laserScan, const Transform &transform=Transform(), float intensity=0.0f)
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 >())
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())
LaserScan laserScanFromPointCloud(const PointCloud2T &cloud, bool filterNaNs, bool is2D, const Transform &transform)
pcl::PointXYZI RTABMAP_EXP laserScanToPointI(const LaserScan &laserScan, int index, float intensity)
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 >())
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)
LaserScan RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud< pcl::PointXYZ > &cloud, const Transform &transform=Transform(), bool filterNaNs=true)
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)