Functions
rtabmap::util3d Namespace Reference

Functions

std::multimap< int,
cv::KeyPoint > RTABMAP_EXP 
aggregate (const std::list< int > &wordIds, const std::vector< cv::KeyPoint > &keypoints)
cv::Mat bgrFromCloud (const pcl::PointCloud< pcl::PointXYZRGBA > &cloud, bool bgrOrder)
pcl::PointCloud< pcl::PointXYZ >
::Ptr RTABMAP_EXP 
cloudFromDepth (const cv::Mat &imageDepth, float cx, float cy, float fx, float fy, int decimation=1)
pcl::PointCloud
< pcl::PointXYZRGB >::Ptr
RTABMAP_EXP 
cloudFromDepthRGB (const cv::Mat &imageRgb, const cv::Mat &imageDepth, float cx, float cy, float fx, float fy, int decimation=1)
pcl::PointCloud< pcl::PointXYZ >
::Ptr RTABMAP_EXP 
cloudFromDisparity (const cv::Mat &imageDisparity, float cx, float cy, float fx, float baseline, int decimation=1)
pcl::PointCloud
< pcl::PointXYZRGB >::Ptr
RTABMAP_EXP 
cloudFromDisparityRGB (const cv::Mat &imageRgb, const cv::Mat &imageDisparity, float cx, float cy, float fx, float baseline, int decimation=1)
pcl::PointCloud
< pcl::PointXYZRGB >::Ptr
RTABMAP_EXP 
cloudFromStereoImages (const cv::Mat &imageLeft, const cv::Mat &imageRight, float cx, float cy, float fx, float baseline, int decimation=1)
pcl::PointCloud
< pcl::PointNormal >::Ptr
RTABMAP_EXP 
computeNormals (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int normalKSearch=20)
pcl::PointCloud
< pcl::PointXYZRGBNormal >
::Ptr RTABMAP_EXP 
computeNormals (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, int normalKSearch=20)
pcl::PointCloud
< pcl::PointXYZRGBNormal >
::Ptr RTABMAP_EXP 
computeNormalsSmoothed (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float smoothingSearchRadius=0.025, bool smoothingPolynomialFit=true)
pcl::IndicesPtr RTABMAP_EXP concatenate (const std::vector< pcl::IndicesPtr > &indices)
 Concatenate a vector of indices to a single vector.
pcl::IndicesPtr RTABMAP_EXP concatenate (const pcl::IndicesPtr &indicesA, const pcl::IndicesPtr &indicesB)
 Concatenate two vector of indices to a single vector.
pcl::PointCloud< pcl::PointXYZ >
::Ptr RTABMAP_EXP 
concatenateClouds (const std::list< pcl::PointCloud< pcl::PointXYZ >::Ptr > &clouds)
pcl::PointCloud
< pcl::PointXYZRGB >::Ptr
RTABMAP_EXP 
concatenateClouds (const std::list< pcl::PointCloud< pcl::PointXYZRGB >::Ptr > &clouds)
cv::Mat RTABMAP_EXP convertMap2Image8U (const cv::Mat &map8S)
int RTABMAP_EXP countUniquePairs (const std::multimap< int, pcl::PointXYZ > &wordsA, const std::multimap< int, pcl::PointXYZ > &wordsB)
cv::Mat RTABMAP_EXP create2DMap (const std::map< int, Transform > &poses, const std::map< int, pcl::PointCloud< pcl::PointXYZ >::Ptr > &scans, float cellSize, bool unknownSpaceFilled, float &xMin, float &yMin, float minMapSize=0.0f)
cv::Mat RTABMAP_EXP create2DMapFromOccupancyLocalMaps (const std::map< int, Transform > &poses, const std::map< int, std::pair< cv::Mat, cv::Mat > > &occupancy, float cellSize, float &xMin, float &yMin, float minMapSize=0.0f, bool erode=false)
pcl::PolygonMesh::Ptr RTABMAP_EXP createMesh (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloudWithNormals, float gp3SearchRadius=0.025, float gp3Mu=2.5, int gp3MaximumNearestNeighbors=100, float gp3MaximumSurfaceAngle=M_PI/4, float gp3MinimumAngle=M_PI/18, float gp3MaximumAngle=2 *M_PI/3, bool gp3NormalConsistency=false)
pcl::PointCloud< pcl::PointXYZ >
::Ptr RTABMAP_EXP 
cvMat2Cloud (const cv::Mat &matrix, const Transform &tranform=Transform::getIdentity())
cv::Mat RTABMAP_EXP cvtDepthFromFloat (const cv::Mat &depth32F)
cv::Mat RTABMAP_EXP cvtDepthToFloat (const cv::Mat &depth16U)
cv::Mat RTABMAP_EXP decimate (const cv::Mat &image, int d)
cv::Mat RTABMAP_EXP depthFromCloud (const pcl::PointCloud< pcl::PointXYZRGBA > &cloud, float &fx, float &fy, bool depth16U=true)
cv::Mat RTABMAP_EXP depthFromDisparity (const cv::Mat &disparity, float fx, float baseline, int type=CV_32FC1)
cv::Mat RTABMAP_EXP depthFromStereoCorrespondences (const cv::Mat &leftImage, const std::vector< cv::Point2f > &leftCorners, const std::vector< cv::Point2f > &rightCorners, const std::vector< unsigned char > &mask, float fx, float baseline)
cv::Mat RTABMAP_EXP depthFromStereoImages (const cv::Mat &leftImage, const cv::Mat &rightImage, const std::vector< cv::Point2f > &leftCorners, float fx, float baseline, int flowWinSize=9, int flowMaxLevel=4, int flowIterations=20, double flowEps=0.02)
cv::Mat RTABMAP_EXP disparityFromStereoCorrespondences (const cv::Mat &leftImage, const std::vector< cv::Point2f > &leftCorners, const std::vector< cv::Point2f > &rightCorners, const std::vector< unsigned char > &mask, float maxSlope=0.1f)
cv::Mat RTABMAP_EXP disparityFromStereoImages (const cv::Mat &leftImage, const cv::Mat &rightImage)
cv::Mat RTABMAP_EXP disparityFromStereoImages (const cv::Mat &leftImage, const cv::Mat &rightImage, const std::vector< cv::Point2f > &leftCorners, int flowWinSize=9, int flowMaxLevel=4, int flowIterations=20, double flowEps=0.02, float maxCorrespondencesSlope=0.1f)
template<typename PointT >
std::vector< pcl::IndicesPtr > extractClusters (const typename pcl::PointCloud< PointT >::Ptr &cloud, float clusterTolerance, int minClusterSize, int maxClusterSize, int *biggestClusterIndex)
template<typename PointT >
std::vector< pcl::IndicesPtr > extractClusters (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, float clusterTolerance, int minClusterSize, int maxClusterSize=std::numeric_limits< int >::max(), int *biggestClusterIndex=0)
 Wrapper of the pcl::EuclideanClusterExtraction class.
