Functions | |
void RTABMAP_EXP | adjustNormalsToViewPoints (const std::map< int, Transform > &poses, const pcl::PointCloud< pcl::PointXYZ >::Ptr &rawCloud, const std::vector< int > &rawCameraIndices, pcl::PointCloud< pcl::PointNormal >::Ptr &cloud) |
void RTABMAP_EXP | adjustNormalsToViewPoints (const std::map< int, Transform > &poses, const pcl::PointCloud< pcl::PointXYZ >::Ptr &rawCloud, const std::vector< int > &rawCameraIndices, pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud) |
std::multimap< int, cv::KeyPoint > RTABMAP_EXP | aggregate (const std::list< int > &wordIds, const std::vector< cv::KeyPoint > &keypoints) |
void RTABMAP_EXP | appendMesh (pcl::PointCloud< pcl::PointXYZRGBNormal > &cloudA, std::vector< pcl::Vertices > &polygonsA, const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloudB, const std::vector< pcl::Vertices > &polygonsB) |
void RTABMAP_EXP | appendMesh (pcl::PointCloud< pcl::PointXYZRGB > &cloudA, std::vector< pcl::Vertices > &polygonsA, const pcl::PointCloud< pcl::PointXYZRGB > &cloudB, const std::vector< pcl::Vertices > &polygonsB) |
cv::Mat | bgrFromCloud (const pcl::PointCloud< pcl::PointXYZRGBA > &cloud, bool bgrOrder) |
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::PointXYZ > ::Ptr | cloudFromDepth (const cv::Mat &imageDepth, float cx, float cy, float fx, float fy, int decimation, float maxDepth, float minDepth, std::vector< int > *validIndices) |
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::PointCloud < pcl::PointXYZRGB >::Ptr | cloudFromDepthRGB (const cv::Mat &imageRgb, const cv::Mat &imageDepth, float cx, float cy, float fx, float fy, int decimation, float maxDepth, float minDepth, std::vector< int > *validIndices) |
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::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) |
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 ¶meters=ParametersMap()) |
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::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 ¶meters=ParametersMap()) |
pcl::PointCloud< pcl::Normal >::Ptr | computeFastOrganizedNormals (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float maxDepthChangeFactor=0.02f, float normalSmoothingSize=10.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0)) |
pcl::PointCloud< pcl::Normal >::Ptr | computeFastOrganizedNormals (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, float maxDepthChangeFactor=0.02f, float normalSmoothingSize=10.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0)) |
pcl::PointCloud< pcl::Normal > ::Ptr RTABMAP_EXP | computeNormals (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int normalKSearch=20, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0)) |
pcl::PointCloud< pcl::Normal > ::Ptr RTABMAP_EXP | computeNormals (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, int normalKSearch=20, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0)) |
pcl::PointCloud< pcl::Normal > ::Ptr RTABMAP_EXP | computeNormals (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, int normalKSearch=20, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0)) |
pcl::PointCloud< pcl::Normal > ::Ptr RTABMAP_EXP | computeNormals (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, int normalKSearch=20, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0)) |
std::vector< float > | computeReprojErrors (std::vector< cv::Point3f > opoints, std::vector< cv::Point2f > ipoints, const cv::Mat &cameraMatrix, const cv::Mat &distCoeffs, const cv::Mat &rvec, const cv::Mat &tvec, float reprojErrorThreshold, std::vector< int > &inliers) |
void RTABMAP_EXP | computeVarianceAndCorrespondences (const pcl::PointCloud< pcl::PointNormal >::ConstPtr &cloudA, const pcl::PointCloud< pcl::PointNormal >::ConstPtr &cloudB, double maxCorrespondenceDistance, double &variance, int &correspondencesOut) |
void RTABMAP_EXP | computeVarianceAndCorrespondences (const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloudA, const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloudB, double maxCorrespondenceDistance, double &variance, int &correspondencesOut) |
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) |
pcl::TextureMesh::Ptr RTABMAP_EXP | concatenateTextureMeshes (const std::list< pcl::TextureMesh::Ptr > &meshes) |
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, float scanMaxRange=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=true) |
void RTABMAP_EXP | createPolygonIndexes (const std::vector< pcl::Vertices > &polygons, int cloudSize, std::vector< std::set< int > > &neighborPolygons, std::vector< std::set< int > > &vertexPolygons) |
Given a set of polygons, create two indexes: polygons to neighbor polygons and vertices to polygons. | |
pcl::TextureMesh::Ptr RTABMAP_EXP | createTextureMesh (const pcl::PolygonMesh::Ptr &mesh, const std::map< int, Transform > &poses, const std::map< int, CameraModel > &cameraModels, const std::map< int, cv::Mat > &images, const std::string &tmpDirectory=".", int kNormalSearch=20) |
cv::Mat RTABMAP_EXP | depthFromCloud (const pcl::PointCloud< pcl::PointXYZRGBA > &cloud, float &fx, float &fy, bool depth16U=true) |
cv::Mat RTABMAP_EXP | downsample (const cv::Mat &cloud, int step) |
pcl::PointCloud< pcl::PointXYZ > ::Ptr RTABMAP_EXP | downsample (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int step) |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr RTABMAP_EXP | downsample (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, int step) |
Transform RTABMAP_EXP | estimateMotion3DTo2D (const std::map< int, cv::Point3f > &words3A, const std::map< int, cv::KeyPoint > &words2B, const CameraModel &cameraModel, int minInliers=10, int iterations=100, double reprojError=5., int flagsPnP=0, int pnpRefineIterations=1, const Transform &guess=Transform::getIdentity(), const std::map< int, cv::Point3f > &words3B=std::map< int, cv::Point3f >(), double *varianceOut=0, std::vector< int > *matchesOut=0, std::vector< int > *inliersOut=0) |
Transform RTABMAP_EXP | estimateMotion3DTo3D (const std::map< int, cv::Point3f > &words3A, const std::map< int, cv::Point3f > &words3B, int minInliers=10, double inliersDistance=0.1, int iterations=100, int refineIterations=5, double *varianceOut=0, std::vector< int > *matchesOut=0, std::vector< int > *inliersOut=0) |
std::vector< pcl::IndicesPtr > RTABMAP_EXP | extractClusters (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float clusterTolerance, int minClusterSize, int maxClusterSize=std::numeric_limits< int >::max(), int *biggestClusterIndex=0) |
std::vector< pcl::IndicesPtr > RTABMAP_EXP | extractClusters (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float clusterTolerance, int minClusterSize, int maxClusterSize=std::numeric_limits< int >::max(), int *biggestClusterIndex=0) |
std::vector< pcl::IndicesPtr > RTABMAP_EXP | extractClusters (const pcl::PointCloud< pcl::PointXYZ >::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. | |
std::vector< pcl::IndicesPtr > RTABMAP_EXP | extractClusters (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, float clusterTolerance, int minClusterSize, int maxClusterSize=std::numeric_limits< int >::max(), int *biggestClusterIndex=0) |
std::vector< pcl::IndicesPtr > RTABMAP_EXP | extractClusters (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float clusterTolerance, int minClusterSize, int maxClusterSize=std::numeric_limits< int >::max(), int *biggestClusterIndex=0) |
pcl::IndicesPtr RTABMAP_EXP | extractIndices (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative) |
pcl::IndicesPtr RTABMAP_EXP | extractIndices (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative) |
pcl::IndicesPtr RTABMAP_EXP | extractIndices (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative) |
pcl::PointCloud< pcl::PointXYZ > ::Ptr RTABMAP_EXP | extractIndices (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative, bool keepOrganized) |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr RTABMAP_EXP | extractIndices (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative, bool keepOrganized) |
pcl::PointCloud < pcl::PointXYZRGBNormal > ::Ptr RTABMAP_EXP | extractIndices (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative, bool keepOrganized) |
pcl::IndicesPtr | extractPlane (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float distanceThreshold, int maxIterations=100, pcl::ModelCoefficients *coefficientsOut=0) |
pcl::IndicesPtr | extractPlane (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float distanceThreshold, int maxIterations=100, pcl::ModelCoefficients *coefficientsOut=0) |
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 | fillProjectedCloudHoles (cv::Mat &depthRegistered, bool verticalDirection, bool fillToBorder) |
std::vector< pcl::Vertices > RTABMAP_EXP | filterCloseVerticesFromMesh (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr cloud, const std::vector< pcl::Vertices > &polygons, float radius, float angle, bool keepLatestInRadius) |
std::vector< pcl::Vertices > RTABMAP_EXP | filterInvalidPolygons (const std::vector< pcl::Vertices > &polygons) |
void RTABMAP_EXP | filterMaxDepth (pcl::PointCloud< pcl::PointXYZ > &inliers1, pcl::PointCloud< pcl::PointXYZ > &inliers2, float maxDepth, char depthAxis, bool removeDuplicates) |
std::map< int, int > RTABMAP_EXP | filterNotUsedVerticesFromMesh (const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloud, const std::vector< pcl::Vertices > &polygons, pcl::PointCloud< pcl::PointXYZRGBNormal > &outputCloud, std::vector< pcl::Vertices > &outputPolygons) |
std::map< int, int > RTABMAP_EXP | filterNotUsedVerticesFromMesh (const pcl::PointCloud< pcl::PointXYZRGB > &cloud, const std::vector< pcl::Vertices > &polygons, pcl::PointCloud< pcl::PointXYZRGB > &outputCloud, std::vector< pcl::Vertices > &outputPolygons) |
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, cv::Point3f > &words1, const std::multimap< int, cv::Point3f > &words2, std::vector< cv::Point3f > &inliers1, std::vector< cv::Point3f > &inliers2, float maxDepth, std::vector< int > *uniqueCorrespondences=0) |
void RTABMAP_EXP | findCorrespondences (const std::map< int, cv::Point3f > &words1, const std::map< int, cv::Point3f > &words2, std::vector< cv::Point3f > &inliers1, std::vector< cv::Point3f > &inliers2, float maxDepth, std::vector< int > *correspondences=0) |
pcl::IndicesPtr RTABMAP_EXP | frustumFiltering (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, const Transform &cameraPose, float horizontalFOV, float verticalFOV, float nearClipPlaneDistance, float farClipPlaneDistance, bool negative=false) |
pcl::PointCloud< pcl::PointXYZ > ::Ptr RTABMAP_EXP | frustumFiltering (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &cameraPose, float horizontalFOV, float verticalFOV, float nearClipPlaneDistance, float farClipPlaneDistance, bool negative=false) |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr RTABMAP_EXP | frustumFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const Transform &cameraPose, float horizontalFOV, float verticalFOV, float nearClipPlaneDistance, float farClipPlaneDistance, bool negative=false) |
std::vector< cv::Point3f > RTABMAP_EXP | generateKeypoints3DDepth (const std::vector< cv::KeyPoint > &keypoints, const cv::Mat &depth, const CameraModel &cameraModel, float minDepth=0, float maxDepth=0) |
std::vector< cv::Point3f > RTABMAP_EXP | generateKeypoints3DDepth (const std::vector< cv::KeyPoint > &keypoints, const cv::Mat &depth, const std::vector< CameraModel > &cameraModels, float minDepth=0, float maxDepth=0) |
std::vector< cv::Point3f > RTABMAP_EXP | generateKeypoints3DDisparity (const std::vector< cv::KeyPoint > &keypoints, const cv::Mat &disparity, const StereoCameraModel &stereoCameraModel, float minDepth=0, float maxDepth=0) |
std::vector< cv::Point3f > RTABMAP_EXP | generateKeypoints3DStereo (const std::vector< cv::Point2f > &leftCorners, const std::vector< cv::Point2f > &rightCorners, const StereoCameraModel &model, const std::vector< unsigned char > &mask=std::vector< unsigned char >(), float minDepth=0, float maxDepth=0) |
std::map< int, cv::Point3f > RTABMAP_EXP | generateWords3DMono (const std::map< int, cv::KeyPoint > &kpts, const std::map< int, cv::KeyPoint > &previousKpts, const CameraModel &cameraModel, Transform &cameraTransform, int pnpIterations=100, float pnpReprojError=8.0f, int pnpFlags=0, int pnpRefineIterations=1, float ransacParam1=3.0f, float ransacParam2=0.99f, const std::map< int, cv::Point3f > &refGuess3D=std::map< int, cv::Point3f >(), double *variance=0) |
int RTABMAP_EXP | getCorrespondencesCount (const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_source, const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_target, float maxDistance) |
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, pcl::PointCloud< pcl::PointXYZ > &cloud_source_registered, float epsilon=0.0f, bool icp2D=false) |
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, pcl::PointCloud< pcl::PointNormal > &cloud_source_registered, float epsilon=0.0f, bool icp2D=false) |
bool RTABMAP_EXP | isFinite (const cv::Point3f &pt) |
cv::Mat RTABMAP_EXP | laserScan2dFromPointCloud (const pcl::PointCloud< pcl::PointXYZ > &cloud, const Transform &transform=Transform()) |
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()) |
cv::Mat RTABMAP_EXP | laserScanFromPointCloud (const pcl::PointCloud< pcl::PointXYZ > &cloud, const Transform &transform=Transform()) |
cv::Mat RTABMAP_EXP | laserScanFromPointCloud (const pcl::PointCloud< pcl::PointNormal > &cloud, const Transform &transform=Transform()) |
pcl::PointCloud< pcl::PointXYZ > ::Ptr RTABMAP_EXP | laserScanToPointCloud (const cv::Mat &laserScan, const Transform &transform=Transform()) |
pcl::PointCloud < pcl::PointNormal >::Ptr RTABMAP_EXP | laserScanToPointCloudNormal (const cv::Mat &laserScan, const Transform &transform=Transform()) |
pcl::PointCloud< pcl::PointXYZ > ::Ptr RTABMAP_EXP | loadBINCloud (const std::string &fileName, int dim) |
pcl::PointCloud< pcl::PointXYZ > ::Ptr RTABMAP_EXP | loadCloud (const std::string &path, const Transform &transform=Transform::getIdentity(), int downsampleStep=1, float voxelSize=0.0f) |
cv::Mat RTABMAP_EXP | loadScan (const std::string &path, const Transform &transform=Transform::getIdentity(), int downsampleStep=1, float voxelSize=0.0f, int normalsK=0) |
pcl::PolygonMesh::Ptr RTABMAP_EXP | meshDecimation (const pcl::PolygonMesh::Ptr &mesh, float factor) |
pcl::PointCloud < pcl::PointXYZRGBNormal > ::Ptr RTABMAP_EXP | mls (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float searchRadius=0.0f, int polygonialOrder=2, int upsamplingMethod=0, float upsamplingRadius=0.0f, float upsamplingStep=0.0f, int pointDensity=0, float dilationVoxelSize=1.0f, int dilationIterations=0) |
pcl::PointCloud < pcl::PointXYZRGBNormal > ::Ptr RTABMAP_EXP | mls (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, float searchRadius=0.0f, int polygonialOrder=2, int upsamplingMethod=0, float upsamplingRadius=0.0f, float upsamplingStep=0.0f, int pointDensity=0, float dilationVoxelSize=1.0f, int dilationIterations=0) |
pcl::IndicesPtr RTABMAP_EXP | normalFiltering (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint) |
pcl::IndicesPtr RTABMAP_EXP | normalFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint) |
pcl::IndicesPtr RTABMAP_EXP | normalFiltering (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint) |
Given a normal and a maximum angle error, keep all points of the cloud respecting this normal. | |
pcl::IndicesPtr RTABMAP_EXP | normalFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint) |
pcl::IndicesPtr RTABMAP_EXP | normalFiltering (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint) |
template<typename pointT > | |
std::vector< pcl::Vertices > | normalizePolygonsSide (const pcl::PointCloud< pointT > &cloud, const std::vector< pcl::Vertices > &polygons, const pcl::PointXYZ &viewPoint=pcl::PointXYZ(0, 0, 0)) |
template<typename PointT > | |
void | occupancy2DFromCloud3D (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, cv::Mat &ground, cv::Mat &obstacles, float cellSize, float groundNormalAngle, int minClusterSize, bool segmentFlatObstacles, float maxGroundHeight) |
template<typename PointT > | |
void | occupancy2DFromCloud3D (const typename pcl::PointCloud< PointT >::Ptr &cloud, cv::Mat &ground, cv::Mat &obstacles, float cellSize, float groundNormalAngle, int minClusterSize, bool segmentFlatObstacles, float maxGroundHeight) |
template<typename PointT > | |
void | occupancy2DFromGroundObstacles (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &groundIndices, const pcl::IndicesPtr &obstaclesIndices, cv::Mat &ground, cv::Mat &obstacles, float cellSize) |
template<typename PointT > | |
void | occupancy2DFromGroundObstacles (const typename pcl::PointCloud< PointT >::Ptr &groundCloud, const typename pcl::PointCloud< PointT >::Ptr &obstaclesCloud, cv::Mat &ground, cv::Mat &obstacles, float cellSize) |
void RTABMAP_EXP | occupancy2DFromLaserScan (const cv::Mat &scan, cv::Mat &ground, cv::Mat &obstacles, float cellSize, bool unknownSpaceFilled=false, float scanMaxRange=0.0f) |
std::vector< pcl::Vertices > RTABMAP_EXP | organizedFastMesh (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, double angleTolerance=M_PI/16, bool quad=true, int trianglePixelSize=2, const Eigen::Vector3f &viewpoint=Eigen::Vector3f(0, 0, 0)) |
std::vector< pcl::Vertices > RTABMAP_EXP | organizedFastMesh (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, double angleTolerance=M_PI/16, bool quad=true, int trianglePixelSize=2, const Eigen::Vector3f &viewpoint=Eigen::Vector3f(0, 0, 0)) |
pcl::IndicesPtr RTABMAP_EXP | passThrough (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false) |
pcl::IndicesPtr RTABMAP_EXP | passThrough (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false) |
pcl::PointCloud< pcl::PointXYZ > ::Ptr RTABMAP_EXP | passThrough (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const std::string &axis, float min, float max, bool negative=false) |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr RTABMAP_EXP | passThrough (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const std::string &axis, float min, float max, bool negative=false) |
template<typename PointT > | |
pcl::PointCloud< PointT >::Ptr | projectCloudOnXYPlane (const typename pcl::PointCloud< PointT > &cloud) |
cv::Mat RTABMAP_EXP | projectCloudToCamera (const cv::Size &imageSize, const cv::Mat &cameraMatrixK, const cv::Mat &laserScan, const rtabmap::Transform &cameraTransform) |
cv::Mat RTABMAP_EXP | projectCloudToCamera (const cv::Size &imageSize, const cv::Mat &cameraMatrixK, const pcl::PointCloud< pcl::PointXYZ >::Ptr laserScan, const rtabmap::Transform &cameraTransform) |
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) |
cv::Point3f RTABMAP_EXP | projectDisparityTo3D (const cv::Point2f &pt, float disparity, const StereoCameraModel &model) |
cv::Point3f RTABMAP_EXP | projectDisparityTo3D (const cv::Point2f &pt, const cv::Mat &disparity, const StereoCameraModel &model) |
pcl::IndicesPtr RTABMAP_EXP | radiusFiltering (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius) |
pcl::IndicesPtr RTABMAP_EXP | radiusFiltering (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius) |
pcl::IndicesPtr RTABMAP_EXP | radiusFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius) |
pcl::IndicesPtr RTABMAP_EXP | radiusFiltering (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius) |
pcl::IndicesPtr RTABMAP_EXP | radiusFiltering (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float radiusSearch, int minNeighborsInRadius) |
Wrapper of the pcl::RadiusOutlierRemoval class. | |
pcl::IndicesPtr RTABMAP_EXP | radiusFiltering (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float radiusSearch, int minNeighborsInRadius) |
pcl::IndicesPtr RTABMAP_EXP | radiusFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, float radiusSearch, int minNeighborsInRadius) |
pcl::IndicesPtr RTABMAP_EXP | radiusFiltering (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float radiusSearch, int minNeighborsInRadius) |
pcl::PointCloud< pcl::PointXYZ > ::Ptr RTABMAP_EXP | randomSampling (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int samples) |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr RTABMAP_EXP | randomSampling (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, int samples) |
void RTABMAP_EXP | rayTrace (const cv::Point2i &start, const cv::Point2i &end, cv::Mat &grid, bool stopOnObstacle) |
pcl::PointCloud< pcl::PointXYZ > ::Ptr RTABMAP_EXP | removeNaNFromPointCloud (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud) |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr RTABMAP_EXP | removeNaNFromPointCloud (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud) |
pcl::PointCloud < pcl::PointNormal >::Ptr RTABMAP_EXP | removeNaNNormalsFromPointCloud (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud) |
pcl::PointCloud < pcl::PointXYZRGBNormal > ::Ptr RTABMAP_EXP | removeNaNNormalsFromPointCloud (const pcl::PointCloud< pcl::PointXYZRGBNormal >::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) |
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.") | |
RTABMAP_DEPRECATED (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, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0),"Use cloudFromDepthRGB with CameraModel interface.") | |
void RTABMAP_EXP | savePCDWords (const std::string &fileName, const std::multimap< int, pcl::PointXYZ > &words, const Transform &transform=Transform::getIdentity()) |
void RTABMAP_EXP | savePCDWords (const std::string &fileName, const std::multimap< int, cv::Point3f > &words, const Transform &transform=Transform::getIdentity()) |
template<typename PointT > | |
void | segmentObstaclesFromGround (const typename pcl::PointCloud< PointT >::Ptr &cloud, const typename pcl::IndicesPtr &indices, pcl::IndicesPtr &ground, pcl::IndicesPtr &obstacles, int normalKSearch, float groundNormalAngle, float clusterRadius, int minClusterSize, bool segmentFlatObstacles, float maxGroundHeight, pcl::IndicesPtr *flatObstacles, const Eigen::Vector4f &viewPoint) |
template<typename PointT > | |
void | segmentObstaclesFromGround (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, pcl::IndicesPtr &ground, pcl::IndicesPtr &obstacles, int normalKSearch, float groundNormalAngle, float clusterRadius, int minClusterSize, bool segmentFlatObstacles=false, float maxGroundHeight=0.0f, pcl::IndicesPtr *flatObstacles=0, const Eigen::Vector4f &viewPoint=Eigen::Vector4f(0, 0, 100, 0)) |
template<typename PointT > | |
void | segmentObstaclesFromGround (const typename pcl::PointCloud< PointT >::Ptr &cloud, pcl::IndicesPtr &ground, pcl::IndicesPtr &obstacles, int normalKSearch, float groundNormalAngle, float clusterRadius, int minClusterSize, bool segmentFlatObstacles, float maxGroundHeight, pcl::IndicesPtr *flatObstacles, const Eigen::Vector4f &viewPoint) |
void RTABMAP_EXP | solvePnPRansac (const std::vector< cv::Point3f > &objectPoints, const std::vector< cv::Point2f > &imagePoints, const cv::Mat &cameraMatrix, const cv::Mat &distCoeffs, cv::Mat &rvec, cv::Mat &tvec, bool useExtrinsicGuess, int iterationsCount, float reprojectionError, int minInliersCount, std::vector< int > &inliers, int flags, int refineIterations=1, float refineSigma=3.0f) |
pcl::IndicesPtr RTABMAP_EXP | subtractAdaptiveFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &substractCloud, const pcl::IndicesPtr &substractIndices, float radiusSearchRatio=0.01, int minNeighborsInRadius=1, const Eigen::Vector3f &viewpoint=Eigen::Vector3f(0, 0, 0)) |
pcl::IndicesPtr RTABMAP_EXP | subtractAdaptiveFiltering (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &substractCloud, const pcl::IndicesPtr &substractIndices, float radiusSearchRatio=0.01, float maxAngle=M_PI/4.0f, int minNeighborsInRadius=1, const Eigen::Vector3f &viewpoint=Eigen::Vector3f(0, 0, 0)) |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr RTABMAP_EXP | subtractFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &substractCloud, float radiusSearch, int minNeighborsInRadius=1) |
pcl::IndicesPtr RTABMAP_EXP | subtractFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &substractCloud, const pcl::IndicesPtr &substractIndices, float radiusSearch, int minNeighborsInRadius=1) |
pcl::PointCloud < pcl::PointNormal >::Ptr RTABMAP_EXP | subtractFiltering (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::PointCloud< pcl::PointNormal >::Ptr &substractCloud, float radiusSearch, float maxAngle=M_PI/4.0f, int minNeighborsInRadius=1) |
pcl::IndicesPtr RTABMAP_EXP | subtractFiltering (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const pcl::PointCloud< pcl::PointNormal >::Ptr &substractCloud, const pcl::IndicesPtr &substractIndices, float radiusSearch, float maxAngle=M_PI/4.0f, int minNeighborsInRadius=1) |
pcl::PointCloud < pcl::PointXYZRGBNormal > ::Ptr RTABMAP_EXP | subtractFiltering (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &substractCloud, float radiusSearch, float maxAngle=M_PI/4.0f, int minNeighborsInRadius=1) |
pcl::IndicesPtr RTABMAP_EXP | subtractFiltering (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &substractCloud, const pcl::IndicesPtr &substractIndices, float radiusSearch, float maxAngle=M_PI/4.0f, int minNeighborsInRadius=1) |
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, int refineModelIterations=10, double refineModelSigma=3.0, std::vector< int > *inliers=0, double *variance=0) |
Transform RTABMAP_EXP | transformFromXYZCorrespondencesSVD (const pcl::PointCloud< pcl::PointXYZ > &cloud1, const pcl::PointCloud< pcl::PointXYZ > &cloud2) |
cv::Point3f RTABMAP_EXP | transformPoint (const cv::Point3f &pt, const Transform &transform) |
pcl::PointXYZ RTABMAP_EXP | transformPoint (const pcl::PointXYZ &pt, const Transform &transform) |
pcl::PointXYZRGB RTABMAP_EXP | transformPoint (const pcl::PointXYZRGB &pt, const Transform &transform) |
pcl::PointNormal RTABMAP_EXP | transformPoint (const pcl::PointNormal &point, const Transform &transform) |
pcl::PointCloud< pcl::PointXYZ > ::Ptr RTABMAP_EXP | transformPointCloud (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform) |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr RTABMAP_EXP | transformPointCloud (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const Transform &transform) |
pcl::PointCloud < pcl::PointNormal >::Ptr RTABMAP_EXP | transformPointCloud (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const Transform &transform) |
pcl::PointCloud < pcl::PointXYZRGBNormal > ::Ptr RTABMAP_EXP | transformPointCloud (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const Transform &transform) |
pcl::PointCloud< pcl::PointXYZ > ::Ptr | uniformSampling (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float voxelSize) |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr | uniformSampling (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float voxelSize) |
pcl::PointCloud < pcl::PointXYZRGBNormal > ::Ptr | uniformSampling (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, float voxelSize) |
pcl::PointCloud< pcl::PointXYZ > ::Ptr RTABMAP_EXP | voxelize (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize) |
pcl::PointCloud < pcl::PointNormal >::Ptr RTABMAP_EXP | voxelize (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize) |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr RTABMAP_EXP | voxelize (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize) |
pcl::PointCloud < pcl::PointXYZRGBNormal > ::Ptr RTABMAP_EXP | voxelize (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize) |
pcl::PointCloud< pcl::PointXYZ > ::Ptr RTABMAP_EXP | voxelize (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float voxelSize) |
pcl::PointCloud < pcl::PointNormal >::Ptr RTABMAP_EXP | voxelize (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, float voxelSize) |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr RTABMAP_EXP | voxelize (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float voxelSize) |
pcl::PointCloud < pcl::PointXYZRGBNormal > ::Ptr RTABMAP_EXP | voxelize (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, float voxelSize) |
void RTABMAP_EXP rtabmap::util3d::adjustNormalsToViewPoints | ( | const std::map< int, Transform > & | poses, |
const pcl::PointCloud< pcl::PointXYZ >::Ptr & | rawCloud, | ||
const std::vector< int > & | rawCameraIndices, | ||
pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud | ||
) |
void RTABMAP_EXP rtabmap::util3d::adjustNormalsToViewPoints | ( | const std::map< int, Transform > & | poses, |
const pcl::PointCloud< pcl::PointXYZ >::Ptr & | rawCloud, | ||
const std::vector< int > & | rawCameraIndices, | ||
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud | ||
) |
std::multimap< int, cv::KeyPoint > rtabmap::util3d::aggregate | ( | const std::list< int > & | wordIds, |
const std::vector< cv::KeyPoint > & | keypoints | ||
) |
Definition at line 481 of file util3d_features.cpp.
void RTABMAP_EXP rtabmap::util3d::appendMesh | ( | pcl::PointCloud< pcl::PointXYZRGBNormal > & | cloudA, |
std::vector< pcl::Vertices > & | polygonsA, | ||
const pcl::PointCloud< pcl::PointXYZRGBNormal > & | cloudB, | ||
const std::vector< pcl::Vertices > & | polygonsB | ||
) |
void RTABMAP_EXP rtabmap::util3d::appendMesh | ( | pcl::PointCloud< pcl::PointXYZRGB > & | cloudA, |
std::vector< pcl::Vertices > & | polygonsA, | ||
const pcl::PointCloud< pcl::PointXYZRGB > & | cloudB, | ||
const std::vector< pcl::Vertices > & | polygonsB | ||
) |
cv::Mat rtabmap::util3d::bgrFromCloud | ( | const pcl::PointCloud< pcl::PointXYZRGBA > & | cloud, |
bool | bgrOrder | ||
) |
Definition at line 48 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::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 at line 255 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, | ||
float | maxDepth, | ||
float | minDepth, | ||
std::vector< int > * | validIndices | ||
) |
Definition at line 242 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::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 at line 364 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, | ||
float | maxDepth, | ||
float | minDepth, | ||
std::vector< int > * | validIndices | ||
) |
Definition at line 350 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::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 at line 476 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::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 at line 561 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP rtabmap::util3d::cloudFromSensorData | ( | const SensorData & | sensorData, |
int | decimation = 1 , |
||
float | maxDepth = 0.0f , |
||
float | minDepth = 0.0f , |
||
std::vector< int > * | validIndices = 0 , |
||
const ParametersMap & | parameters = ParametersMap() |
||
) |
Definition at line 696 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::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 at line 645 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP rtabmap::util3d::cloudRGBFromSensorData | ( | const SensorData & | sensorData, |
int | decimation = 1 , |
||
float | maxDepth = 0.0f , |
||
float | minDepth = 0.0f , |
||
std::vector< int > * | validIndices = 0 , |
||
const ParametersMap & | parameters = ParametersMap() |
||
) |
Create an RGB cloud from the images contained in SensorData. If there is only one camera, the returned cloud is organized. Otherwise, all NaN points are removed and the cloud will be dense.
sensorData,the | sensor data. |
decimation,images | are decimated by this factor before projecting points to 3D. The factor should be a factor of the image width and height. |
maxDepth,maximum | depth of the projected points (farther points are set to null in case of an organized cloud). |
minDepth,minimum | depth of the projected points (closer points are set to null in case of an organized cloud). |
validIndices,the | indices of valid points in the cloud |
Definition at line 787 of file util3d.cpp.
pcl::PointCloud<pcl::Normal>::Ptr rtabmap::util3d::computeFastOrganizedNormals | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
float | maxDepthChangeFactor = 0.02f , |
||
float | normalSmoothingSize = 10.0f , |
||
const Eigen::Vector3f & | viewPoint = Eigen::Vector3f(0, 0, 0) |
||
) |
pcl::PointCloud<pcl::Normal>::Ptr rtabmap::util3d::computeFastOrganizedNormals | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | maxDepthChangeFactor = 0.02f , |
||
float | normalSmoothingSize = 10.0f , |
||
const Eigen::Vector3f & | viewPoint = Eigen::Vector3f(0, 0, 0) |
||
) |
pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP rtabmap::util3d::computeNormals | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
int | normalKSearch = 20 , |
||
const Eigen::Vector3f & | viewPoint = Eigen::Vector3f(0, 0, 0) |
||
) |
pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP rtabmap::util3d::computeNormals | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
int | normalKSearch = 20 , |
||
const Eigen::Vector3f & | viewPoint = Eigen::Vector3f(0, 0, 0) |
||
) |
pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP rtabmap::util3d::computeNormals | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
int | normalKSearch = 20 , |
||
const Eigen::Vector3f & | viewPoint = Eigen::Vector3f(0, 0, 0) |
||
) |
pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP rtabmap::util3d::computeNormals | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
int | normalKSearch = 20 , |
||
const Eigen::Vector3f & | viewPoint = Eigen::Vector3f(0, 0, 0) |
||
) |
std::vector<float> rtabmap::util3d::computeReprojErrors | ( | std::vector< cv::Point3f > | opoints, |
std::vector< cv::Point2f > | ipoints, | ||
const cv::Mat & | cameraMatrix, | ||
const cv::Mat & | distCoeffs, | ||
const cv::Mat & | rvec, | ||
const cv::Mat & | tvec, | ||
float | reprojErrorThreshold, | ||
std::vector< int > & | inliers | ||
) |
Definition at line 281 of file util3d_motion_estimation.cpp.
void rtabmap::util3d::computeVarianceAndCorrespondences | ( | const pcl::PointCloud< pcl::PointNormal >::ConstPtr & | cloudA, |
const pcl::PointCloud< pcl::PointNormal >::ConstPtr & | cloudB, | ||
double | maxCorrespondenceDistance, | ||
double & | variance, | ||
int & | correspondencesOut | ||
) |
Definition at line 236 of file util3d_registration.cpp.
void rtabmap::util3d::computeVarianceAndCorrespondences | ( | const pcl::PointCloud< pcl::PointXYZ >::ConstPtr & | cloudA, |
const pcl::PointCloud< pcl::PointXYZ >::ConstPtr & | cloudB, | ||
double | maxCorrespondenceDistance, | ||
double & | variance, | ||
int & | correspondencesOut | ||
) |
Definition at line 269 of file util3d_registration.cpp.
pcl::IndicesPtr rtabmap::util3d::concatenate | ( | const std::vector< pcl::IndicesPtr > & | indices | ) |
Concatenate a vector of indices to a single vector.
indices | the vector of indices to concatenate. |
Definition at line 1392 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.
indicesA | the first vector of indices to concatenate. |
indicesB | the second vector of indices to concatenate. |
Definition at line 1412 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::concatenateClouds | ( | const std::list< pcl::PointCloud< pcl::PointXYZ >::Ptr > & | clouds | ) |
Definition at line 1313 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::concatenateClouds | ( | const std::list< pcl::PointCloud< pcl::PointXYZRGB >::Ptr > & | clouds | ) |
Definition at line 1323 of file util3d.cpp.
pcl::TextureMesh::Ptr rtabmap::util3d::concatenateTextureMeshes | ( | const std::list< pcl::TextureMesh::Ptr > & | meshes | ) |
Definition at line 1333 of file util3d.cpp.
cv::Mat rtabmap::util3d::convertMap2Image8U | ( | const cv::Mat & | map8S | ) |
Definition at line 634 of file util3d_mapping.cpp.
int rtabmap::util3d::countUniquePairs | ( | const std::multimap< int, pcl::PointXYZ > & | wordsA, |
const std::multimap< int, pcl::PointXYZ > & | wordsB | ||
) |
Definition at line 208 of file util3d_correspondences.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, | ||
float | scanMaxRange | ||
) |
Create 2d Occupancy grid (CV_8S) -1 = unknown 0 = empty space 100 = obstacle
poses | |
scans | |
cellSize | m |
unknownSpaceFilled | if false no fill, otherwise a virtual laser sweeps the unknown space from each pose (stopping on detected obstacle) |
xMin | |
yMin | |
minMapSize | minimum map size in meters |
scanMaxRange | laser scan maximum range, would be set if unknownSpaceFilled=true |
Definition at line 395 of file util3d_mapping.cpp.
cv::Mat rtabmap::util3d::create2DMapFromOccupancyLocalMaps | ( | const std::map< int, Transform > & | posesIn, |
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
poses | |
occupancy | <empty, occupied> |
cellSize | m |
xMin | |
yMin | |
minMapSize | minimum width (m) |
erode |
Definition at line 125 of file util3d_mapping.cpp.
pcl::PolygonMesh::Ptr RTABMAP_EXP 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 = true |
||
) |
void RTABMAP_EXP rtabmap::util3d::createPolygonIndexes | ( | const std::vector< pcl::Vertices > & | polygons, |
int | cloudSize, | ||
std::vector< std::set< int > > & | neighborPolygons, | ||
std::vector< std::set< int > > & | vertexPolygons | ||
) |
Given a set of polygons, create two indexes: polygons to neighbor polygons and vertices to polygons.
polygons | the polygons to be indexed. |
cloudSize | the size of the cloud of the corresponding mesh to polygons (must be at least as high as the highest vertex value contained in the polygons). |
neighborPolygons | returned index from polygons to neighbor polygons (index size = polygons size). |
vertexPolygons | returned index from vertices to polygons (index size = cloudSize). |
pcl::TextureMesh::Ptr RTABMAP_EXP rtabmap::util3d::createTextureMesh | ( | const pcl::PolygonMesh::Ptr & | mesh, |
const std::map< int, Transform > & | poses, | ||
const std::map< int, CameraModel > & | cameraModels, | ||
const std::map< int, cv::Mat > & | images, | ||
const std::string & | tmpDirectory = "." , |
||
int | kNormalSearch = 20 |
||
) |
cv::Mat rtabmap::util3d::depthFromCloud | ( | const pcl::PointCloud< pcl::PointXYZRGBA > & | cloud, |
float & | fx, | ||
float & | fy, | ||
bool | depth16U = true |
||
) |
Definition at line 74 of file util3d.cpp.
cv::Mat rtabmap::util3d::downsample | ( | const cv::Mat & | cloud, |
int | step | ||
) |
Definition at line 67 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::downsample | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
int | step | ||
) |
Definition at line 91 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::downsample | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
int | step | ||
) |
Definition at line 114 of file util3d_filtering.cpp.
Transform rtabmap::util3d::estimateMotion3DTo2D | ( | const std::map< int, cv::Point3f > & | words3A, |
const std::map< int, cv::KeyPoint > & | words2B, | ||
const CameraModel & | cameraModel, | ||
int | minInliers = 10 , |
||
int | iterations = 100 , |
||
double | reprojError = 5. , |
||
int | flagsPnP = 0 , |
||
int | pnpRefineIterations = 1 , |
||
const Transform & | guess = Transform::getIdentity() , |
||
const std::map< int, cv::Point3f > & | words3B = std::map<int, cv::Point3f>() , |
||
double * | varianceOut = 0 , |
||
std::vector< int > * | matchesOut = 0 , |
||
std::vector< int > * | inliersOut = 0 |
||
) |
Definition at line 50 of file util3d_motion_estimation.cpp.
Transform rtabmap::util3d::estimateMotion3DTo3D | ( | const std::map< int, cv::Point3f > & | words3A, |
const std::map< int, cv::Point3f > & | words3B, | ||
int | minInliers = 10 , |
||
double | inliersDistance = 0.1 , |
||
int | iterations = 100 , |
||
int | refineIterations = 5 , |
||
double * | varianceOut = 0 , |
||
std::vector< int > * | matchesOut = 0 , |
||
std::vector< int > * | inliersOut = 0 |
||
) |
Definition at line 201 of file util3d_motion_estimation.cpp.
std::vector< pcl::IndicesPtr > rtabmap::util3d::extractClusters | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
float | clusterTolerance, | ||
int | minClusterSize, | ||
int | maxClusterSize = std::numeric_limits<int>::max() , |
||
int * | biggestClusterIndex = 0 |
||
) |
For convenience.
Definition at line 1462 of file util3d_filtering.cpp.
std::vector< pcl::IndicesPtr > rtabmap::util3d::extractClusters | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
float | clusterTolerance, | ||
int | minClusterSize, | ||
int | maxClusterSize = std::numeric_limits<int>::max() , |
||
int * | biggestClusterIndex = 0 |
||
) |
Definition at line 1472 of file util3d_filtering.cpp.
std::vector< pcl::IndicesPtr > rtabmap::util3d::extractClusters | ( | const pcl::PointCloud< pcl::PointXYZ >::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.
cloud | the input cloud. |
indices | the input indices of the cloud to process, if empty, all points in the cloud are processed. |
clusterTolerance | the cluster distance tolerance (see pcl::EuclideanClusterExtraction). |
minClusterSize | minimum size of the clusters to return (see pcl::EuclideanClusterExtraction). |
maxClusterSize | maximum size of the clusters to return (see pcl::EuclideanClusterExtraction). |
biggestClusterIndex | the index of the biggest cluster, if the clusters are empty, a negative index is set. |
Definition at line 1483 of file util3d_filtering.cpp.
std::vector< pcl::IndicesPtr > rtabmap::util3d::extractClusters | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | clusterTolerance, | ||
int | minClusterSize, | ||
int | maxClusterSize = std::numeric_limits<int>::max() , |
||
int * | biggestClusterIndex = 0 |
||
) |
Definition at line 1535 of file util3d_filtering.cpp.
std::vector< pcl::IndicesPtr > rtabmap::util3d::extractClusters | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | clusterTolerance, | ||
int | minClusterSize, | ||
int | maxClusterSize = std::numeric_limits<int>::max() , |
||
int * | biggestClusterIndex = 0 |
||
) |
Definition at line 1587 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::extractIndices | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
bool | negative | ||
) |
Definition at line 1640 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::extractIndices | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
bool | negative | ||
) |
Definition at line 1653 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::extractIndices | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
bool | negative | ||
) |
Definition at line 1666 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::extractIndices | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
bool | negative, | ||
bool | keepOrganized | ||
) |
Definition at line 1680 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::extractIndices | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
bool | negative, | ||
bool | keepOrganized | ||
) |
Definition at line 1695 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr rtabmap::util3d::extractIndices | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
bool | negative, | ||
bool | keepOrganized | ||
) |
Definition at line 1710 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::extractPlane | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
float | distanceThreshold, | ||
int | maxIterations = 100 , |
||
pcl::ModelCoefficients * | coefficientsOut = 0 |
||
) |
Definition at line 1726 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::extractPlane | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | distanceThreshold, | ||
int | maxIterations = 100 , |
||
pcl::ModelCoefficients * | coefficientsOut = 0 |
||
) |
Definition at line 1736 of file util3d_filtering.cpp.
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 43 of file util3d_correspondences.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 136 of file util3d_correspondences.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 189 of file util3d_correspondences.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 198 of file util3d_correspondences.cpp.
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 167 of file util3d_correspondences.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 64 of file util3d_correspondences.cpp.
void rtabmap::util3d::fillProjectedCloudHoles | ( | cv::Mat & | depthRegistered, |
bool | verticalDirection, | ||
bool | fillToBorder | ||
) |
Definition at line 1225 of file util3d.cpp.
std::vector<pcl::Vertices> RTABMAP_EXP rtabmap::util3d::filterCloseVerticesFromMesh | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr | cloud, |
const std::vector< pcl::Vertices > & | polygons, | ||
float | radius, | ||
float | angle, | ||
bool | keepLatestInRadius | ||
) |
std::vector<pcl::Vertices> RTABMAP_EXP rtabmap::util3d::filterInvalidPolygons | ( | const std::vector< pcl::Vertices > & | polygons | ) |
void rtabmap::util3d::filterMaxDepth | ( | pcl::PointCloud< pcl::PointXYZ > & | inliers1, |
pcl::PointCloud< pcl::PointXYZ > & | inliers2, | ||
float | maxDepth, | ||
char | depthAxis, | ||
bool | removeDuplicates | ||
) |
Definition at line 225 of file util3d_correspondences.cpp.
std::map<int, int> RTABMAP_EXP rtabmap::util3d::filterNotUsedVerticesFromMesh | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal > & | cloud, |
const std::vector< pcl::Vertices > & | polygons, | ||
pcl::PointCloud< pcl::PointXYZRGBNormal > & | outputCloud, | ||
std::vector< pcl::Vertices > & | outputPolygons | ||
) |
std::map<int, int> RTABMAP_EXP rtabmap::util3d::filterNotUsedVerticesFromMesh | ( | const pcl::PointCloud< pcl::PointXYZRGB > & | cloud, |
const std::vector< pcl::Vertices > & | polygons, | ||
pcl::PointCloud< pcl::PointXYZRGB > & | outputCloud, | ||
std::vector< pcl::Vertices > & | outputPolygons | ||
) |
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 299 of file util3d_correspondences.cpp.
void rtabmap::util3d::findCorrespondences | ( | const std::multimap< int, cv::Point3f > & | words1, |
const std::multimap< int, cv::Point3f > & | words2, | ||
std::vector< cv::Point3f > & | inliers1, | ||
std::vector< cv::Point3f > & | inliers2, | ||
float | maxDepth, | ||
std::vector< int > * | uniqueCorrespondences = 0 |
||
) |
Definition at line 317 of file util3d_correspondences.cpp.
void rtabmap::util3d::findCorrespondences | ( | const std::map< int, cv::Point3f > & | words1, |
const std::map< int, cv::Point3f > & | words2, | ||
std::vector< cv::Point3f > & | inliers1, | ||
std::vector< cv::Point3f > & | inliers2, | ||
float | maxDepth, | ||
std::vector< int > * | correspondences = 0 |
||
) |
Definition at line 363 of file util3d_correspondences.cpp.
pcl::IndicesPtr rtabmap::util3d::frustumFiltering | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Transform & | cameraPose, | ||
float | horizontalFOV, | ||
float | verticalFOV, | ||
float | nearClipPlaneDistance, | ||
float | farClipPlaneDistance, | ||
bool | negative = false |
||
) |
Definition at line 343 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::frustumFiltering | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
const Transform & | cameraPose, | ||
float | horizontalFOV, | ||
float | verticalFOV, | ||
float | nearClipPlaneDistance, | ||
float | farClipPlaneDistance, | ||
bool | negative = false |
||
) |
Definition at line 376 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::frustumFiltering | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const Transform & | cameraPose, | ||
float | horizontalFOV, | ||
float | verticalFOV, | ||
float | nearClipPlaneDistance, | ||
float | farClipPlaneDistance, | ||
bool | negative = false |
||
) |
Definition at line 404 of file util3d_filtering.cpp.
std::vector< cv::Point3f > rtabmap::util3d::generateKeypoints3DDepth | ( | const std::vector< cv::KeyPoint > & | keypoints, |
const cv::Mat & | depth, | ||
const CameraModel & | cameraModel, | ||
float | minDepth = 0 , |
||
float | maxDepth = 0 |
||
) |
Definition at line 51 of file util3d_features.cpp.
std::vector< cv::Point3f > rtabmap::util3d::generateKeypoints3DDepth | ( | const std::vector< cv::KeyPoint > & | keypoints, |
const cv::Mat & | depth, | ||
const std::vector< CameraModel > & | cameraModels, | ||
float | minDepth = 0 , |
||
float | maxDepth = 0 |
||
) |
Definition at line 64 of file util3d_features.cpp.
std::vector< cv::Point3f > rtabmap::util3d::generateKeypoints3DDisparity | ( | const std::vector< cv::KeyPoint > & | keypoints, |
const cv::Mat & | disparity, | ||
const StereoCameraModel & | stereoCameraModel, | ||
float | minDepth = 0 , |
||
float | maxDepth = 0 |
||
) |
Definition at line 119 of file util3d_features.cpp.
std::vector< cv::Point3f > rtabmap::util3d::generateKeypoints3DStereo | ( | const std::vector< cv::Point2f > & | leftCorners, |
const std::vector< cv::Point2f > & | rightCorners, | ||
const StereoCameraModel & | model, | ||
const std::vector< unsigned char > & | mask = std::vector<unsigned char>() , |
||
float | minDepth = 0 , |
||
float | maxDepth = 0 |
||
) |
Definition at line 155 of file util3d_features.cpp.
std::map< int, cv::Point3f > rtabmap::util3d::generateWords3DMono | ( | const std::map< int, cv::KeyPoint > & | kpts, |
const std::map< int, cv::KeyPoint > & | previousKpts, | ||
const CameraModel & | cameraModel, | ||
Transform & | cameraTransform, | ||
int | pnpIterations = 100 , |
||
float | pnpReprojError = 8.0f , |
||
int | pnpFlags = 0 , |
||
int | pnpRefineIterations = 1 , |
||
float | ransacParam1 = 3.0f , |
||
float | ransacParam2 = 0.99f , |
||
const std::map< int, cv::Point3f > & | refGuess3D = std::map<int, cv::Point3f>() , |
||
double * | variance = 0 |
||
) |
Definition at line 206 of file util3d_features.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 275 of file util3d_correspondences.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, | ||
pcl::PointCloud< pcl::PointXYZ > & | cloud_source_registered, | ||
float | epsilon = 0.0f , |
||
bool | icp2D = false |
||
) |
Definition at line 303 of file util3d_registration.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, | ||
pcl::PointCloud< pcl::PointNormal > & | cloud_source_registered, | ||
float | epsilon = 0.0f , |
||
bool | icp2D = false |
||
) |
Definition at line 341 of file util3d_registration.cpp.
bool rtabmap::util3d::isFinite | ( | const cv::Point3f & | pt | ) |
Definition at line 1308 of file util3d.cpp.
cv::Mat rtabmap::util3d::laserScan2dFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZ > & | cloud, |
const Transform & | transform = Transform() |
||
) |
Definition at line 977 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZ > rtabmap::util3d::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 at line 886 of file util3d.cpp.
cv::Mat rtabmap::util3d::laserScanFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZ > & | cloud, |
const Transform & | transform = Transform() |
||
) |
Definition at line 922 of file util3d.cpp.
cv::Mat rtabmap::util3d::laserScanFromPointCloud | ( | const pcl::PointCloud< pcl::PointNormal > & | cloud, |
const Transform & | transform = Transform() |
||
) |
Definition at line 947 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::laserScanToPointCloud | ( | const cv::Mat & | laserScan, |
const Transform & | transform = Transform() |
||
) |
Definition at line 1000 of file util3d.cpp.
pcl::PointCloud< pcl::PointNormal >::Ptr rtabmap::util3d::laserScanToPointCloudNormal | ( | const cv::Mat & | laserScan, |
const Transform & | transform = Transform() |
||
) |
Definition at line 1036 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::loadBINCloud | ( | const std::string & | fileName, |
int | dim | ||
) |
Definition at line 1461 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::loadCloud | ( | const std::string & | path, |
const Transform & | transform = Transform::getIdentity() , |
||
int | downsampleStep = 1 , |
||
float | voxelSize = 0.0f |
||
) |
Definition at line 1521 of file util3d.cpp.
cv::Mat rtabmap::util3d::loadScan | ( | const std::string & | path, |
const Transform & | transform = Transform::getIdentity() , |
||
int | downsampleStep = 1 , |
||
float | voxelSize = 0.0f , |
||
int | normalsK = 0 |
||
) |
Definition at line 1497 of file util3d.cpp.
pcl::PolygonMesh::Ptr RTABMAP_EXP rtabmap::util3d::meshDecimation | ( | const pcl::PolygonMesh::Ptr & | mesh, |
float | factor | ||
) |
pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP rtabmap::util3d::mls | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
float | searchRadius = 0.0f , |
||
int | polygonialOrder = 2 , |
||
int | upsamplingMethod = 0 , |
||
float | upsamplingRadius = 0.0f , |
||
float | upsamplingStep = 0.0f , |
||
int | pointDensity = 0 , |
||
float | dilationVoxelSize = 1.0f , |
||
int | dilationIterations = 0 |
||
) |
pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP rtabmap::util3d::mls | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | searchRadius = 0.0f , |
||
int | polygonialOrder = 2 , |
||
int | upsamplingMethod = 0 , |
||
float | upsamplingRadius = 0.0f , |
||
float | upsamplingStep = 0.0f , |
||
int | pointDensity = 0 , |
||
float | dilationVoxelSize = 1.0f , |
||
int | dilationIterations = 0 |
||
) |
pcl::IndicesPtr rtabmap::util3d::normalFiltering | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
float | angleMax, | ||
const Eigen::Vector4f & | normal, | ||
int | normalKSearch, | ||
const Eigen::Vector4f & | viewpoint | ||
) |
For convenience.
Definition at line 1273 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::normalFiltering | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
float | angleMax, | ||
const Eigen::Vector4f & | normal, | ||
int | normalKSearch, | ||
const Eigen::Vector4f & | viewpoint | ||
) |
Definition at line 1283 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::normalFiltering | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | angleMax, | ||
const Eigen::Vector4f & | normal, | ||
int | normalKSearch, | ||
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.
cloud | the input cloud. |
indices | the input indices of the cloud to process, if empty, all points in the cloud are processed. |
angleMax | the maximum angle. |
normal | the normal to which each point's normal is compared. |
normalKSearch | number of neighbor points used for normal estimation (see pcl::NormalEstimation). |
viewpoint | from which viewpoint the normals should be estimated (see pcl::NormalEstimation). |
Definition at line 1296 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::normalFiltering | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | angleMax, | ||
const Eigen::Vector4f & | normal, | ||
int | normalKSearch, | ||
const Eigen::Vector4f & | viewpoint | ||
) |
Definition at line 1356 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::normalFiltering | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | angleMax, | ||
const Eigen::Vector4f & | normal, | ||
int | normalKSearch, | ||
const Eigen::Vector4f & | viewpoint | ||
) |
Definition at line 1416 of file util3d_filtering.cpp.
std::vector<pcl::Vertices> rtabmap::util3d::normalizePolygonsSide | ( | const pcl::PointCloud< pointT > & | cloud, |
const std::vector< pcl::Vertices > & | polygons, | ||
const pcl::PointXYZ & | viewPoint = pcl::PointXYZ(0,0,0) |
||
) |
Definition at line 194 of file util3d_surface.h.
void rtabmap::util3d::occupancy2DFromCloud3D | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
cv::Mat & | ground, | ||
cv::Mat & | obstacles, | ||
float | cellSize, | ||
float | groundNormalAngle, | ||
int | minClusterSize, | ||
bool | segmentFlatObstacles, | ||
float | maxGroundHeight | ||
) |
Definition at line 272 of file util3d_mapping.hpp.
void rtabmap::util3d::occupancy2DFromCloud3D | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
cv::Mat & | ground, | ||
cv::Mat & | obstacles, | ||
float | cellSize, | ||
float | groundNormalAngle, | ||
int | minClusterSize, | ||
bool | segmentFlatObstacles, | ||
float | maxGroundHeight | ||
) |
Definition at line 311 of file util3d_mapping.hpp.
void rtabmap::util3d::occupancy2DFromGroundObstacles | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
const pcl::IndicesPtr & | groundIndices, | ||
const pcl::IndicesPtr & | obstaclesIndices, | ||
cv::Mat & | ground, | ||
cv::Mat & | obstacles, | ||
float | cellSize | ||
) |
Definition at line 199 of file util3d_mapping.hpp.
void rtabmap::util3d::occupancy2DFromGroundObstacles | ( | const typename pcl::PointCloud< PointT >::Ptr & | groundCloud, |
const typename pcl::PointCloud< PointT >::Ptr & | obstaclesCloud, | ||
cv::Mat & | ground, | ||
cv::Mat & | obstacles, | ||
float | cellSize | ||
) |
Definition at line 229 of file util3d_mapping.hpp.
void rtabmap::util3d::occupancy2DFromLaserScan | ( | const cv::Mat & | scan, |
cv::Mat & | ground, | ||
cv::Mat & | obstacles, | ||
float | cellSize, | ||
bool | unknownSpaceFilled = false , |
||
float | scanMaxRange = 0.0f |
||
) |
Definition at line 48 of file util3d_mapping.cpp.
std::vector<pcl::Vertices> RTABMAP_EXP rtabmap::util3d::organizedFastMesh | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
double | angleTolerance = M_PI/16 , |
||
bool | quad = true , |
||
int | trianglePixelSize = 2 , |
||
const Eigen::Vector3f & | viewpoint = Eigen::Vector3f(0, 0, 0) |
||
) |
std::vector<pcl::Vertices> RTABMAP_EXP rtabmap::util3d::organizedFastMesh | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
double | angleTolerance = M_PI/16 , |
||
bool | quad = true , |
||
int | trianglePixelSize = 2 , |
||
const Eigen::Vector3f & | viewpoint = Eigen::Vector3f(0, 0, 0) |
||
) |
pcl::IndicesPtr rtabmap::util3d::passThrough | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const std::string & | axis, | ||
float | min, | ||
float | max, | ||
bool | negative = false |
||
) |
Definition at line 260 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::passThrough | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const std::string & | axis, | ||
float | min, | ||
float | max, | ||
bool | negative = false |
||
) |
Definition at line 281 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::passThrough | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
const std::string & | axis, | ||
float | min, | ||
float | max, | ||
bool | negative = false |
||
) |
Definition at line 303 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::passThrough | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const std::string & | axis, | ||
float | min, | ||
float | max, | ||
bool | negative = false |
||
) |
Definition at line 323 of file util3d_filtering.cpp.
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::projectCloudOnXYPlane | ( | const typename pcl::PointCloud< PointT > & | cloud | ) |
Definition at line 41 of file util3d_mapping.hpp.
cv::Mat rtabmap::util3d::projectCloudToCamera | ( | const cv::Size & | imageSize, |
const cv::Mat & | cameraMatrixK, | ||
const cv::Mat & | laserScan, | ||
const rtabmap::Transform & | cameraTransform | ||
) |
Definition at line 1114 of file util3d.cpp.
cv::Mat rtabmap::util3d::projectCloudToCamera | ( | const cv::Size & | imageSize, |
const cv::Mat & | cameraMatrixK, | ||
const pcl::PointCloud< pcl::PointXYZ >::Ptr | laserScan, | ||
const rtabmap::Transform & | cameraTransform | ||
) |
Definition at line 1179 of file util3d.cpp.
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 211 of file util3d.cpp.
cv::Point3f rtabmap::util3d::projectDisparityTo3D | ( | const cv::Point2f & | pt, |
float | disparity, | ||
const StereoCameraModel & | model | ||
) |
Definition at line 1075 of file util3d.cpp.
cv::Point3f rtabmap::util3d::projectDisparityTo3D | ( | const cv::Point2f & | pt, |
const cv::Mat & | disparity, | ||
const StereoCameraModel & | model | ||
) |
Definition at line 1095 of file util3d.cpp.
pcl::IndicesPtr rtabmap::util3d::radiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
float | radiusSearch, | ||
int | minNeighborsInRadius | ||
) |
For convenience.
Definition at line 470 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::radiusFiltering | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
float | radiusSearch, | ||
int | minNeighborsInRadius | ||
) |
Definition at line 478 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::radiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
float | radiusSearch, | ||
int | minNeighborsInRadius | ||
) |
Definition at line 486 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::radiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
float | radiusSearch, | ||
int | minNeighborsInRadius | ||
) |
Definition at line 494 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::radiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZ >::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.
cloud | the input cloud. |
indices | the input indices of the cloud to check, if empty, all points in the cloud are checked. |
radiusSearch | the radius in meter. |
minNeighborsInRadius | the minimum of neighbors to keep the point. |
Definition at line 504 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::radiusFiltering | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | radiusSearch, | ||
int | minNeighborsInRadius | ||
) |
Definition at line 549 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::radiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | radiusSearch, | ||
int | minNeighborsInRadius | ||
) |
Definition at line 594 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::radiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | radiusSearch, | ||
int | minNeighborsInRadius | ||
) |
Definition at line 639 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::randomSampling | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
int | samples | ||
) |
Definition at line 237 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::randomSampling | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
int | samples | ||
) |
Definition at line 248 of file util3d_filtering.cpp.
void rtabmap::util3d::rayTrace | ( | const cv::Point2i & | start, |
const cv::Point2i & | end, | ||
cv::Mat & | grid, | ||
bool | stopOnObstacle | ||
) |
Definition at line 552 of file util3d_mapping.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::removeNaNFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud | ) |
Definition at line 433 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::removeNaNFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud | ) |
Definition at line 441 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointNormal >::Ptr rtabmap::util3d::removeNaNNormalsFromPointCloud | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud | ) |
Definition at line 451 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr rtabmap::util3d::removeNaNNormalsFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud | ) |
Definition at line 459 of file util3d_filtering.cpp.
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 134 of file util3d.cpp.
cv::Mat RTABMAP_EXP rtabmap::util3d::rgbFromCloud | ( | const pcl::PointCloud< pcl::PointXYZRGBA > & | cloud, |
bool | bgrOrder = true |
||
) |
rtabmap::util3d::RTABMAP_DEPRECATED | ( | pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP | cloudFromDepthconst 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." | |||
) |
rtabmap::util3d::RTABMAP_DEPRECATED | ( | pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP | cloudFromDepthRGBconst cv::Mat &imageRgb, 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 cloudFromDepthRGB with CameraModel interface." | |||
) |
void rtabmap::util3d::savePCDWords | ( | const std::string & | fileName, |
const std::multimap< int, pcl::PointXYZ > & | words, | ||
const Transform & | transform = Transform::getIdentity() |
||
) |
Definition at line 1424 of file util3d.cpp.
void rtabmap::util3d::savePCDWords | ( | const std::string & | fileName, |
const std::multimap< int, cv::Point3f > & | words, | ||
const Transform & | transform = Transform::getIdentity() |
||
) |
Definition at line 1442 of file util3d.cpp.
void rtabmap::util3d::segmentObstaclesFromGround | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
const typename pcl::IndicesPtr & | indices, | ||
pcl::IndicesPtr & | ground, | ||
pcl::IndicesPtr & | obstacles, | ||
int | normalKSearch, | ||
float | groundNormalAngle, | ||
float | clusterRadius, | ||
int | minClusterSize, | ||
bool | segmentFlatObstacles, | ||
float | maxGroundHeight, | ||
pcl::IndicesPtr * | flatObstacles, | ||
const Eigen::Vector4f & | viewPoint | ||
) |
Definition at line 54 of file util3d_mapping.hpp.
void rtabmap::util3d::segmentObstaclesFromGround | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
pcl::IndicesPtr & | ground, | ||
pcl::IndicesPtr & | obstacles, | ||
int | normalKSearch, | ||
float | groundNormalAngle, | ||
float | clusterRadius, | ||
int | minClusterSize, | ||
bool | segmentFlatObstacles = false , |
||
float | maxGroundHeight = 0.0f , |
||
pcl::IndicesPtr * | flatObstacles = 0 , |
||
const Eigen::Vector4f & | viewPoint = Eigen::Vector4f(0, 0, 100, 0) |
||
) |
void rtabmap::util3d::segmentObstaclesFromGround | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
pcl::IndicesPtr & | ground, | ||
pcl::IndicesPtr & | obstacles, | ||
int | normalKSearch, | ||
float | groundNormalAngle, | ||
float | clusterRadius, | ||
int | minClusterSize, | ||
bool | segmentFlatObstacles, | ||
float | maxGroundHeight, | ||
pcl::IndicesPtr * | flatObstacles, | ||
const Eigen::Vector4f & | viewPoint | ||
) |
Definition at line 169 of file util3d_mapping.hpp.
void rtabmap::util3d::solvePnPRansac | ( | const std::vector< cv::Point3f > & | objectPoints, |
const std::vector< cv::Point2f > & | imagePoints, | ||
const cv::Mat & | cameraMatrix, | ||
const cv::Mat & | distCoeffs, | ||
cv::Mat & | rvec, | ||
cv::Mat & | tvec, | ||
bool | useExtrinsicGuess, | ||
int | iterationsCount, | ||
float | reprojectionError, | ||
int | minInliersCount, | ||
std::vector< int > & | inliers, | ||
int | flags, | ||
int | refineIterations = 1 , |
||
float | refineSigma = 3.0f |
||
) |
Definition at line 314 of file util3d_motion_estimation.cpp.
pcl::IndicesPtr rtabmap::util3d::subtractAdaptiveFiltering | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | substractCloud, | ||
const pcl::IndicesPtr & | substractIndices, | ||
float | radiusSearchRatio = 0.01 , |
||
int | minNeighborsInRadius = 1 , |
||
const Eigen::Vector3f & | viewpoint = Eigen::Vector3f(0,0,0) |
||
) |
Subtract a cloud from another one using radius filtering.
cloud | the input cloud. |
indices | the input indices of the cloud to check, if empty, all points in the cloud are checked. |
cloud | the input cloud to subtract. |
indices | the input indices of the subtracted cloud to check, if empty, all points in the cloud are checked. |
radiusSearchRatio | the ratio used to compute the radius at different distances (e.g., a ratio of 0.1 at 4 m results in a radius of 4 cm). |
Definition at line 1048 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::subtractAdaptiveFiltering | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | substractCloud, | ||
const pcl::IndicesPtr & | substractIndices, | ||
float | radiusSearchRatio = 0.01 , |
||
float | maxAngle = M_PI/4.0f , |
||
int | minNeighborsInRadius = 1 , |
||
const Eigen::Vector3f & | viewpoint = Eigen::Vector3f(0,0,0) |
||
) |
Subtract a cloud from another one using radius filtering.
cloud | the input cloud. |
indices | the input indices of the cloud to check, if empty, all points in the cloud are checked. |
cloud | the input cloud to subtract. |
indices | the input indices of the subtracted cloud to check, if empty, all points in the cloud are checked. |
radiusSearchRatio | the ratio used to compute the radius at different distances (e.g., a ratio of 0.01 at 4 m results in a radius of 4 cm). |
Definition at line 1127 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::subtractFiltering | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | substractCloud, | ||
float | radiusSearch, | ||
int | minNeighborsInRadius = 1 |
||
) |
For convenience.
Definition at line 685 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::subtractFiltering | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | substractCloud, | ||
const pcl::IndicesPtr & | substractIndices, | ||
float | radiusSearch, | ||
int | minNeighborsInRadius = 1 |
||
) |
Subtract a cloud from another one using radius filtering.
cloud | the input cloud. |
indices | the input indices of the cloud to check, if empty, all points in the cloud are checked. |
cloud | the input cloud to subtract. |
indices | the input indices of the subtracted cloud to check, if empty, all points in the cloud are checked. |
radiusSearch | the radius in meter. |
Definition at line 699 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointNormal >::Ptr rtabmap::util3d::subtractFiltering | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
const pcl::PointCloud< pcl::PointNormal >::Ptr & | substractCloud, | ||
float | radiusSearch, | ||
float | maxAngle = M_PI/4.0f , |
||
int | minNeighborsInRadius = 1 |
||
) |
For convenience.
Definition at line 762 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::subtractFiltering | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const pcl::PointCloud< pcl::PointNormal >::Ptr & | substractCloud, | ||
const pcl::IndicesPtr & | substractIndices, | ||
float | radiusSearch, | ||
float | maxAngle = M_PI/4.0f , |
||
int | minNeighborsInRadius = 1 |
||
) |
Subtract a cloud from another one using radius filtering.
cloud | the input cloud. |
indices | the input indices of the cloud to check, if empty, all points in the cloud are checked. |
cloud | the input cloud to subtract. |
indices | the input indices of the subtracted cloud to check, if empty, all points in the cloud are checked. |
radiusSearch | the radius in meter. |
Definition at line 777 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr rtabmap::util3d::subtractFiltering | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | substractCloud, | ||
float | radiusSearch, | ||
float | maxAngle = M_PI/4.0f , |
||
int | minNeighborsInRadius = 1 |
||
) |
For convenience.
Definition at line 905 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::subtractFiltering | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | substractCloud, | ||
const pcl::IndicesPtr & | substractIndices, | ||
float | radiusSearch, | ||
float | maxAngle = M_PI/4.0f , |
||
int | minNeighborsInRadius = 1 |
||
) |
Subtract a cloud from another one using radius filtering.
cloud | the input cloud. |
indices | the input indices of the cloud to check, if empty, all points in the cloud are checked. |
cloud | the input cloud to subtract. |
indices | the input indices of the subtracted cloud to check, if empty, all points in the cloud are checked. |
radiusSearch | the radius in meter. |
Definition at line 920 of file util3d_filtering.cpp.
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 , |
||
int | refineModelIterations = 10 , |
||
double | refineModelSigma = 3.0 , |
||
std::vector< int > * | inliers = 0 , |
||
double * | variance = 0 |
||
) |
Definition at line 61 of file util3d_registration.cpp.
Transform rtabmap::util3d::transformFromXYZCorrespondencesSVD | ( | const pcl::PointCloud< pcl::PointXYZ > & | cloud1, |
const pcl::PointCloud< pcl::PointXYZ > & | cloud2 | ||
) |
Definition at line 48 of file util3d_registration.cpp.
cv::Point3f rtabmap::util3d::transformPoint | ( | const cv::Point3f & | pt, |
const Transform & | transform | ||
) |
Definition at line 71 of file util3d_transforms.cpp.
pcl::PointXYZ rtabmap::util3d::transformPoint | ( | const pcl::PointXYZ & | pt, |
const Transform & | transform | ||
) |
Definition at line 81 of file util3d_transforms.cpp.
pcl::PointXYZRGB rtabmap::util3d::transformPoint | ( | const pcl::PointXYZRGB & | pt, |
const Transform & | transform | ||
) |
Definition at line 87 of file util3d_transforms.cpp.
pcl::PointNormal rtabmap::util3d::transformPoint | ( | const pcl::PointNormal & | point, |
const Transform & | transform | ||
) |
Definition at line 93 of file util3d_transforms.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::transformPointCloud | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
const Transform & | transform | ||
) |
Definition at line 38 of file util3d_transforms.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::transformPointCloud | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const Transform & | transform | ||
) |
Definition at line 46 of file util3d_transforms.cpp.
pcl::PointCloud< pcl::PointNormal >::Ptr rtabmap::util3d::transformPointCloud | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
const Transform & | transform | ||
) |
Definition at line 54 of file util3d_transforms.cpp.
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr rtabmap::util3d::transformPointCloud | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
const Transform & | transform | ||
) |
Definition at line 62 of file util3d_transforms.cpp.
pcl::PointCloud<pcl::PointXYZ>::Ptr rtabmap::util3d::uniformSampling | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
float | voxelSize | ||
) | [inline] |
Definition at line 84 of file util3d_filtering.h.
pcl::PointCloud<pcl::PointXYZRGB>::Ptr rtabmap::util3d::uniformSampling | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
float | voxelSize | ||
) | [inline] |
Definition at line 90 of file util3d_filtering.h.
pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr rtabmap::util3d::uniformSampling | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
float | voxelSize | ||
) | [inline] |
Definition at line 96 of file util3d_filtering.h.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::voxelize | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | voxelSize | ||
) |
Definition at line 138 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointNormal >::Ptr rtabmap::util3d::voxelize | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | voxelSize | ||
) |
Definition at line 155 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::voxelize | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | voxelSize | ||
) |
Definition at line 172 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr rtabmap::util3d::voxelize | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | voxelSize | ||
) |
Definition at line 189 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::voxelize | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
float | voxelSize | ||
) |
Definition at line 207 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointNormal >::Ptr rtabmap::util3d::voxelize | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
float | voxelSize | ||
) |
Definition at line 214 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::voxelize | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
float | voxelSize | ||
) |
Definition at line 221 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr rtabmap::util3d::voxelize | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
float | voxelSize | ||
) |
Definition at line 228 of file util3d_filtering.cpp.