template<typename PointT >
pcl::IndicesPtr extractNegativeIndices (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices)
void RTABMAP_EXP extractXYZCorrespondences (const std::multimap< int, pcl::PointXYZ > &words1, const std::multimap< int, pcl::PointXYZ > &words2, pcl::PointCloud< pcl::PointXYZ > &cloud1, pcl::PointCloud< pcl::PointXYZ > &cloud2)
void RTABMAP_EXP extractXYZCorrespondences (const std::list< std::pair< cv::Point2f, cv::Point2f > > &correspondences, const cv::Mat &depthImage1, const cv::Mat &depthImage2, float cx, float cy, float fx, float fy, float maxDepth, pcl::PointCloud< pcl::PointXYZ > &cloud1, pcl::PointCloud< pcl::PointXYZ > &cloud2)
void RTABMAP_EXP extractXYZCorrespondences (const std::list< std::pair< cv::Point2f, cv::Point2f > > &correspondences, const pcl::PointCloud< pcl::PointXYZ > &cloud1, const pcl::PointCloud< pcl::PointXYZ > &cloud2, pcl::PointCloud< pcl::PointXYZ > &inliers1, pcl::PointCloud< pcl::PointXYZ > &inliers2, char depthAxis)
void RTABMAP_EXP extractXYZCorrespondences (const std::list< std::pair< cv::Point2f, cv::Point2f > > &correspondences, const pcl::PointCloud< pcl::PointXYZRGB > &cloud1, const pcl::PointCloud< pcl::PointXYZRGB > &cloud2, pcl::PointCloud< pcl::PointXYZ > &inliers1, pcl::PointCloud< pcl::PointXYZ > &inliers2, char depthAxis)
template<typename PointT >
void extractXYZCorrespondencesImpl (const std::list< std::pair< cv::Point2f, cv::Point2f > > &correspondences, const pcl::PointCloud< PointT > &cloud1, const pcl::PointCloud< PointT > &cloud2, pcl::PointCloud< pcl::PointXYZ > &inliers1, pcl::PointCloud< pcl::PointXYZ > &inliers2, char depthAxis)
void RTABMAP_EXP extractXYZCorrespondencesRANSAC (const std::multimap< int, pcl::PointXYZ > &words1, const std::multimap< int, pcl::PointXYZ > &words2, pcl::PointCloud< pcl::PointXYZ > &cloud1, pcl::PointCloud< pcl::PointXYZ > &cloud2)
void RTABMAP_EXP fillRegisteredDepthHoles (cv::Mat &depth, bool vertical, bool horizontal, bool fillDoubleHoles=false)
void RTABMAP_EXP filterMaxDepth (pcl::PointCloud< pcl::PointXYZ > &inliers1, pcl::PointCloud< pcl::PointXYZ > &inliers2, float maxDepth, char depthAxis, bool removeDuplicates)
void RTABMAP_EXP findCorrespondences (const std::multimap< int, cv::KeyPoint > &wordsA, const std::multimap< int, cv::KeyPoint > &wordsB, std::list< std::pair< cv::Point2f, cv::Point2f > > &pairs)
void RTABMAP_EXP findCorrespondences (const std::multimap< int, pcl::PointXYZ > &words1, const std::multimap< int, pcl::PointXYZ > &words2, pcl::PointCloud< pcl::PointXYZ > &inliers1, pcl::PointCloud< pcl::PointXYZ > &inliers2, float maxDepth, std::set< int > *uniqueCorrespondences=0)
std::list< std::pair
< cv::Point2f, cv::Point2f > > 
findCorrespondences (const std::multimap< int, cv::KeyPoint > &words1, const std::multimap< int, cv::KeyPoint > &words2)
pcl::PointCloud< pcl::PointXYZ >
::Ptr RTABMAP_EXP 
generateKeypoints3DDepth (const std::vector< cv::KeyPoint > &keypoints, const cv::Mat &depth, float fx, float fy, float cx, float cy, const Transform &transform)
pcl::PointCloud< pcl::PointXYZ >
::Ptr RTABMAP_EXP 
generateKeypoints3DDisparity (const std::vector< cv::KeyPoint > &keypoints, const cv::Mat &disparity, float fx, float baseline, float cx, float cy, const Transform &transform)
pcl::PointCloud< pcl::PointXYZ >
::Ptr RTABMAP_EXP 
generateKeypoints3DStereo (const std::vector< cv::KeyPoint > &keypoints, const cv::Mat &leftImage, const cv::Mat &rightImage, float fx, float baseline, float cx, float cy, const Transform &transform=Transform::getIdentity(), int flowWinSize=9, int flowMaxLevel=4, int flowIterations=20, double flowEps=0.02)
std::multimap< int,
pcl::PointXYZ > RTABMAP_EXP 
generateWords3DMono (const std::multimap< int, cv::KeyPoint > &kpts, const std::multimap< int, cv::KeyPoint > &previousKpts, float fx, float fy, float cx, float cy, const Transform &localTransform, Transform &cameraTransform, int pnpIterations=100, float pnpReprojError=8.0f, int pnpFlags=cv::ITERATIVE, float ransacParam1=3.0f, float ransacParam2=0.99f, const std::multimap< int, pcl::PointXYZ > &refGuess3D=std::multimap< int, pcl::PointXYZ >(), double *variance=0)
pcl::PointCloud< pcl::PointXYZ >
::Ptr RTABMAP_EXP 
get3DFASTKpts (const cv::Mat &image, const cv::Mat &imageDepth, float constant, int fastThreshold=50, bool fastNonmaxSuppression=true, float maxDepth=5.0f)
int RTABMAP_EXP getCorrespondencesCount (const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_source, const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_target, float maxDistance)
float RTABMAP_EXP getDepth (const cv::Mat &depthImage, float x, float y, bool smoothing, float maxZError=0.02f)
pcl::PointCloud< pcl::PointXYZ >
::Ptr RTABMAP_EXP 
getICPReadyCloud (const cv::Mat &depth, float fx, float fy, float cx, float cy, int decimation, double maxDepth, float voxel, int samples, const Transform &transform=Transform::getIdentity())
Transform RTABMAP_EXP icp (const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_source, const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_target, double maxCorrespondenceDistance, int maximumIterations, bool *hasConverged=0, double *variance=0, int *correspondences=0)
Transform RTABMAP_EXP icp2D (const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_source, const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_target, double maxCorrespondenceDistance, int maximumIterations, bool *hasConverged=0, double *variance=0, int *correspondences=0)
Transform RTABMAP_EXP icpPointToPlane (const pcl::PointCloud< pcl::PointNormal >::ConstPtr &cloud_source, const pcl::PointCloud< pcl::PointNormal >::ConstPtr &cloud_target, double maxCorrespondenceDistance, int maximumIterations, bool *hasConverged=0, double *variance=0, int *correspondences=0)
cv::Mat RTABMAP_EXP laserScanFromPointCloud (const pcl::PointCloud< pcl::PointXYZ > &cloud)
pcl::PointCloud< pcl::PointXYZ >
::Ptr RTABMAP_EXP 
laserScanToPointCloud (const cv::Mat &laserScan)
template<typename PointT >
pcl::IndicesPtr normalFiltering (const typename pcl::PointCloud< PointT >::Ptr &cloud, float angleMax, const Eigen::Vector4f &normal, float radiusSearch, const Eigen::Vector4f &viewpoint)
template<typename PointT >
pcl::IndicesPtr normalFiltering (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, float angleMax, const Eigen::Vector4f &normal, float radiusSearch, const Eigen::Vector4f &viewpoint)
 Given a normal and a maximum angle error, keep all points of the cloud respecting this normal.
template<typename PointT >
void occupancy2DFromCloud3D (const typename pcl::PointCloud< PointT >::Ptr &cloud, cv::Mat &ground, cv::Mat &obstacles, float cellSize, float groundNormalAngle, int minClusterSize)
void RTABMAP_EXP occupancy2DFromLaserScan (const cv::Mat &scan, cv::Mat &ground, cv::Mat &obstacles, float cellSize)
template<typename PointT >
pcl::PointCloud< PointT >::Ptr passThrough (const typename pcl::PointCloud< PointT >::Ptr &cloud, const std::string &axis, float min, float max)
template<typename PointT >
void projectCloudOnXYPlane (typename pcl::PointCloud< PointT >::Ptr &cloud)
pcl::PointXYZ RTABMAP_EXP projectDepthTo3D (const cv::Mat &depthImage, float x, float y, float cx, float cy, float fx, float fy, bool smoothing, float maxZError=0.02f)
pcl::PointXYZ RTABMAP_EXP projectDisparityTo3D (const cv::Point2f &pt, float disparity, float cx, float cy, float fx, float baseline)
pcl::PointXYZ RTABMAP_EXP projectDisparityTo3D (const cv::Point2f &pt, const cv::Mat &disparity, float cx, float cy, float fx, float baseline)
template<typename PointT >
pcl::IndicesPtr radiusFiltering (const typename pcl::PointCloud< PointT >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius)
template<typename PointT >
pcl::IndicesPtr radiusFiltering (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, float radiusSearch, int minNeighborsInRadius)
 Wrapper of the pcl::RadiusOutlierRemoval class.
void RTABMAP_EXP rayTrace (const cv::Point2i &start, const cv::Point2i &end, cv::Mat &grid, bool stopOnObstacle)
cv::Mat RTABMAP_EXP registerDepth (const cv::Mat &depth, const cv::Mat &depthK, const cv::Mat &colorK, const rtabmap::Transform &transform)
template<typename PointT >
pcl::PointCloud< PointT >::Ptr removeNaNFromPointCloud (const typename pcl::PointCloud< PointT >::Ptr &cloud)
template<typename PointT >
pcl::PointCloud< PointT >::Ptr removeNaNNormalsFromPointCloud (const typename pcl::PointCloud< PointT >::Ptr &cloud)
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)
cv::Mat RTABMAP_EXP rgbFromCloud (const pcl::PointCloud< pcl::PointXYZRGBA > &cloud, bool bgrOrder=true)
template<typename PointT >
pcl::PointCloud< PointT >::Ptr sampling (const typename pcl::PointCloud< PointT >::Ptr &cloud, int samples)
void RTABMAP_EXP savePCDWords (const std::string &fileName, const std::multimap< int, pcl::PointXYZ > &words, const Transform &transform=Transform::getIdentity())
template<typename PointT >
void segmentObstaclesFromGround (const typename pcl::PointCloud< PointT >::Ptr &cloud, pcl::IndicesPtr &ground, pcl::IndicesPtr &obstacles, float normalRadiusSearch, float groundNormalAngle, int minClusterSize, bool segmentFlatObstacles)
Transform RTABMAP_EXP transformFromXYZCorrespondences (const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud1, const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud2, double inlierThreshold=0.02, int iterations=100, bool refineModel=false, double refineModelSigma=3.0, int refineModelIterations=10, std::vector< int > *inliers=0, double *variance=0)
template<typename PointT >
PointT transformPoint (const PointT &pt, const Transform &transform)
template<typename PointT >
pcl::PointCloud< PointT >::Ptr transformPointCloud (const typename pcl::PointCloud< PointT >::Ptr &cloud, const Transform &transform)
template<typename PointT >
pcl::PointCloud< PointT >::Ptr voxelize (const typename pcl::PointCloud< PointT >::Ptr &cloud, float voxelSize)

Function Documentation

std::multimap< int, cv::KeyPoint > rtabmap::util3d::aggregate ( const std::list< int > &  wordIds,
const std::vector< cv::KeyPoint > &  keypoints 
)

Definition at line 687 of file util3d.cpp.

cv::Mat rtabmap::util3d::bgrFromCloud ( const pcl::PointCloud< pcl::PointXYZRGBA > &  cloud,
bool  bgrOrder 
)

Definition at line 63 of file util3d.cpp.

pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::cloudFromDepth ( const cv::Mat &  imageDepth,
float  cx,
float  cy,
float  fx,
float  fy,
int  decimation = 1 
)

Definition at line 883 of file util3d.cpp.

pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::cloudFromDepthRGB ( const cv::Mat &  imageRgb,
const cv::Mat &  imageDepth,
float  cx,
float  cy,
float  fx,
float  fy,
int  decimation = 1 
)

Definition at line 925 of file util3d.cpp.

pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::cloudFromDisparity ( const cv::Mat &  imageDisparity,
float  cx,
float  cy,
float  fx,
float  baseline,
int  decimation = 1 
)

Definition at line 991 of file util3d.cpp.

pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::cloudFromDisparityRGB ( const cv::Mat &  imageRgb,
const cv::Mat &  imageDisparity,
float  cx,
float  cy,
float  fx,
float  baseline,
int  decimation = 1 
)

Definition at line 1038 of file util3d.cpp.

pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::cloudFromStereoImages ( const cv::Mat &  imageLeft,
const cv::Mat &  imageRight,
float  cx,
float  cy,
float  fx,
float  baseline,
int  decimation = 1 
)

Definition at line 1105 of file util3d.cpp.

pcl::PointCloud< pcl::PointNormal >::Ptr rtabmap::util3d::computeNormals ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  cloud,
int  normalKSearch = 20 
)

Definition at line 2211 of file util3d.cpp.

pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr rtabmap::util3d::computeNormals ( const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  cloud,
int  normalKSearch = 20 
)

Definition at line 2235 of file util3d.cpp.

pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr rtabmap::util3d::computeNormalsSmoothed ( const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  cloud,
float  smoothingSearchRadius = 0.025,
bool  smoothingPolynomialFit = true 
)

Definition at line 2259 of file util3d.cpp.

pcl::IndicesPtr rtabmap::util3d::concatenate ( const std::vector< pcl::IndicesPtr > &  indices)

Concatenate a vector of indices to a single vector.

Parameters:
indicesthe vector of indices to concatenate.
Note:
This methods doesn't check if indices exist in the two set and doesn't sort the output indices. If we are not sure if the the two set of indices set are disjoint and/or you need sorted indices, the use of mergeIndices().
Returns:
the indices concatenated.

Definition at line 3087 of file util3d.cpp.

pcl::IndicesPtr rtabmap::util3d::concatenate ( const pcl::IndicesPtr &  indicesA,
const pcl::IndicesPtr &  indicesB 
)

Concatenate two vector of indices to a single vector.

Parameters:
indicesAthe first vector of indices to concatenate.
indicesBthe second vector of indices to concatenate.
Note:
This methods doesn't check if indices exist in the two set and doesn't sort the output indices. If we are not sure if the the two set of indices set are disjoint and/or you need sorted indices, the use of mergeIndices().
Returns:
the indices concatenated.

Definition at line 3107 of file util3d.cpp.

pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::concatenateClouds ( const std::list< pcl::PointCloud< pcl::PointXYZ >::Ptr > &  clouds)

Definition at line 2416 of file util3d.cpp.

pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::concatenateClouds ( const std::list< pcl::PointCloud< pcl::PointXYZRGB >::Ptr > &  clouds)

Definition at line 2426 of file util3d.cpp.

cv::Mat rtabmap::util3d::convertMap2Image8U ( const cv::Mat &  map8S)

Definition at line 3059 of file util3d.cpp.

int rtabmap::util3d::countUniquePairs ( const std::multimap< int, pcl::PointXYZ > &  wordsA,
const std::multimap< int, pcl::PointXYZ > &  wordsB 
)

Definition at line 1704 of file util3d.cpp.

cv::Mat rtabmap::util3d::create2DMap ( const std::map< int, Transform > &  poses,
const std::map< int, pcl::PointCloud< pcl::PointXYZ >::Ptr > &  scans,
float  cellSize,
bool  unknownSpaceFilled,
float &  xMin,
float &  yMin,
float  minMapSize 
)

Create 2d Occupancy grid (CV_8S) -1 = unknown 0 = empty space 100 = obstacle

Parameters:
poses
scans
cellSizem
unknownSpaceFilledif false no fill, otherwise a virtual laser sweeps the unknown space from each pose (stopping on detected obstacle)
xMin
yMin

Definition at line 2830 of file util3d.cpp.

cv::Mat rtabmap::util3d::create2DMapFromOccupancyLocalMaps ( const std::map< int, Transform > &  poses,
const std::map< int, std::pair< cv::Mat, cv::Mat > > &  occupancy,
float  cellSize,
float &  xMin,
float &  yMin,
float  minMapSize,
bool  erode 
)

Create 2d Occupancy grid (CV_8S) from 2d occupancy -1 = unknown 0 = empty space 100 = obstacle

Parameters:
poses
occupancy<empty, occupied>
cellSizem
xMin
yMin
minMapSizeminimum width (m)
erode

Definition at line 2576 of file util3d.cpp.

pcl::PolygonMesh::Ptr rtabmap::util3d::createMesh ( const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &  cloudWithNormals,
float  gp3SearchRadius = 0.025,
float  gp3Mu = 2.5,
int  gp3MaximumNearestNeighbors = 100,
float  gp3MaximumSurfaceAngle = M_PI/4,
float  gp3MinimumAngle = M_PI/18,
float  gp3MaximumAngle = 2*M_PI/3,
bool  gp3NormalConsistency = false 
)

Definition at line 2462 of file util3d.cpp.

pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::cvMat2Cloud ( const cv::Mat &  matrix,
const Transform &  tranform = Transform::getIdentity() 
)

Definition at line 2329 of file util3d.cpp.

cv::Mat rtabmap::util3d::cvtDepthFromFloat ( const cv::Mat &  depth32F)

Definition at line 226 of file util3d.cpp.

cv::Mat rtabmap::util3d::cvtDepthToFloat ( const cv::Mat &  depth16U)

Definition at line 250 of file util3d.cpp.

cv::Mat rtabmap::util3d::decimate ( const cv::Mat &  image,
int  d 
)

Definition at line 3119 of file util3d.cpp.

cv::Mat rtabmap::util3d::depthFromCloud ( const pcl::PointCloud< pcl::PointXYZRGBA > &  cloud,
float &  fx,
float &  fy,
bool  depth16U = true 
)

Definition at line 89 of file util3d.cpp.

cv::Mat rtabmap::util3d::depthFromDisparity ( const cv::Mat &  disparity,
float  fx,
float  baseline,
int  type = CV_32FC1 
)

Definition at line 1320 of file util3d.cpp.

cv::Mat rtabmap::util3d::depthFromStereoCorrespondences ( const cv::Mat &  leftImage,
const std::vector< cv::Point2f > &  leftCorners,
const std::vector< cv::Point2f > &  rightCorners,
const std::vector< unsigned char > &  mask,
float  fx,
float  baseline 
)

Definition at line 1262 of file util3d.cpp.

cv::Mat rtabmap::util3d::depthFromStereoImages ( const cv::Mat &  leftImage,
const cv::Mat &  rightImage,
const std::vector< cv::Point2f > &  leftCorners,
float  fx,
float  baseline,
int  flowWinSize = 9,
int  flowMaxLevel = 4,
int  flowIterations = 20,
double  flowEps = 0.02 
)

Definition at line 1200 of file util3d.cpp.

cv::Mat rtabmap::util3d::disparityFromStereoCorrespondences ( const cv::Mat &  leftImage,
const std::vector< cv::Point2f > &  leftCorners,
const std::vector< cv::Point2f > &  rightCorners,
const std::vector< unsigned char > &  mask,
float  maxSlope = 0.1f 
)

Definition at line 1237 of file util3d.cpp.

cv::Mat rtabmap::util3d::disparityFromStereoImages ( const cv::Mat &  leftImage,
const cv::Mat &  rightImage 
)

Definition at line 1131 of file util3d.cpp.

cv::Mat rtabmap::util3d::disparityFromStereoImages ( const cv::Mat &  leftImage,
const cv::Mat &  rightImage,
const std::vector< cv::Point2f > &  leftCorners,
int  flowWinSize = 9,
int  flowMaxLevel = 4,
int  flowIterations = 20,
double  flowEps = 0.02,
float  maxCorrespondencesSlope = 0.1f 
)

Definition at line 1165 of file util3d.cpp.

template<typename PointT >
std::vector< pcl::IndicesPtr > rtabmap::util3d::extractClusters ( const typename pcl::PointCloud< PointT >::Ptr &  cloud,
float  clusterTolerance,
int  minClusterSize,
int  maxClusterSize = std::numeric_limits< int >::max(),
int *  biggestClusterIndex = 0 
)

For convenience.

Definition at line 363 of file util3d.hpp.

template<typename PointT >
std::vector< pcl::IndicesPtr > rtabmap::util3d::extractClusters ( const typename pcl::PointCloud< PointT >::Ptr &  cloud,
const pcl::IndicesPtr &  indices,
float  clusterTolerance,
int  minClusterSize,
int  maxClusterSize = std::numeric_limits< int >::max(),
int *  biggestClusterIndex = 0 
)

Wrapper of the pcl::EuclideanClusterExtraction class.

Extract all clusters from a point cloud given a maximum cluster distance tolerance.

Parameters:
cloudthe input cloud.
indicesthe input indices of the cloud to process, if empty, all points in the cloud are processed.
clusterTolerancethe cluster distance tolerance (see pcl::EuclideanClusterExtraction).
minClusterSizeminimum size of the clusters to return (see pcl::EuclideanClusterExtraction).
maxClusterSizemaximum size of the clusters to return (see pcl::EuclideanClusterExtraction).
biggestClusterIndexthe index of the biggest cluster, if the clusters are empty, a negative index is set.
Returns:
the indices of each cluster found.

Definition at line 375 of file util3d.hpp.

template<typename PointT >
pcl::IndicesPtr rtabmap::util3d::extractNegativeIndices ( const typename pcl::PointCloud< PointT >::Ptr &  cloud,
const pcl::IndicesPtr &  indices 
)

Definition at line 429 of file util3d.hpp.

void rtabmap::util3d::extractXYZCorrespondences ( const std::multimap< int, pcl::PointXYZ > &  words1,
const std::multimap< int, pcl::PointXYZ > &  words2,
pcl::PointCloud< pcl::PointXYZ > &  cloud1,
pcl::PointCloud< pcl::PointXYZ > &  cloud2 
)

Definition at line 1539 of file util3d.cpp.

void rtabmap::util3d::extractXYZCorrespondences ( const std::list< std::pair< cv::Point2f, cv::Point2f > > &  correspondences,
const cv::Mat &  depthImage1,
const cv::Mat &  depthImage2,
float  cx,
float  cy,
float  fx,
float  fy,
float  maxDepth,
pcl::PointCloud< pcl::PointXYZ > &  cloud1,
pcl::PointCloud< pcl::PointXYZ > &  cloud2 
)

Definition at line 1632 of file util3d.cpp.

void rtabmap::util3d::extractXYZCorrespondences ( const std::list< std::pair< cv::Point2f, cv::Point2f > > &  correspondences,
const pcl::PointCloud< pcl::PointXYZ > &  cloud1,
const pcl::PointCloud< pcl::PointXYZ > &  cloud2,
pcl::PointCloud< pcl::PointXYZ > &  inliers1,
pcl::PointCloud< pcl::PointXYZ > &  inliers2,
char  depthAxis 
)

Definition at line 1685 of file util3d.cpp.

void rtabmap::util3d::extractXYZCorrespondences ( const std::list< std::pair< cv::Point2f, cv::Point2f > > &  correspondences,
const pcl::PointCloud< pcl::PointXYZRGB > &  cloud1,
const pcl::PointCloud< pcl::PointXYZRGB > &  cloud2,
pcl::PointCloud< pcl::PointXYZ > &  inliers1,
pcl::PointCloud< pcl::PointXYZ > &  inliers2,
char  depthAxis 
)

Definition at line 1694 of file util3d.cpp.

template<typename PointT >
void rtabmap::util3d::extractXYZCorrespondencesImpl ( const std::list< std::pair< cv::Point2f, cv::Point2f > > &  correspondences,
const pcl::PointCloud< PointT > &  cloud1,
const pcl::PointCloud< PointT > &  cloud2,
pcl::PointCloud< pcl::PointXYZ > &  inliers1,
pcl::PointCloud< pcl::PointXYZ > &  inliers2,
char  depthAxis 
) [inline]

Definition at line 1663 of file util3d.cpp.

void rtabmap::util3d::extractXYZCorrespondencesRANSAC ( const std::multimap< int, pcl::PointXYZ > &  words1,
const std::multimap< int, pcl::PointXYZ > &  words2,
pcl::PointCloud< pcl::PointXYZ > &  cloud1,
pcl::PointCloud< pcl::PointXYZ > &  cloud2 
)

Definition at line 1560 of file util3d.cpp.

void rtabmap::util3d::fillRegisteredDepthHoles ( cv::Mat &  depth,
bool  vertical,
bool  horizontal,
bool  fillDoubleHoles = false 
)

Definition at line 1411 of file util3d.cpp.

void rtabmap::util3d::filterMaxDepth ( pcl::PointCloud< pcl::PointXYZ > &  inliers1,
pcl::PointCloud< pcl::PointXYZ > &  inliers2,
float  maxDepth,
char  depthAxis,
bool  removeDuplicates 
)

Definition at line 1721 of file util3d.cpp.

void rtabmap::util3d::findCorrespondences ( const std::multimap< int, cv::KeyPoint > &  wordsA,
const std::multimap< int, cv::KeyPoint > &  wordsB,
std::list< std::pair< cv::Point2f, cv::Point2f > > &  pairs 
)

if a=[1 2 3 4 6 6], b=[1 1 2 4 5 6 6], results= [(2,2) (4,4)] realPairsCount = 5

Definition at line 2311 of file util3d.cpp.

void rtabmap::util3d::findCorrespondences ( const std::multimap< int, pcl::PointXYZ > &  words1,
const std::multimap< int, pcl::PointXYZ > &  words2,
pcl::PointCloud< pcl::PointXYZ > &  inliers1,
pcl::PointCloud< pcl::PointXYZ > &  inliers2,
float  maxDepth,
std::set< int > *  uniqueCorrespondences = 0 
)

Definition at line 735 of file util3d.cpp.

std::list<std::pair<cv::Point2f, cv::Point2f> > rtabmap::util3d::findCorrespondences ( const std::multimap< int, cv::KeyPoint > &  words1,
const std::multimap< int, cv::KeyPoint > &  words2 
)

Definition at line 701 of file util3d.cpp.

pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::generateKeypoints3DDepth ( const std::vector< cv::KeyPoint > &  keypoints,
const cv::Mat &  depth,
float  fx,
float  fy,
float  cx,
float  cy,
const Transform &  transform 
)

Definition at line 269 of file util3d.cpp.

pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::generateKeypoints3DDisparity ( const std::vector< cv::KeyPoint > &  keypoints,
const cv::Mat &  disparity,
float  fx,
float  baseline,
float  cx,
float  cy,
const Transform &  transform 
)

Definition at line 305 of file util3d.cpp.

pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::generateKeypoints3DStereo ( const std::vector< cv::KeyPoint > &  keypoints,
const cv::Mat &  leftImage,
const cv::Mat &  rightImage,
float  fx,
float  baseline,
float  cx,
float  cy,
const Transform &  transform = Transform::getIdentity(),
int  flowWinSize = 9,
int  flowMaxLevel = 4,
int  flowIterations = 20,
double  flowEps = 0.02 
)

Definition at line 336 of file util3d.cpp.

std::multimap< int, pcl::PointXYZ > rtabmap::util3d::generateWords3DMono ( const std::multimap< int, cv::KeyPoint > &  kpts,
const std::multimap< int, cv::KeyPoint > &  previousKpts,
float  fx,
float  fy,
float  cx,
float  cy,
const Transform &  localTransform,
Transform &  cameraTransform,
int  pnpIterations = 100,
float  pnpReprojError = 8.0f,
int  pnpFlags = cv::ITERATIVE,
float  ransacParam1 = 3.0f,
float  ransacParam2 = 0.99f,
const std::multimap< int, pcl::PointXYZ > &  refGuess3D = std::multimap<int, pcl::PointXYZ>(),
double *  variance = 0 
)

Definition at line 411 of file util3d.cpp.

pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::get3DFASTKpts ( const cv::Mat &  image,
const cv::Mat &  imageDepth,
float  constant,
int  fastThreshold = 50,
bool  fastNonmaxSuppression = true,
float  maxDepth = 5.0f 
)

Definition at line 2436 of file util3d.cpp.

int rtabmap::util3d::getCorrespondencesCount ( const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &  cloud_source,
const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &  cloud_target,
float  maxDistance 
)

Definition at line 2287 of file util3d.cpp.

float rtabmap::util3d::getDepth ( const cv::Mat &  depthImage,
float  x,
float  y,
bool  smoothing,
float  maxZError = 0.02f 
)

Definition at line 773 of file util3d.cpp.

pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::getICPReadyCloud ( const cv::Mat &  depth,
float  fx,
float  fy,
float  cx,
float  cy,
int  decimation,
double  maxDepth,
float  voxel,
int  samples,
const Transform &  transform = Transform::getIdentity() 
)

Definition at line 2363 of file util3d.cpp.

Transform rtabmap::util3d::icp ( const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &  cloud_source,
const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &  cloud_target,
double  maxCorrespondenceDistance,
int  maximumIterations,
bool *  hasConverged = 0,
double *  variance = 0,
int *  correspondences = 0 
)

Definition at line 1948 of file util3d.cpp.

Transform rtabmap::util3d::icp2D ( const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &  cloud_source,
const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &  cloud_target,
double  maxCorrespondenceDistance,
int  maximumIterations,
bool *  hasConverged = 0,
double *  variance = 0,
int *  correspondences = 0 
)

Definition at line 2123 of file util3d.cpp.

Transform rtabmap::util3d::icpPointToPlane ( const pcl::PointCloud< pcl::PointNormal >::ConstPtr &  cloud_source,
const pcl::PointCloud< pcl::PointNormal >::ConstPtr &  cloud_target,
double  maxCorrespondenceDistance,
int  maximumIterations,
bool *  hasConverged = 0,
double *  variance = 0,
int *  correspondences = 0 
)

Definition at line 2033 of file util3d.cpp.

cv::Mat rtabmap::util3d::laserScanFromPointCloud ( const pcl::PointCloud< pcl::PointXYZ > &  cloud)

Definition at line 1514 of file util3d.cpp.

pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::laserScanToPointCloud ( const cv::Mat &  laserScan)

Definition at line 1525 of file util3d.cpp.

template<typename PointT >
pcl::IndicesPtr rtabmap::util3d::normalFiltering ( const typename pcl::PointCloud< PointT >::Ptr &  cloud,
float  angleMax,
const Eigen::Vector4f &  normal,
float  radiusSearch,
const Eigen::Vector4f &  viewpoint 
)

For convenience.

Definition at line 288 of file util3d.hpp.

template<typename PointT >
pcl::IndicesPtr rtabmap::util3d::normalFiltering ( const typename pcl::PointCloud< PointT >::Ptr &  cloud,
const pcl::IndicesPtr &  indices,
float  angleMax,
const Eigen::Vector4f &  normal,
float  radiusSearch,
const Eigen::Vector4f &  viewpoint 
)

Given a normal and a maximum angle error, keep all points of the cloud respecting this normal.

The normals are computed using the radius search parameter (pcl::NormalEstimation class is used for this), then for each normal, the corresponding point is filtered if the angle (using pcl::getAngle3D()) with the normal specified by the user is larger than the maximum angle specified by the user.

Parameters:
cloudthe input cloud.
indicesthe input indices of the cloud to process, if empty, all points in the cloud are processed.
angleMaxthe maximum angle.
normalthe normal to which each point's normal is compared.
radiusSearchradius parameter used for normal estimation (see pcl::NormalEstimation).
viewpointfrom which viewpoint the normals should be estimated (see pcl::NormalEstimation).
Returns:
the indices of the points which respect the normal constraint.

Definition at line 300 of file util3d.hpp.

template<typename PointT >
void rtabmap::util3d::occupancy2DFromCloud3D ( const typename pcl::PointCloud< PointT >::Ptr &  cloud,
cv::Mat &  ground,
cv::Mat &  obstacles,
float  cellSize,
float  groundNormalAngle,
int  minClusterSize 
)

Definition at line 443 of file util3d.hpp.

void rtabmap::util3d::occupancy2DFromLaserScan ( const cv::Mat &  scan,
cv::Mat &  ground,
cv::Mat &  obstacles,
float  cellSize 
)

Definition at line 2501 of file util3d.cpp.

template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::passThrough ( const typename pcl::PointCloud< PointT >::Ptr &  cloud,
const std::string &  axis,
float  min,
float  max 
)

Definition at line 78 of file util3d.hpp.

template<typename PointT >
void rtabmap::util3d::projectCloudOnXYPlane ( typename pcl::PointCloud< PointT >::Ptr &  cloud)

Definition at line 219 of file util3d.hpp.

pcl::PointXYZ rtabmap::util3d::projectDepthTo3D ( const cv::Mat &  depthImage,
float  x,
float  y,
float  cx,
float  cy,
float  fx,
float  fy,
bool  smoothing,
float  maxZError = 0.02f 
)

Definition at line 851 of file util3d.cpp.

pcl::PointXYZ rtabmap::util3d::projectDisparityTo3D ( const cv::Point2f &  pt,
float  disparity,
float  cx,
float  cy,
float  fx,
float  baseline 
)

Definition at line 1288 of file util3d.cpp.

pcl::PointXYZ rtabmap::util3d::projectDisparityTo3D ( const cv::Point2f &  pt,
const cv::Mat &  disparity,
float  cx,
float  cy,
float  fx,
float  baseline 
)

Definition at line 1302 of file util3d.cpp.

template<typename PointT >
pcl::IndicesPtr rtabmap::util3d::radiusFiltering ( const typename pcl::PointCloud< PointT >::Ptr &  cloud,
float  radiusSearch,
int  minNeighborsInRadius 
)

For convenience.

Definition at line 229 of file util3d.hpp.

template<typename PointT >
pcl::IndicesPtr rtabmap::util3d::radiusFiltering ( const typename pcl::PointCloud< PointT >::Ptr &  cloud,
const pcl::IndicesPtr &  indices,
float  radiusSearch,
int  minNeighborsInRadius 
)

Wrapper of the pcl::RadiusOutlierRemoval class.

Points in the cloud which have less than a minimum of neighbors in the specified radius are filtered.

Parameters:
cloudthe input cloud.
indicesthe input indices of the cloud to check, if empty, all points in the cloud are checked.
radiusSearchthe radius in meter.
minNeighborsInRadiusthe minimum of neighbors to keep the point.
Returns:
the indices of the points satisfying the parameters.

Definition at line 239 of file util3d.hpp.

void rtabmap::util3d::rayTrace ( const cv::Point2i &  start,
const cv::Point2i &  end,
cv::Mat &  grid,
bool  stopOnObstacle 
)

Definition at line 2977 of file util3d.cpp.

cv::Mat rtabmap::util3d::registerDepth ( const cv::Mat &  depth,
const cv::Mat &  depthK,
const cv::Mat &  colorK,
const rtabmap::Transform transform 
)

Definition at line 1350 of file util3d.cpp.

template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::removeNaNFromPointCloud ( const typename pcl::PointCloud< PointT >::Ptr &  cloud)

Definition at line 99 of file util3d.hpp.

template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::removeNaNNormalsFromPointCloud ( const typename pcl::PointCloud< PointT >::Ptr &  cloud)

Definition at line 111 of file util3d.hpp.

void rtabmap::util3d::rgbdFromCloud ( const pcl::PointCloud< pcl::PointXYZRGBA > &  cloud,
cv::Mat &  rgb,
cv::Mat &  depth,
float &  fx,
float &  fy,
bool  bgrOrder = true,
bool  depth16U = true 
)

Definition at line 149 of file util3d.cpp.

cv::Mat RTABMAP_EXP rtabmap::util3d::rgbFromCloud ( const pcl::PointCloud< pcl::PointXYZRGBA > &  cloud,
bool  bgrOrder = true 
)
template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::sampling ( const typename pcl::PointCloud< PointT >::Ptr &  cloud,
int  samples 
)

Definition at line 63 of file util3d.hpp.

void rtabmap::util3d::savePCDWords ( const std::string &  fileName,
const std::multimap< int, pcl::PointXYZ > &  words,
const Transform &  transform = Transform::getIdentity() 
)

Definition at line 3166 of file util3d.cpp.

template<typename PointT >
void rtabmap::util3d::segmentObstaclesFromGround ( const typename pcl::PointCloud< PointT >::Ptr &  cloud,
pcl::IndicesPtr &  ground,
pcl::IndicesPtr &  obstacles,
float  normalRadiusSearch,
float  groundNormalAngle,
int  minClusterSize,
bool  segmentFlatObstacles 
)

Definition at line 143 of file util3d.hpp.

Transform rtabmap::util3d::transformFromXYZCorrespondences ( const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &  cloud1,
const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &  cloud2,
double  inlierThreshold = 0.02,
int  iterations = 100,
bool  refineModel = false,
double  refineModelSigma = 3.0,
int  refineModelIterations = 10,
std::vector< int > *  inliers = 0,
double *  variance = 0 
)

Definition at line 1769 of file util3d.cpp.

template<typename PointT >
PointT rtabmap::util3d::transformPoint ( const PointT &  pt,
const Transform &  transform 
)

Definition at line 135 of file util3d.hpp.

template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::transformPointCloud ( const typename pcl::PointCloud< PointT >::Ptr &  cloud,
const Transform &  transform 
)

Definition at line 123 of file util3d.hpp.

template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::voxelize ( const typename pcl::PointCloud< PointT >::Ptr &  cloud,
float  voxelSize 
)

Definition at line 47 of file util3d.hpp.



rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:44