Classes | |
class | ProjectionInfo |
Functions | |
RTABMAP_DEPRECATED LaserScan RTABMAP_CORE_EXPORT | adjustNormalsToViewPoint (const LaserScan &scan, const Eigen::Vector3f &viewpoint, bool forceGroundNormalsUp) |
LaserScan RTABMAP_CORE_EXPORT | adjustNormalsToViewPoint (const LaserScan &scan, const Eigen::Vector3f &viewpoint=Eigen::Vector3f(0, 0, 0), float groundNormalsUp=0.0f) |
RTABMAP_DEPRECATED void RTABMAP_CORE_EXPORT | adjustNormalsToViewPoint (pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const Eigen::Vector3f &viewpoint, bool forceGroundNormalsUp) |
void RTABMAP_CORE_EXPORT | adjustNormalsToViewPoint (pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const Eigen::Vector3f &viewpoint=Eigen::Vector3f(0, 0, 0), float groundNormalsUp=0.0f) |
RTABMAP_DEPRECATED void RTABMAP_CORE_EXPORT | adjustNormalsToViewPoint (pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const Eigen::Vector3f &viewpoint, bool forceGroundNormalsUp) |
void RTABMAP_CORE_EXPORT | adjustNormalsToViewPoint (pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const Eigen::Vector3f &viewpoint=Eigen::Vector3f(0, 0, 0), float groundNormalsUp=0.0f) |
RTABMAP_DEPRECATED void RTABMAP_CORE_EXPORT | adjustNormalsToViewPoint (pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const Eigen::Vector3f &viewpoint, bool forceGroundNormalsUp) |
void RTABMAP_CORE_EXPORT | adjustNormalsToViewPoint (pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const Eigen::Vector3f &viewpoint=Eigen::Vector3f(0, 0, 0), float groundNormalsUp=0.0f) |
template<typename PointNormalT > | |
void | adjustNormalsToViewPointImpl (typename pcl::PointCloud< PointNormalT >::Ptr &cloud, const Eigen::Vector3f &viewpoint, float groundNormalsUp) |
void RTABMAP_CORE_EXPORT | 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, float groundNormalsUp=0.0f) |
void RTABMAP_CORE_EXPORT | adjustNormalsToViewPoints (const std::map< int, Transform > &poses, const pcl::PointCloud< pcl::PointXYZ >::Ptr &rawCloud, const std::vector< int > &rawCameraIndices, pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, float groundNormalsUp=0.0f) |
void RTABMAP_CORE_EXPORT | 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, float groundNormalsUp=0.0f) |
void RTABMAP_CORE_EXPORT | adjustNormalsToViewPoints (const std::map< int, Transform > &viewpoints, const LaserScan &rawScan, const std::vector< int > &viewpointIds, LaserScan &scan, float groundNormalsUp=0.0f) |
template<typename PointT > | |
void | adjustNormalsToViewPointsImpl (const std::map< int, Transform > &poses, const pcl::PointCloud< pcl::PointXYZ >::Ptr &rawCloud, const std::vector< int > &rawCameraIndices, typename pcl::PointCloud< PointT >::Ptr &cloud, float groundNormalsUp) |
std::multimap< int, cv::KeyPoint > RTABMAP_CORE_EXPORT | aggregate (const std::list< int > &wordIds, const std::vector< cv::KeyPoint > &keypoints) |
void RTABMAP_CORE_EXPORT | appendMesh (pcl::PointCloud< pcl::PointXYZRGB > &cloudA, std::vector< pcl::Vertices > &polygonsA, const pcl::PointCloud< pcl::PointXYZRGB > &cloudB, const std::vector< pcl::Vertices > &polygonsB) |
void RTABMAP_CORE_EXPORT | appendMesh (pcl::PointCloud< pcl::PointXYZRGBNormal > &cloudA, std::vector< pcl::Vertices > &polygonsA, const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloudB, const std::vector< pcl::Vertices > &polygonsB) |
pcl::PolygonMesh::Ptr RTABMAP_CORE_EXPORT | assemblePolygonMesh (const cv::Mat &cloudMat, const std::vector< std::vector< RTABMAP_PCL_INDEX > > &polygons) |
pcl::TextureMesh::Ptr RTABMAP_CORE_EXPORT | assembleTextureMesh (const cv::Mat &cloudMat, const std::vector< std::vector< std::vector< RTABMAP_PCL_INDEX > > > &polygons, const std::vector< std::vector< Eigen::Vector2f > > &texCoords, cv::Mat &textures, bool mergeTextures=false) |
cv::Mat | bgrFromCloud (const pcl::PointCloud< pcl::PointXYZRGBA > &cloud, bool bgrOrder) |
void RTABMAP_CORE_EXPORT | cleanTextureMesh (pcl::TextureMesh &textureMesh, int minClusterSize) |
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT | cloudFromDepth (const cv::Mat &imageDepth, const CameraModel &model, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0) |
RTABMAP_DEPRECATED pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT | 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) |
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT | 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) |
RTABMAP_DEPRECATED pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT | 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) |
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT | 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_CORE_EXPORT | 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_CORE_EXPORT | cloudFromSensorData (const SensorData &sensorData, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap &stereoParameters=ParametersMap(), const std::vector< float > &roiRatios=std::vector< float >()) |
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT | 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_CORE_EXPORT | cloudRGBFromSensorData (const SensorData &sensorData, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap &stereoParameters=ParametersMap(), const std::vector< float > &roiRatios=std::vector< float >()) |
std::vector< pcl::PointCloud< pcl::PointXYZ >::Ptr > RTABMAP_CORE_EXPORT | cloudsFromSensorData (const SensorData &sensorData, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< pcl::IndicesPtr > *validIndices=0, const ParametersMap &stereoParameters=ParametersMap(), const std::vector< float > &roiRatios=std::vector< float >()) |
std::vector< pcl::PointCloud< pcl::PointXYZRGB >::Ptr > RTABMAP_CORE_EXPORT | cloudsRGBFromSensorData (const SensorData &sensorData, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< pcl::IndicesPtr > *validIndices=0, const ParametersMap &stereoParameters=ParametersMap(), const std::vector< float > &roiRatios=std::vector< float >()) |
std::list< std::list< int > > RTABMAP_CORE_EXPORT | clusterPolygons (const std::vector< std::set< int > > &neighborPolygons, int minClusterSize=0) |
RTABMAP_DEPRECATED LaserScan RTABMAP_CORE_EXPORT | commonFiltering (const LaserScan &scan, int downsamplingStep, float rangeMin, float rangeMax, float voxelSize, int normalK, float normalRadius, bool forceGroundNormalsUp) |
LaserScan RTABMAP_CORE_EXPORT | commonFiltering (const LaserScan &scan, int downsamplingStep, float rangeMin=0.0f, float rangeMax=0.0f, float voxelSize=0.0f, int normalK=0, float normalRadius=0.0f, float groundNormalsUp=0.0f) |
pcl::PointCloud< pcl::Normal >::Ptr RTABMAP_CORE_EXPORT | 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_CORE_EXPORT | 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_CORE_EXPORT | computeFastOrganizedNormals2D (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int searchK=5, float searchRadius=0.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0)) |
pcl::PointCloud< pcl::Normal >::Ptr RTABMAP_CORE_EXPORT | computeFastOrganizedNormals2D (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, int searchK=5, float searchRadius=0.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0)) |
template<typename PointT > | |
pcl::PointCloud< pcl::Normal >::Ptr | computeFastOrganizedNormals2DImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, int searchK, float searchRadius, const Eigen::Vector3f &viewPoint) |
cv::Mat RTABMAP_CORE_EXPORT | computeNormals (const cv::Mat &laserScan, int searchK, float searchRadius) |
LaserScan | computeNormals (const LaserScan &laserScan, int searchK, float searchRadius) |
pcl::PointCloud< pcl::Normal >::Ptr RTABMAP_CORE_EXPORT | computeNormals (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, int searchK=20, float searchRadius=0.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0)) |
pcl::PointCloud< pcl::Normal >::Ptr RTABMAP_CORE_EXPORT | computeNormals (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int searchK=20, float searchRadius=0.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0)) |
pcl::PointCloud< pcl::Normal >::Ptr RTABMAP_CORE_EXPORT | computeNormals (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, const pcl::IndicesPtr &indices, int searchK=20, float searchRadius=0.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0)) |
pcl::PointCloud< pcl::Normal >::Ptr RTABMAP_CORE_EXPORT | computeNormals (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, int searchK=20, float searchRadius=0.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0)) |
pcl::PointCloud< pcl::Normal >::Ptr RTABMAP_CORE_EXPORT | computeNormals (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, int searchK=20, float searchRadius=0.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0)) |
pcl::PointCloud< pcl::Normal >::Ptr RTABMAP_CORE_EXPORT | computeNormals (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, int searchK=20, float searchRadius=0.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0)) |
pcl::PointCloud< pcl::Normal >::Ptr RTABMAP_CORE_EXPORT | computeNormals2D (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int searchK=5, float searchRadius=0.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0)) |
pcl::PointCloud< pcl::Normal >::Ptr RTABMAP_CORE_EXPORT | computeNormals2D (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, int searchK=5, float searchRadius=0.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0)) |
template<typename PointT > | |
pcl::PointCloud< pcl::Normal >::Ptr | computeNormals2DImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, int searchK, float searchRadius, const Eigen::Vector3f &viewPoint) |
float RTABMAP_CORE_EXPORT | computeNormalsComplexity (const LaserScan &scan, const Transform &t=Transform::getIdentity(), cv::Mat *pcaEigenVectors=0, cv::Mat *pcaEigenValues=0) |
float RTABMAP_CORE_EXPORT | computeNormalsComplexity (const pcl::PointCloud< pcl::Normal > &normals, const Transform &t=Transform::getIdentity(), bool is2d=false, cv::Mat *pcaEigenVectors=0, cv::Mat *pcaEigenValues=0) |
float RTABMAP_CORE_EXPORT | computeNormalsComplexity (const pcl::PointCloud< pcl::PointNormal > &cloud, const Transform &t=Transform::getIdentity(), bool is2d=false, cv::Mat *pcaEigenVectors=0, cv::Mat *pcaEigenValues=0) |
float RTABMAP_CORE_EXPORT | computeNormalsComplexity (const pcl::PointCloud< pcl::PointXYZINormal > &cloud, const Transform &t=Transform::getIdentity(), bool is2d=false, cv::Mat *pcaEigenVectors=0, cv::Mat *pcaEigenValues=0) |
float RTABMAP_CORE_EXPORT | computeNormalsComplexity (const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloud, const Transform &t=Transform::getIdentity(), bool is2d=false, cv::Mat *pcaEigenVectors=0, cv::Mat *pcaEigenValues=0) |
template<typename PointT > | |
pcl::PointCloud< pcl::Normal >::Ptr | computeNormalsImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, int searchK, float searchRadius, const Eigen::Vector3f &viewPoint) |
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_CORE_EXPORT | computeVarianceAndCorrespondences (const pcl::PointCloud< pcl::PointNormal >::ConstPtr &cloudA, const pcl::PointCloud< pcl::PointNormal >::ConstPtr &cloudB, double maxCorrespondenceDistance, double maxCorrespondenceAngle, double &variance, int &correspondencesOut, bool reciprocal) |
void RTABMAP_CORE_EXPORT | computeVarianceAndCorrespondences (const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloudA, const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloudB, double maxCorrespondenceDistance, double &variance, int &correspondencesOut, bool reciprocal) |
void RTABMAP_CORE_EXPORT | computeVarianceAndCorrespondences (const pcl::PointCloud< pcl::PointXYZI >::ConstPtr &cloudA, const pcl::PointCloud< pcl::PointXYZI >::ConstPtr &cloudB, double maxCorrespondenceDistance, double &variance, int &correspondencesOut, bool reciprocal) |
void RTABMAP_CORE_EXPORT | computeVarianceAndCorrespondences (const pcl::PointCloud< pcl::PointXYZINormal >::ConstPtr &cloudA, const pcl::PointCloud< pcl::PointXYZINormal >::ConstPtr &cloudB, double maxCorrespondenceDistance, double maxCorrespondenceAngle, double &variance, int &correspondencesOut, bool reciprocal) |
template<typename PointNormalT > | |
void | computeVarianceAndCorrespondencesImpl (const typename pcl::PointCloud< PointNormalT >::ConstPtr &cloudA, const typename pcl::PointCloud< PointNormalT >::ConstPtr &cloudB, double maxCorrespondenceDistance, double maxCorrespondenceAngle, double &variance, int &correspondencesOut, bool reciprocal) |
template<typename PointT > | |
void | computeVarianceAndCorrespondencesImpl (const typename pcl::PointCloud< PointT >::ConstPtr &cloudA, const typename pcl::PointCloud< PointT >::ConstPtr &cloudB, double maxCorrespondenceDistance, double &variance, int &correspondencesOut, bool reciprocal) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | concatenate (const pcl::IndicesPtr &indicesA, const pcl::IndicesPtr &indicesB) |
Concatenate two vector of indices to a single vector. More... | |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | concatenate (const std::vector< pcl::IndicesPtr > &indices) |
Concatenate a vector of indices to a single vector. More... | |
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT | concatenateClouds (const std::list< pcl::PointCloud< pcl::PointXYZ >::Ptr > &clouds) |
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT | concatenateClouds (const std::list< pcl::PointCloud< pcl::PointXYZRGB >::Ptr > &clouds) |
void RTABMAP_CORE_EXPORT | concatenateTextureMaterials (pcl::TextureMesh &mesh, const cv::Size &imageSize, int textureSize, int maxTextures, float &scale, std::vector< bool > *materialsKept=0) |
pcl::TextureMesh::Ptr RTABMAP_CORE_EXPORT | concatenateTextureMeshes (const std::list< pcl::TextureMesh::Ptr > &meshes) |
cv::Mat RTABMAP_CORE_EXPORT | convertImage8U2Map (const cv::Mat &map8U, bool pgmFormat=false) |
cv::Mat RTABMAP_CORE_EXPORT | convertMap2Image8U (const cv::Mat &map8S, bool pgmFormat=false) |
std::vector< std::vector< RTABMAP_PCL_INDEX > > RTABMAP_CORE_EXPORT | convertPolygonsFromPCL (const std::vector< pcl::Vertices > &polygons) |
std::vector< std::vector< std::vector< RTABMAP_PCL_INDEX > > > RTABMAP_CORE_EXPORT | convertPolygonsFromPCL (const std::vector< std::vector< pcl::Vertices > > &polygons) |
std::vector< pcl::Vertices > RTABMAP_CORE_EXPORT | convertPolygonsToPCL (const std::vector< std::vector< RTABMAP_PCL_INDEX > > &polygons) |
std::vector< std::vector< pcl::Vertices > > RTABMAP_CORE_EXPORT | convertPolygonsToPCL (const std::vector< std::vector< std::vector< RTABMAP_PCL_INDEX > > > &tex_polygons) |
int RTABMAP_CORE_EXPORT | countUniquePairs (const std::multimap< int, pcl::PointXYZ > &wordsA, const std::multimap< int, pcl::PointXYZ > &wordsB) |
RTABMAP_DEPRECATED cv::Mat RTABMAP_CORE_EXPORT | create2DMap (const std::map< int, Transform > &poses, const std::map< int, pcl::PointCloud< pcl::PointXYZ >::Ptr > &scans, const std::map< int, cv::Point3f > &viewpoints, float cellSize, bool unknownSpaceFilled, float &xMin, float &yMin, float minMapSize=0.0f, float scanMaxRange=0.0f) |
RTABMAP_DEPRECATED cv::Mat RTABMAP_CORE_EXPORT | 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_CORE_EXPORT | create2DMap (const std::map< int, Transform > &poses, const std::map< int, std::pair< cv::Mat, cv::Mat > > &scans, const std::map< int, cv::Point3f > &viewpoints, float cellSize, bool unknownSpaceFilled, float &xMin, float &yMin, float minMapSize=0.0f, float scanMaxRange=0.0f) |
cv::Mat RTABMAP_CORE_EXPORT | 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, float footprintRadius=0.0f) |
pcl::PolygonMesh::Ptr RTABMAP_CORE_EXPORT | 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_CORE_EXPORT | 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. More... | |
pcl::texture_mapping::CameraVector | createTextureCameras (const std::map< int, Transform > &poses, const std::map< int, std::vector< CameraModel > > &cameraModels, const std::map< int, cv::Mat > &cameraDepths, const std::vector< float > &roiRatios) |
pcl::TextureMesh::Ptr RTABMAP_CORE_EXPORT | createTextureMesh (const pcl::PolygonMesh::Ptr &mesh, const std::map< int, Transform > &poses, const std::map< int, CameraModel > &cameraModels, const std::map< int, cv::Mat > &cameraDepths, float maxDistance=0.0f, float maxDepthError=0.0f, float maxAngle=0.0f, int minClusterSize=50, const std::vector< float > &roiRatios=std::vector< float >(), const ProgressState *state=0, std::vector< std::map< int, pcl::PointXY > > *vertexToPixels=0, bool distanceToCamPolicy=false) |
pcl::TextureMesh::Ptr RTABMAP_CORE_EXPORT | createTextureMesh (const pcl::PolygonMesh::Ptr &mesh, const std::map< int, Transform > &poses, const std::map< int, std::vector< CameraModel > > &cameraModels, const std::map< int, cv::Mat > &cameraDepths, float maxDistance=0.0f, float maxDepthError=0.0f, float maxAngle=0.0f, int minClusterSize=50, const std::vector< float > &roiRatios=std::vector< float >(), const ProgressState *state=0, std::vector< std::map< int, pcl::PointXY > > *vertexToPixels=0, bool distanceToCamPolicy=false) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | cropBox (const pcl::PCLPointCloud2::Ptr &cloud, const pcl::IndicesPtr &indices, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false) |
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_CORE_EXPORT | cropBox (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | cropBox (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false) |
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT | cropBox (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | cropBox (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false) |
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_CORE_EXPORT | cropBox (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | cropBox (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, const pcl::IndicesPtr &indices, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false) |
pcl::PointCloud< pcl::PointXYZINormal >::Ptr RTABMAP_CORE_EXPORT | cropBox (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | cropBox (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false) |
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT | cropBox (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | cropBox (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false) |
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_CORE_EXPORT | cropBox (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | cropBox (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false) |
template<typename PointT > | |
pcl::PointCloud< PointT >::Ptr | cropBoxImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform, bool negative) |
template<typename PointT > | |
pcl::IndicesPtr | cropBoxImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform, bool negative) |
template<typename pointRGBT > | |
void | denseMeshPostProcessing (pcl::PolygonMeshPtr &mesh, float meshDecimationFactor, int maximumPolygons, const typename pcl::PointCloud< pointRGBT >::Ptr &cloud, float transferColorRadius, bool coloredOutput, bool cleanMesh, int minClusterSize, ProgressState *progressState) |
cv::Mat RTABMAP_CORE_EXPORT | depthFromCloud (const pcl::PointCloud< pcl::PointXYZRGBA > &cloud, float &fx, float &fy, bool depth16U=true) |
LaserScan RTABMAP_CORE_EXPORT | deskew (const LaserScan &input, double inputStamp, const rtabmap::Transform &velocity) |
Lidar deskewing. More... | |
LaserScan RTABMAP_CORE_EXPORT | downsample (const LaserScan &cloud, int step) |
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_CORE_EXPORT | downsample (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, int step) |
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT | downsample (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int step) |
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_CORE_EXPORT | downsample (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, int step) |
pcl::PointCloud< pcl::PointXYZINormal >::Ptr RTABMAP_CORE_EXPORT | downsample (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, int step) |
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT | downsample (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, int step) |
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_CORE_EXPORT | downsample (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, int step) |
template<typename PointT > | |
pcl::PointCloud< PointT >::Ptr | downsampleImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, int step) |
cv::Mat RTABMAP_CORE_EXPORT | erodeMap (const cv::Mat &map) |
Transform RTABMAP_CORE_EXPORT | 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, int varianceMedianRatio=4, float maxVariance=0, const Transform &guess=Transform::getIdentity(), const std::map< int, cv::Point3f > &words3B=std::map< int, cv::Point3f >(), cv::Mat *covariance=0, std::vector< int > *matchesOut=0, std::vector< int > *inliersOut=0, bool splitLinearCovarianceComponents=false) |
Transform RTABMAP_CORE_EXPORT | estimateMotion3DTo2D (const std::map< int, cv::Point3f > &words3A, const std::map< int, cv::KeyPoint > &words2B, const std::vector< CameraModel > &cameraModels, unsigned int samplingPolicy=0, int minInliers=10, int iterations=100, double reprojError=5., int flagsPnP=0, int pnpRefineIterations=1, int varianceMedianRatio=4, float maxVariance=0, const Transform &guess=Transform::getIdentity(), const std::map< int, cv::Point3f > &words3B=std::map< int, cv::Point3f >(), cv::Mat *covariance=0, std::vector< int > *matchesOut=0, std::vector< int > *inliersOut=0, bool splitLinearCovarianceComponents=false) |
Transform RTABMAP_CORE_EXPORT | 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, cv::Mat *covariance=0, std::vector< int > *matchesOut=0, std::vector< int > *inliersOut=0) |
std::vector< pcl::IndicesPtr > RTABMAP_CORE_EXPORT | extractClusters (const pcl::PointCloud< pcl::PointNormal >::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_CORE_EXPORT | 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. More... | |
std::vector< pcl::IndicesPtr > RTABMAP_CORE_EXPORT | 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_CORE_EXPORT | extractClusters (const pcl::PointCloud< pcl::PointXYZI >::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_CORE_EXPORT | extractClusters (const pcl::PointCloud< pcl::PointXYZINormal >::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_CORE_EXPORT | 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_CORE_EXPORT | 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_CORE_EXPORT | 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) |
template<typename PointT > | |
std::vector< pcl::IndicesPtr > | extractClustersImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, float clusterTolerance, int minClusterSize, int maxClusterSize, int *biggestClusterIndex) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | extractIndices (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | extractIndices (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative) |
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT | extractIndices (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative, bool keepOrganized) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | extractIndices (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative) |
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_CORE_EXPORT | extractIndices (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative, bool keepOrganized) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | extractIndices (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative) |
pcl::PointCloud< pcl::PointXYZINormal >::Ptr RTABMAP_CORE_EXPORT | extractIndices (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative, bool keepOrganized) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | extractIndices (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative) |
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT | extractIndices (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative, bool keepOrganized) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | extractIndices (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative) |
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_CORE_EXPORT | extractIndices (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative, bool keepOrganized) |
template<typename PointT > | |
pcl::IndicesPtr | extractIndicesImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative) |
template<typename PointT > | |
pcl::PointCloud< PointT >::Ptr | extractIndicesImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative, bool keepOrganized) |
pcl::IndicesPtr | extractPlane (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float distanceThreshold, int maxIterations=100, pcl::ModelCoefficients *coefficientsOut=0) |
pcl::IndicesPtr | extractPlane (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float distanceThreshold, int maxIterations=100, pcl::ModelCoefficients *coefficientsOut=0) |
void RTABMAP_CORE_EXPORT | 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_CORE_EXPORT | 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_CORE_EXPORT | 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) |
void RTABMAP_CORE_EXPORT | 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) |
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_CORE_EXPORT | 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_CORE_EXPORT | fillProjectedCloudHoles (cv::Mat &depthRegistered, bool verticalDirection, bool fillToBorder) |
std::vector< pcl::Vertices > RTABMAP_CORE_EXPORT | 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_CORE_EXPORT | filterInvalidPolygons (const std::vector< pcl::Vertices > &polygons) |
void RTABMAP_CORE_EXPORT | filterMaxDepth (pcl::PointCloud< pcl::PointXYZ > &inliers1, pcl::PointCloud< pcl::PointXYZ > &inliers2, float maxDepth, char depthAxis, bool removeDuplicates) |
std::vector< int > RTABMAP_CORE_EXPORT | filterNaNPointsFromMesh (const pcl::PointCloud< pcl::PointXYZRGB > &cloud, const std::vector< pcl::Vertices > &polygons, pcl::PointCloud< pcl::PointXYZRGB > &outputCloud, std::vector< pcl::Vertices > &outputPolygons) |
std::vector< int > RTABMAP_CORE_EXPORT | filterNotUsedVerticesFromMesh (const pcl::PointCloud< pcl::PointXYZRGB > &cloud, const std::vector< pcl::Vertices > &polygons, pcl::PointCloud< pcl::PointXYZRGB > &outputCloud, std::vector< pcl::Vertices > &outputPolygons) |
std::vector< int > RTABMAP_CORE_EXPORT | filterNotUsedVerticesFromMesh (const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloud, const std::vector< pcl::Vertices > &polygons, pcl::PointCloud< pcl::PointXYZRGBNormal > &outputCloud, std::vector< pcl::Vertices > &outputPolygons) |
void RTABMAP_CORE_EXPORT | 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) |
void RTABMAP_CORE_EXPORT | 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_CORE_EXPORT | 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_CORE_EXPORT | fixTextureMeshForVisualization (pcl::TextureMesh &textureMesh) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | 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_CORE_EXPORT | 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_CORE_EXPORT | frustumFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const Transform &cameraPose, float horizontalFOV, float verticalFOV, float nearClipPlaneDistance, float farClipPlaneDistance, bool negative=false) |
template<typename PointT > | |
pcl::IndicesPtr | frustumFilteringImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, const Transform &cameraPose, float horizontalFOV, float verticalFOV, float nearClipPlaneDistance, float farClipPlaneDistance, bool negative) |
template<typename PointT > | |
pcl::PointCloud< PointT >::Ptr | frustumFilteringImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const Transform &cameraPose, float horizontalFOV, float verticalFOV, float nearClipPlaneDistance, float farClipPlaneDistance, bool negative) |
int | gcd (int a, int b) |
std::vector< cv::Point3f > RTABMAP_CORE_EXPORT | 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_CORE_EXPORT | 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_CORE_EXPORT | 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_CORE_EXPORT | 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_CORE_EXPORT | generateWords3DMono (const std::map< int, cv::KeyPoint > &kpts, const std::map< int, cv::KeyPoint > &previousKpts, const CameraModel &cameraModel, Transform &cameraTransform, float ransacReprojThreshold=3.0f, float ransacConfidence=0.99f, const std::map< int, cv::Point3f > &refGuess3D=std::map< int, cv::Point3f >(), double *variance=0, std::vector< int > *matchesOut=0) |
int RTABMAP_CORE_EXPORT | getCorrespondencesCount (const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_source, const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_target, float maxDistance) |
void RTABMAP_CORE_EXPORT | getMinMax3D (const cv::Mat &laserScan, cv::Point3f &min, cv::Point3f &max) |
void RTABMAP_CORE_EXPORT | getMinMax3D (const cv::Mat &laserScan, pcl::PointXYZ &min, pcl::PointXYZ &max) |
Transform RTABMAP_CORE_EXPORT | 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_CORE_EXPORT | icp (const pcl::PointCloud< pcl::PointXYZI >::ConstPtr &cloud_source, const pcl::PointCloud< pcl::PointXYZI >::ConstPtr &cloud_target, double maxCorrespondenceDistance, int maximumIterations, bool &hasConverged, pcl::PointCloud< pcl::PointXYZI > &cloud_source_registered, float epsilon=0.0f, bool icp2D=false) |
template<typename PointT > | |
Transform | icpImpl (const typename pcl::PointCloud< PointT >::ConstPtr &cloud_source, const typename pcl::PointCloud< PointT >::ConstPtr &cloud_target, double maxCorrespondenceDistance, int maximumIterations, bool &hasConverged, pcl::PointCloud< PointT > &cloud_source_registered, float epsilon, bool icp2D) |
Transform RTABMAP_CORE_EXPORT | 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) |
Transform RTABMAP_CORE_EXPORT | icpPointToPlane (const pcl::PointCloud< pcl::PointXYZINormal >::ConstPtr &cloud_source, const pcl::PointCloud< pcl::PointXYZINormal >::ConstPtr &cloud_target, double maxCorrespondenceDistance, int maximumIterations, bool &hasConverged, pcl::PointCloud< pcl::PointXYZINormal > &cloud_source_registered, float epsilon=0.0f, bool icp2D=false) |
template<typename PointNormalT > | |
Transform | icpPointToPlaneImpl (const typename pcl::PointCloud< PointNormalT >::ConstPtr &cloud_source, const typename pcl::PointCloud< PointNormalT >::ConstPtr &cloud_target, double maxCorrespondenceDistance, int maximumIterations, bool &hasConverged, pcl::PointCloud< PointNormalT > &cloud_source_registered, float epsilon, bool icp2D) |
template<typename PointT > | |
bool | intersectRayMesh (const Eigen::Vector3f &origin, const Eigen::Vector3f &dir, const typename pcl::PointCloud< PointT > &cloud, const std::vector< pcl::Vertices > &polygons, bool ignoreBackFaces, float &distance, Eigen::Vector3f &normal, int &index) |
bool RTABMAP_CORE_EXPORT | intersectRayTriangle (const Eigen::Vector3f &p, const Eigen::Vector3f &dir, const Eigen::Vector3f &v0, const Eigen::Vector3f &v1, const Eigen::Vector3f &v2, float &distance, Eigen::Vector3f &normal) |
bool RTABMAP_CORE_EXPORT | isFinite (const cv::Point3f &pt) |
LaserScan RTABMAP_CORE_EXPORT | laserScan2dFromPointCloud (const pcl::PointCloud< pcl::PointNormal > &cloud, const Transform &transform=Transform(), bool filterNaNs=true) |
LaserScan RTABMAP_CORE_EXPORT | laserScan2dFromPointCloud (const pcl::PointCloud< pcl::PointXYZ > &cloud, const pcl::PointCloud< pcl::Normal > &normals, const Transform &transform=Transform(), bool filterNaNs=true) |
LaserScan RTABMAP_CORE_EXPORT | laserScan2dFromPointCloud (const pcl::PointCloud< pcl::PointXYZ > &cloud, const Transform &transform=Transform(), bool filterNaNs=true) |
LaserScan RTABMAP_CORE_EXPORT | laserScan2dFromPointCloud (const pcl::PointCloud< pcl::PointXYZI > &cloud, const pcl::PointCloud< pcl::Normal > &normals, const Transform &transform=Transform(), bool filterNaNs=true) |
LaserScan RTABMAP_CORE_EXPORT | laserScan2dFromPointCloud (const pcl::PointCloud< pcl::PointXYZI > &cloud, const Transform &transform=Transform(), bool filterNaNs=true) |
LaserScan RTABMAP_CORE_EXPORT | laserScan2dFromPointCloud (const pcl::PointCloud< pcl::PointXYZINormal > &cloud, const Transform &transform=Transform(), bool filterNaNs=true) |
pcl::PointCloud< pcl::PointXYZ > RTABMAP_CORE_EXPORT | laserScanFromDepthImage (const cv::Mat &depthImage, float fx, float fy, float cx, float cy, float maxDepth=0, float minDepth=0, const Transform &localTransform=Transform::getIdentity()) |
pcl::PointCloud< pcl::PointXYZ > RTABMAP_CORE_EXPORT | laserScanFromDepthImages (const cv::Mat &depthImages, const std::vector< CameraModel > &cameraModels, float maxDepth, float minDepth) |
LaserScan RTABMAP_CORE_EXPORT | laserScanFromPointCloud (const pcl::PointCloud< pcl::PointNormal > &cloud, const pcl::IndicesPtr &indices, const Transform &transform=Transform(), bool filterNaNs=true) |
LaserScan RTABMAP_CORE_EXPORT | laserScanFromPointCloud (const pcl::PointCloud< pcl::PointNormal > &cloud, const Transform &transform=Transform(), bool filterNaNs=true) |
LaserScan RTABMAP_CORE_EXPORT | laserScanFromPointCloud (const pcl::PointCloud< pcl::PointXYZ > &cloud, const pcl::IndicesPtr &indices, const Transform &transform=Transform(), bool filterNaNs=true) |
LaserScan RTABMAP_CORE_EXPORT | laserScanFromPointCloud (const pcl::PointCloud< pcl::PointXYZ > &cloud, const pcl::PointCloud< pcl::Normal > &normals, const Transform &transform=Transform(), bool filterNaNs=true) |
LaserScan RTABMAP_CORE_EXPORT | laserScanFromPointCloud (const pcl::PointCloud< pcl::PointXYZ > &cloud, const Transform &transform=Transform(), bool filterNaNs=true) |
LaserScan RTABMAP_CORE_EXPORT | laserScanFromPointCloud (const pcl::PointCloud< pcl::PointXYZI > &cloud, const pcl::IndicesPtr &indices, const Transform &transform=Transform(), bool filterNaNs=true) |
LaserScan RTABMAP_CORE_EXPORT | laserScanFromPointCloud (const pcl::PointCloud< pcl::PointXYZI > &cloud, const pcl::PointCloud< pcl::Normal > &normals, const Transform &transform=Transform(), bool filterNaNs=true) |
LaserScan RTABMAP_CORE_EXPORT | laserScanFromPointCloud (const pcl::PointCloud< pcl::PointXYZI > &cloud, const Transform &transform=Transform(), bool filterNaNs=true) |
LaserScan RTABMAP_CORE_EXPORT | laserScanFromPointCloud (const pcl::PointCloud< pcl::PointXYZINormal > &cloud, const pcl::IndicesPtr &indices, const Transform &transform=Transform(), bool filterNaNs=true) |
LaserScan RTABMAP_CORE_EXPORT | laserScanFromPointCloud (const pcl::PointCloud< pcl::PointXYZINormal > &cloud, const Transform &transform=Transform(), bool filterNaNs=true) |
LaserScan RTABMAP_CORE_EXPORT | laserScanFromPointCloud (const pcl::PointCloud< pcl::PointXYZRGB > &cloud, const pcl::IndicesPtr &indices, const Transform &transform=Transform(), bool filterNaNs=true) |
LaserScan RTABMAP_CORE_EXPORT | laserScanFromPointCloud (const pcl::PointCloud< pcl::PointXYZRGB > &cloud, const pcl::PointCloud< pcl::Normal > &normals, const Transform &transform=Transform(), bool filterNaNs=true) |
LaserScan RTABMAP_CORE_EXPORT | laserScanFromPointCloud (const pcl::PointCloud< pcl::PointXYZRGB > &cloud, const Transform &transform=Transform(), bool filterNaNs=true) |
LaserScan RTABMAP_CORE_EXPORT | laserScanFromPointCloud (const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloud, const pcl::IndicesPtr &indices, const Transform &transform=Transform(), bool filterNaNs=true) |
LaserScan RTABMAP_CORE_EXPORT | laserScanFromPointCloud (const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloud, const Transform &transform=Transform(), bool filterNaNs=true) |
template<typename PointCloud2T > | |
LaserScan | laserScanFromPointCloud (const PointCloud2T &cloud, bool filterNaNs, bool is2D, const Transform &transform) |
pcl::PointXYZ RTABMAP_CORE_EXPORT | laserScanToPoint (const LaserScan &laserScan, int index) |
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT | laserScanToPointCloud (const LaserScan &laserScan, const Transform &transform=Transform()) |
pcl::PCLPointCloud2::Ptr RTABMAP_CORE_EXPORT | laserScanToPointCloud2 (const LaserScan &laserScan, const Transform &transform=Transform()) |
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_CORE_EXPORT | laserScanToPointCloudI (const LaserScan &laserScan, const Transform &transform=Transform(), float intensity=0.0f) |
pcl::PointCloud< pcl::PointXYZINormal >::Ptr RTABMAP_CORE_EXPORT | laserScanToPointCloudINormal (const LaserScan &laserScan, const Transform &transform=Transform(), float intensity=0.0f) |
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_CORE_EXPORT | laserScanToPointCloudNormal (const LaserScan &laserScan, const Transform &transform=Transform()) |
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT | laserScanToPointCloudRGB (const LaserScan &laserScan, const Transform &transform=Transform(), unsigned char r=100, unsigned char g=100, unsigned char b=100) |
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_CORE_EXPORT | laserScanToPointCloudRGBNormal (const LaserScan &laserScan, const Transform &transform=Transform(), unsigned char r=100, unsigned char g=100, unsigned char b=100) |
pcl::PointXYZI RTABMAP_CORE_EXPORT | laserScanToPointI (const LaserScan &laserScan, int index, float intensity) |
pcl::PointXYZINormal RTABMAP_CORE_EXPORT | laserScanToPointINormal (const LaserScan &laserScan, int index, float intensity) |
pcl::PointNormal RTABMAP_CORE_EXPORT | laserScanToPointNormal (const LaserScan &laserScan, int index) |
pcl::PointXYZRGB RTABMAP_CORE_EXPORT | laserScanToPointRGB (const LaserScan &laserScan, int index, unsigned char r=100, unsigned char g=100, unsigned char b=100) |
pcl::PointXYZRGBNormal RTABMAP_CORE_EXPORT | laserScanToPointRGBNormal (const LaserScan &laserScan, int index, unsigned char r, unsigned char g, unsigned char b) |
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT | loadBINCloud (const std::string &fileName) |
RTABMAP_DEPRECATED pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT | loadBINCloud (const std::string &fileName, int dim) |
cv::Mat RTABMAP_CORE_EXPORT | loadBINScan (const std::string &fileName) |
RTABMAP_DEPRECATED pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT | loadCloud (const std::string &path, const Transform &transform=Transform::getIdentity(), int downsampleStep=1, float voxelSize=0.0f) |
LaserScan RTABMAP_CORE_EXPORT | loadScan (const std::string &path) |
cv::Mat RTABMAP_CORE_EXPORT | mergeTextures (pcl::TextureMesh &mesh, const std::map< int, cv::Mat > &images, const std::map< int, CameraModel > &calibrations, const Memory *memory=0, const DBDriver *dbDriver=0, int textureSize=4096, int textureCount=1, const std::vector< std::map< int, pcl::PointXY > > &vertexToPixels=std::vector< std::map< int, pcl::PointXY > >(), bool gainCompensation=true, float gainBeta=10.0f, bool gainRGB=true, bool blending=true, int blendingDecimation=0, int brightnessContrastRatioLow=0, int brightnessContrastRatioHigh=0, bool exposureFusion=false, const ProgressState *state=0, unsigned char blankValue=255, std::map< int, std::map< int, cv::Vec4d > > *gains=0, std::map< int, std::map< int, cv::Mat > > *blendingGains=0, std::pair< float, float > *contrastValues=0) |
cv::Mat RTABMAP_CORE_EXPORT | mergeTextures (pcl::TextureMesh &mesh, const std::map< int, cv::Mat > &images, const std::map< int, std::vector< CameraModel > > &calibrations, const Memory *memory=0, const DBDriver *dbDriver=0, int textureSize=4096, int textureCount=1, const std::vector< std::map< int, pcl::PointXY > > &vertexToPixels=std::vector< std::map< int, pcl::PointXY > >(), bool gainCompensation=true, float gainBeta=10.0f, bool gainRGB=true, bool blending=true, int blendingDecimation=0, int brightnessContrastRatioLow=0, int brightnessContrastRatioHigh=0, bool exposureFusion=false, const ProgressState *state=0, unsigned char blankValue=255, std::map< int, std::map< int, cv::Vec4d > > *gains=0, std::map< int, std::map< int, cv::Mat > > *blendingGains=0, std::pair< float, float > *contrastValues=0) |
pcl::PolygonMesh::Ptr RTABMAP_CORE_EXPORT | meshDecimation (const pcl::PolygonMesh::Ptr &mesh, float factor) |
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_CORE_EXPORT | 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::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_CORE_EXPORT | 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) |
RTABMAP_DEPRECATED bool RTABMAP_CORE_EXPORT | multiBandTexturing (const std::string &outputOBJPath, const pcl::PCLPointCloud2 &cloud, const std::vector< pcl::Vertices > &polygons, const std::map< int, Transform > &cameraPoses, const std::vector< std::map< int, pcl::PointXY > > &vertexToPixels, const std::map< int, cv::Mat > &images, const std::map< int, std::vector< CameraModel > > &cameraModels, const Memory *memory=0, const DBDriver *dbDriver=0, int textureSize=8192, const std::string &textureFormat="jpg", const std::map< int, std::map< int, cv::Vec4d > > &gains=std::map< int, std::map< int, cv::Vec4d > >(), const std::map< int, std::map< int, cv::Mat > > &blendingGains=std::map< int, std::map< int, cv::Mat > >(), const std::pair< float, float > &contrastValues=std::pair< float, float >(0, 0), bool gainRGB=true) |
bool RTABMAP_CORE_EXPORT | multiBandTexturing (const std::string &outputOBJPath, const pcl::PCLPointCloud2 &cloud, const std::vector< pcl::Vertices > &polygons, const std::map< int, Transform > &cameraPoses, const std::vector< std::map< int, pcl::PointXY > > &vertexToPixels, const std::map< int, cv::Mat > &images, const std::map< int, std::vector< CameraModel > > &cameraModels, const Memory *memory=0, const DBDriver *dbDriver=0, unsigned int textureSize=8192, unsigned int textureDownscale=2, const std::string &nbContrib="1 5 10 0", const std::string &textureFormat="jpg", const std::map< int, std::map< int, cv::Vec4d > > &gains=std::map< int, std::map< int, cv::Vec4d > >(), const std::map< int, std::map< int, cv::Mat > > &blendingGains=std::map< int, std::map< int, cv::Mat > >(), const std::pair< float, float > &contrastValues=std::pair< float, float >(0, 0), bool gainRGB=true, unsigned int unwrapMethod=0, bool fillHoles=false, unsigned int padding=5, double bestScoreThreshold=0.1, double angleHardThreshold=90.0, bool forceVisibleByAllVertices=false) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | normalFiltering (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint, float groundNormalsUp=0.0f) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | normalFiltering (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint, float groundNormalsUp=0.0f) |
Given a normal and a maximum angle error, keep all points of the cloud respecting this normal. More... | |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | normalFiltering (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint, float groundNormalsUp=0.0f) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | normalFiltering (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, const pcl::IndicesPtr &indices, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint, float groundNormalsUp=0.0f) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | normalFiltering (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint, float groundNormalsUp=0.0f) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | normalFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint, float groundNormalsUp=0.0f) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | normalFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint, float groundNormalsUp=0.0f) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | normalFiltering (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint, float groundNormalsUp=0.0f) |
template<typename PointNormalT > | |
pcl::IndicesPtr | normalFilteringImpl (const typename pcl::PointCloud< PointNormalT >::Ptr &cloud, const pcl::IndicesPtr &indices, float angleMax, const Eigen::Vector4f &normal, const Eigen::Vector4f &viewpoint, float groundNormalsUp) |
template<typename PointT > | |
pcl::IndicesPtr | normalFilteringImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint, float groundNormalsUp) |
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 > | |
std::vector< pcl::Vertices > | normalizePolygonsSide (const typename pcl::PointCloud< pointT > &cloud, const std::vector< pcl::Vertices > &polygons, const pcl::PointXYZ &viewPoint) |
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) |
RTABMAP_DEPRECATED void RTABMAP_CORE_EXPORT | occupancy2DFromLaserScan (const cv::Mat &scan, const cv::Point3f &viewpoint, cv::Mat &empty, cv::Mat &occupied, float cellSize, bool unknownSpaceFilled=false, float scanMaxRange=0.0f) |
RTABMAP_DEPRECATED void RTABMAP_CORE_EXPORT | occupancy2DFromLaserScan (const cv::Mat &scan, cv::Mat &empty, cv::Mat &occupied, float cellSize, bool unknownSpaceFilled=false, float scanMaxRange=0.0f) |
void RTABMAP_CORE_EXPORT | occupancy2DFromLaserScan (const cv::Mat &scanHit, const cv::Mat &scanNoHit, const cv::Point3f &viewpoint, cv::Mat &empty, cv::Mat &occupied, float cellSize, bool unknownSpaceFilled=false, float scanMaxRange=0.0f) |
std::vector< pcl::Vertices > RTABMAP_CORE_EXPORT | organizedFastMesh (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, double angleTolerance, bool quad, int trianglePixelSize, const Eigen::Vector3f &viewpoint=Eigen::Vector3f(0, 0, 0)) |
std::vector< pcl::Vertices > RTABMAP_CORE_EXPORT | 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_CORE_EXPORT | 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_CORE_EXPORT | passThrough (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false) |
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_CORE_EXPORT | passThrough (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const std::string &axis, float min, float max, bool negative=false) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | passThrough (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false) |
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT | passThrough (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const std::string &axis, float min, float max, bool negative=false) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | passThrough (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false) |
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_CORE_EXPORT | passThrough (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, const std::string &axis, float min, float max, bool negative=false) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | passThrough (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false) |
pcl::PointCloud< pcl::PointXYZINormal >::Ptr RTABMAP_CORE_EXPORT | passThrough (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const std::string &axis, float min, float max, bool negative=false) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | 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::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT | passThrough (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const std::string &axis, float min, float max, bool negative=false) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | passThrough (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false) |
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_CORE_EXPORT | passThrough (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const std::string &axis, float min, float max, bool negative=false) |
template<typename PointT > | |
pcl::IndicesPtr | passThroughImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative) |
template<typename PointT > | |
pcl::PointCloud< PointT >::Ptr | passThroughImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const std::string &axis, float min, float max, bool negative) |
template<typename PointT > | |
pcl::PointCloud< PointT >::Ptr | projectCloudOnXYPlane (const typename pcl::PointCloud< PointT > &cloud) |
cv::Mat RTABMAP_CORE_EXPORT | projectCloudToCamera (const cv::Size &imageSize, const cv::Mat &cameraMatrixK, const cv::Mat &laserScan, const rtabmap::Transform &cameraTransform) |
cv::Mat RTABMAP_CORE_EXPORT | projectCloudToCamera (const cv::Size &imageSize, const cv::Mat &cameraMatrixK, const pcl::PCLPointCloud2::Ptr laserScan, const rtabmap::Transform &cameraTransform) |
cv::Mat RTABMAP_CORE_EXPORT | projectCloudToCamera (const cv::Size &imageSize, const cv::Mat &cameraMatrixK, const pcl::PointCloud< pcl::PointXYZ >::Ptr laserScan, const rtabmap::Transform &cameraTransform) |
std::vector< std::pair< std::pair< int, int >, pcl::PointXY > > RTABMAP_CORE_EXPORT | projectCloudToCameras (const pcl::PointCloud< pcl::PointXYZINormal > &cloud, const std::map< int, Transform > &cameraPoses, const std::map< int, std::vector< CameraModel > > &cameraModels, float maxDistance=0.0f, float maxAngle=0.0f, const std::vector< float > &roiRatios=std::vector< float >(), const cv::Mat &projMask=cv::Mat(), bool distanceToCamPolicy=false, const ProgressState *state=0) |
std::vector< std::pair< std::pair< int, int >, pcl::PointXY > > RTABMAP_CORE_EXPORT | projectCloudToCameras (const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloud, const std::map< int, Transform > &cameraPoses, const std::map< int, std::vector< CameraModel > > &cameraModels, float maxDistance=0.0f, float maxAngle=0.0f, const std::vector< float > &roiRatios=std::vector< float >(), const cv::Mat &projMask=cv::Mat(), bool distanceToCamPolicy=false, const ProgressState *state=0) |
std::vector< std::pair< std::pair< int, int >, pcl::PointXY > > | projectCloudToCameras (const typename pcl::PointCloud< pcl::PointXYZINormal > &cloud, const std::map< int, Transform > &cameraPoses, const std::map< int, std::vector< CameraModel > > &cameraModels, float maxDistance, float maxAngle, const std::vector< float > &roiRatios, const cv::Mat &projMask, bool distanceToCamPolicy, const ProgressState *state) |
std::vector< std::pair< std::pair< int, int >, pcl::PointXY > > | projectCloudToCameras (const typename pcl::PointCloud< pcl::PointXYZRGBNormal > &cloud, const std::map< int, Transform > &cameraPoses, const std::map< int, std::vector< CameraModel > > &cameraModels, float maxDistance, float maxAngle, const std::vector< float > &roiRatios, const cv::Mat &projMask, bool distanceToCamPolicy, const ProgressState *state) |
template<class PointT > | |
std::vector< std::pair< std::pair< int, int >, pcl::PointXY > > | projectCloudToCamerasImpl (const typename pcl::PointCloud< PointT > &cloud, const std::map< int, Transform > &cameraPoses, const std::map< int, std::vector< CameraModel > > &cameraModels, float maxDistance, float maxAngle, const std::vector< float > &roiRatios, const cv::Mat &projMask, bool distanceToCamPolicy, const ProgressState *state) |
pcl::PointXYZ RTABMAP_CORE_EXPORT | projectDepthTo3D (const cv::Mat &depthImage, float x, float y, float cx, float cy, float fx, float fy, bool smoothing, float depthErrorRatio=0.02f) |
Eigen::Vector3f RTABMAP_CORE_EXPORT | projectDepthTo3DRay (const cv::Size &imageSize, float x, float y, float cx, float cy, float fx, float fy) |
cv::Point3f RTABMAP_CORE_EXPORT | projectDisparityTo3D (const cv::Point2f &pt, const cv::Mat &disparity, const StereoCameraModel &model) |
cv::Point3f RTABMAP_CORE_EXPORT | projectDisparityTo3D (const cv::Point2f &pt, float disparity, const StereoCameraModel &model) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | proportionalRadiusFiltering (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::vector< int > &viewpointIndices, const std::map< int, Transform > &viewpoints, float factor=0.01f, float neighborScale=2.0f) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | proportionalRadiusFiltering (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const std::vector< int > &viewpointIndices, const std::map< int, Transform > &viewpoints, float factor=0.01f, float neighborScale=2.0f) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | proportionalRadiusFiltering (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::vector< int > &viewpointIndices, const std::map< int, Transform > &viewpoints, float factor=0.01f, float neighborScale=2.0f) |
Filter points based on distance from their viewpoint. More... | |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | proportionalRadiusFiltering (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const std::vector< int > &viewpointIndices, const std::map< int, Transform > &viewpoints, float factor=0.01f, float neighborScale=2.0f) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | proportionalRadiusFiltering (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::vector< int > &viewpointIndices, const std::map< int, Transform > &viewpoints, float factor=0.01f, float neighborScale=2.0f) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | proportionalRadiusFiltering (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, const std::vector< int > &viewpointIndices, const std::map< int, Transform > &viewpoints, float factor=0.01f, float neighborScale=2.0f) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | proportionalRadiusFiltering (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::vector< int > &viewpointIndices, const std::map< int, Transform > &viewpoints, float factor=0.01f, float neighborScale=2.0f) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | proportionalRadiusFiltering (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const std::vector< int > &viewpointIndices, const std::map< int, Transform > &viewpoints, float factor=0.01f, float neighborScale=2.0f) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | proportionalRadiusFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::vector< int > &viewpointIndices, const std::map< int, Transform > &viewpoints, float factor=0.01f, float neighborScale=2.0f) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | proportionalRadiusFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const std::vector< int > &viewpointIndices, const std::map< int, Transform > &viewpoints, float factor=0.01f, float neighborScale=2.0f) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | proportionalRadiusFiltering (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::vector< int > &viewpointIndices, const std::map< int, Transform > &viewpoints, float factor=0.01f, float neighborScale=2.0f) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | proportionalRadiusFiltering (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const std::vector< int > &viewpointIndices, const std::map< int, Transform > &viewpoints, float factor=0.01f, float neighborScale=2.0f) |
template<typename PointT > | |
pcl::IndicesPtr | proportionalRadiusFilteringImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::vector< int > &viewpointIndices, const std::map< int, Transform > &viewpoints, float factor, float neighborScale) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | radiusFiltering (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float radiusSearch, int minNeighborsInRadius) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | radiusFiltering (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | radiusFiltering (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float radiusSearch, int minNeighborsInRadius) |
Wrapper of the pcl::RadiusOutlierRemoval class. More... | |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | radiusFiltering (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | radiusFiltering (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, const pcl::IndicesPtr &indices, float radiusSearch, int minNeighborsInRadius) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | radiusFiltering (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | radiusFiltering (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float radiusSearch, int minNeighborsInRadius) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | radiusFiltering (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | radiusFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, float radiusSearch, int minNeighborsInRadius) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | radiusFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | radiusFiltering (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float radiusSearch, int minNeighborsInRadius) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | radiusFiltering (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius) |
template<typename PointT > | |
pcl::IndicesPtr | radiusFilteringImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, float radiusSearch, int minNeighborsInRadius) |
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_CORE_EXPORT | randomSampling (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, int samples) |
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT | randomSampling (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int samples) |
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_CORE_EXPORT | randomSampling (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, int samples) |
pcl::PointCloud< pcl::PointXYZINormal >::Ptr RTABMAP_CORE_EXPORT | randomSampling (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, int samples) |
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT | randomSampling (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, int samples) |
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_CORE_EXPORT | randomSampling (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, int samples) |
template<typename PointT > | |
pcl::PointCloud< PointT >::Ptr | randomSamplingImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, int samples) |
LaserScan RTABMAP_CORE_EXPORT | rangeFiltering (const LaserScan &scan, float rangeMin, float rangeMax) |
void RTABMAP_CORE_EXPORT | rayTrace (const cv::Point2i &start, const cv::Point2i &end, cv::Mat &grid, bool stopOnObstacle) |
pcl::PCLPointCloud2::Ptr RTABMAP_CORE_EXPORT | removeNaNFromPointCloud (const pcl::PCLPointCloud2::Ptr &cloud) |
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT | removeNaNFromPointCloud (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud) |
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_CORE_EXPORT | removeNaNFromPointCloud (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud) |
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT | removeNaNFromPointCloud (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud) |
template<typename PointT > | |
pcl::PointCloud< PointT >::Ptr | removeNaNFromPointCloudImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud) |
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_CORE_EXPORT | removeNaNNormalsFromPointCloud (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud) |
pcl::PointCloud< pcl::PointXYZINormal >::Ptr RTABMAP_CORE_EXPORT | removeNaNNormalsFromPointCloud (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud) |
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_CORE_EXPORT | removeNaNNormalsFromPointCloud (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud) |
template<typename PointT > | |
pcl::PointCloud< PointT >::Ptr | removeNaNNormalsFromPointCloudImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud) |
void RTABMAP_CORE_EXPORT | 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_CORE_EXPORT | rgbFromCloud (const pcl::PointCloud< pcl::PointXYZRGBA > &cloud, bool bgrOrder=true) |
void RTABMAP_CORE_EXPORT | savePCDWords (const std::string &fileName, const std::multimap< int, cv::Point3f > &words, const Transform &transform=Transform::getIdentity()) |
void RTABMAP_CORE_EXPORT | savePCDWords (const std::string &fileName, const std::multimap< int, pcl::PointXYZ > &words, const Transform &transform=Transform::getIdentity()) |
template<typename PointT > | |
void | segmentObstaclesFromGround (const typename pcl::PointCloud< PointT >::Ptr &cloud, 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), float groundNormalsUp=0) |
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, float groundNormalsUp) |
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, float groundNormalsUp) |
void RTABMAP_CORE_EXPORT | 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) |
double | sqr (uchar v) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | 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_CORE_EXPORT | 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::IndicesPtr RTABMAP_CORE_EXPORT | 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::PointNormal >::Ptr RTABMAP_CORE_EXPORT | 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_CORE_EXPORT | subtractFiltering (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &substractCloud, const pcl::IndicesPtr &substractIndices, float radiusSearch, float maxAngle=M_PI/4.0f, int minNeighborsInRadius=1) |
pcl::PointCloud< pcl::PointXYZINormal >::Ptr RTABMAP_CORE_EXPORT | subtractFiltering (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &substractCloud, float radiusSearch, float maxAngle=M_PI/4.0f, int minNeighborsInRadius=1) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | 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::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT | subtractFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &substractCloud, float radiusSearch, int minNeighborsInRadius=1) |
pcl::IndicesPtr RTABMAP_CORE_EXPORT | 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) |
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_CORE_EXPORT | 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) |
template<typename PointT > | |
pcl::IndicesPtr | subtractFilteringImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, const typename pcl::PointCloud< PointT >::Ptr &substractCloud, const pcl::IndicesPtr &substractIndices, float radiusSearch, float maxAngle, int minNeighborsInRadius) |
template<typename PointT > | |
pcl::IndicesPtr | subtractFilteringImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, const typename pcl::PointCloud< PointT >::Ptr &substractCloud, const pcl::IndicesPtr &substractIndices, float radiusSearch, int minNeighborsInRadius) |
Transform RTABMAP_CORE_EXPORT | 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, cv::Mat *variance=0) |
Transform RTABMAP_CORE_EXPORT | transformFromXYZCorrespondencesSVD (const pcl::PointCloud< pcl::PointXYZ > &cloud1, const pcl::PointCloud< pcl::PointXYZ > &cloud2) |
LaserScan RTABMAP_CORE_EXPORT | transformLaserScan (const LaserScan &laserScan, const Transform &transform) |
cv::Point3d RTABMAP_CORE_EXPORT | transformPoint (const cv::Point3d &pt, const Transform &transform) |
cv::Point3f RTABMAP_CORE_EXPORT | transformPoint (const cv::Point3f &pt, const Transform &transform) |
pcl::PointNormal RTABMAP_CORE_EXPORT | transformPoint (const pcl::PointNormal &point, const Transform &transform) |
pcl::PointXYZ RTABMAP_CORE_EXPORT | transformPoint (const pcl::PointXYZ &pt, const Transform &transform) |
pcl::PointXYZI RTABMAP_CORE_EXPORT | transformPoint (const pcl::PointXYZI &pt, const Transform &transform) |
pcl::PointXYZINormal RTABMAP_CORE_EXPORT | transformPoint (const pcl::PointXYZINormal &point, const Transform &transform) |
pcl::PointXYZRGB RTABMAP_CORE_EXPORT | transformPoint (const pcl::PointXYZRGB &pt, const Transform &transform) |
pcl::PointXYZRGBNormal RTABMAP_CORE_EXPORT | transformPoint (const pcl::PointXYZRGBNormal &point, const Transform &transform) |
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_CORE_EXPORT | transformPointCloud (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const Transform &transform) |
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_CORE_EXPORT | transformPointCloud (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const Transform &transform) |
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT | transformPointCloud (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, const Transform &transform) |
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT | transformPointCloud (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform) |
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_CORE_EXPORT | transformPointCloud (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, const pcl::IndicesPtr &indices, const Transform &transform) |
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_CORE_EXPORT | transformPointCloud (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, const Transform &transform) |
pcl::PointCloud< pcl::PointXYZINormal >::Ptr RTABMAP_CORE_EXPORT | transformPointCloud (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const Transform &transform) |
pcl::PointCloud< pcl::PointXYZINormal >::Ptr RTABMAP_CORE_EXPORT | transformPointCloud (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const Transform &transform) |
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT | transformPointCloud (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, const Transform &transform) |
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT | transformPointCloud (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const Transform &transform) |
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_CORE_EXPORT | transformPointCloud (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const Transform &transform) |
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_CORE_EXPORT | 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::PointNormal >::Ptr RTABMAP_CORE_EXPORT | voxelize (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize) |
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_CORE_EXPORT | voxelize (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, float voxelSize) |
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT | voxelize (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize) |
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT | voxelize (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float voxelSize) |
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_CORE_EXPORT | voxelize (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize) |
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_CORE_EXPORT | voxelize (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, float voxelSize) |
pcl::PointCloud< pcl::PointXYZINormal >::Ptr RTABMAP_CORE_EXPORT | voxelize (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize) |
pcl::PointCloud< pcl::PointXYZINormal >::Ptr RTABMAP_CORE_EXPORT | voxelize (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, float voxelSize) |
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT | voxelize (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize) |
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT | voxelize (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float voxelSize) |
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_CORE_EXPORT | voxelize (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize) |
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_CORE_EXPORT | voxelize (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, float voxelSize) |
template<typename PointT > | |
pcl::PointCloud< PointT >::Ptr | voxelizeImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize, int level=0) |
LaserScan rtabmap::util3d::adjustNormalsToViewPoint | ( | const LaserScan & | scan, |
const Eigen::Vector3f & | viewpoint, | ||
bool | forceGroundNormalsUp | ||
) |
Definition at line 3502 of file util3d_surface.cpp.
LaserScan rtabmap::util3d::adjustNormalsToViewPoint | ( | const LaserScan & | scan, |
const Eigen::Vector3f & | viewpoint = Eigen::Vector3f(0,0,0) , |
||
float | groundNormalsUp = 0.0f |
||
) |
Definition at line 3509 of file util3d_surface.cpp.
void rtabmap::util3d::adjustNormalsToViewPoint | ( | pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
const Eigen::Vector3f & | viewpoint, | ||
bool | forceGroundNormalsUp | ||
) |
Definition at line 3583 of file util3d_surface.cpp.
void rtabmap::util3d::adjustNormalsToViewPoint | ( | pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
const Eigen::Vector3f & | viewpoint = Eigen::Vector3f(0,0,0) , |
||
float | groundNormalsUp = 0.0f |
||
) |
Definition at line 3590 of file util3d_surface.cpp.
void rtabmap::util3d::adjustNormalsToViewPoint | ( | pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
const Eigen::Vector3f & | viewpoint, | ||
bool | forceGroundNormalsUp | ||
) |
Definition at line 3613 of file util3d_surface.cpp.
void rtabmap::util3d::adjustNormalsToViewPoint | ( | pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
const Eigen::Vector3f & | viewpoint = Eigen::Vector3f(0,0,0) , |
||
float | groundNormalsUp = 0.0f |
||
) |
Definition at line 3620 of file util3d_surface.cpp.
void rtabmap::util3d::adjustNormalsToViewPoint | ( | pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
const Eigen::Vector3f & | viewpoint, | ||
bool | forceGroundNormalsUp | ||
) |
Definition at line 3598 of file util3d_surface.cpp.
void rtabmap::util3d::adjustNormalsToViewPoint | ( | pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
const Eigen::Vector3f & | viewpoint = Eigen::Vector3f(0,0,0) , |
||
float | groundNormalsUp = 0.0f |
||
) |
Definition at line 3605 of file util3d_surface.cpp.
void rtabmap::util3d::adjustNormalsToViewPointImpl | ( | typename pcl::PointCloud< PointNormalT >::Ptr & | cloud, |
const Eigen::Vector3f & | viewpoint, | ||
float | groundNormalsUp | ||
) |
Definition at line 3556 of file util3d_surface.cpp.
void 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, | ||
float | groundNormalsUp = 0.0f |
||
) |
Definition at line 3679 of file util3d_surface.cpp.
void rtabmap::util3d::adjustNormalsToViewPoints | ( | const std::map< int, Transform > & | poses, |
const pcl::PointCloud< pcl::PointXYZ >::Ptr & | rawCloud, | ||
const std::vector< int > & | rawCameraIndices, | ||
pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, | ||
float | groundNormalsUp = 0.0f |
||
) |
Definition at line 3699 of file util3d_surface.cpp.
void 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, | ||
float | groundNormalsUp = 0.0f |
||
) |
Definition at line 3689 of file util3d_surface.cpp.
void rtabmap::util3d::adjustNormalsToViewPoints | ( | const std::map< int, Transform > & | viewpoints, |
const LaserScan & | rawScan, | ||
const std::vector< int > & | viewpointIds, | ||
LaserScan & | scan, | ||
float | groundNormalsUp = 0.0f |
||
) |
Definition at line 3709 of file util3d_surface.cpp.
void rtabmap::util3d::adjustNormalsToViewPointsImpl | ( | const std::map< int, Transform > & | poses, |
const pcl::PointCloud< pcl::PointXYZ >::Ptr & | rawCloud, | ||
const std::vector< int > & | rawCameraIndices, | ||
typename pcl::PointCloud< PointT >::Ptr & | cloud, | ||
float | groundNormalsUp | ||
) |
Definition at line 3630 of file util3d_surface.cpp.
std::multimap< int, cv::KeyPoint > rtabmap::util3d::aggregate | ( | const std::list< int > & | wordIds, |
const std::vector< cv::KeyPoint > & | keypoints | ||
) |
Definition at line 414 of file util3d_features.cpp.
void 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 | ||
) |
Definition at line 309 of file util3d_surface.cpp.
void 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 | ||
) |
Definition at line 283 of file util3d_surface.cpp.
pcl::PolygonMesh::Ptr rtabmap::util3d::assemblePolygonMesh | ( | const cv::Mat & | cloudMat, |
const std::vector< std::vector< RTABMAP_PCL_INDEX > > & | polygons | ||
) |
Definition at line 1395 of file util3d_surface.cpp.
pcl::TextureMesh::Ptr rtabmap::util3d::assembleTextureMesh | ( | const cv::Mat & | cloudMat, |
const std::vector< std::vector< std::vector< RTABMAP_PCL_INDEX > > > & | polygons, | ||
const std::vector< std::vector< Eigen::Vector2f > > & | texCoords, | ||
cv::Mat & | textures, | ||
bool | mergeTextures = false |
||
) |
Definition at line 1272 of file util3d_surface.cpp.
cv::Mat rtabmap::util3d::bgrFromCloud | ( | const pcl::PointCloud< pcl::PointXYZRGBA > & | cloud, |
bool | bgrOrder | ||
) |
Definition at line 52 of file util3d.cpp.
void rtabmap::util3d::cleanTextureMesh | ( | pcl::TextureMesh & | textureMesh, |
int | minClusterSize | ||
) |
Remove not textured polygon clusters. If minClusterSize<0, only the largest cluster is kept.
Definition at line 873 of file util3d_surface.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 279 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::cloudFromDepth | ( | const cv::Mat & | imageDepth, |
float | cx, | ||
float | cy, | ||
float | fx, | ||
float | fy, | ||
int | decimation = 1 , |
||
float | maxDepth = 0.0f , |
||
float | minDepth = 0.0f , |
||
std::vector< int > * | validIndices = 0 |
||
) |
Definition at line 266 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 430 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::cloudFromDepthRGB | ( | const cv::Mat & | imageRgb, |
const cv::Mat & | imageDepth, | ||
float | cx, | ||
float | cy, | ||
float | fx, | ||
float | fy, | ||
int | decimation = 1 , |
||
float | maxDepth = 0.0f , |
||
float | minDepth = 0.0f , |
||
std::vector< int > * | validIndices = 0 |
||
) |
Definition at line 416 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 612 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 713 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::cloudFromSensorData | ( | const SensorData & | sensorData, |
int | decimation = 1 , |
||
float | maxDepth = 0.0f , |
||
float | minDepth = 0.0f , |
||
std::vector< int > * | validIndices = 0 , |
||
const ParametersMap & | stereoParameters = ParametersMap() , |
||
const std::vector< float > & | roiRatios = std::vector<float>() |
||
) |
Create a XYZ 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 |
stereoParameters,stereo | optional parameters (in case it is stereo data) |
roiRatios,[left,right,top,bottom] | region of interest (in ratios) of the image projected. |
Definition at line 1040 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 814 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::cloudRGBFromSensorData | ( | const SensorData & | sensorData, |
int | decimation = 1 , |
||
float | maxDepth = 0.0f , |
||
float | minDepth = 0.0f , |
||
std::vector< int > * | validIndices = 0 , |
||
const ParametersMap & | stereoParameters = ParametersMap() , |
||
const std::vector< float > & | roiRatios = std::vector<float>() |
||
) |
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 |
stereoParameters,stereo | optional parameters (in case it is stereo data) |
roiRatios,[left,right,top,bottom] | region of interest (in ratios) of the image projected. |
Definition at line 1268 of file util3d.cpp.
std::vector< pcl::PointCloud< pcl::PointXYZ >::Ptr > rtabmap::util3d::cloudsFromSensorData | ( | const SensorData & | sensorData, |
int | decimation = 1 , |
||
float | maxDepth = 0.0f , |
||
float | minDepth = 0.0f , |
||
std::vector< pcl::IndicesPtr > * | validIndices = 0 , |
||
const ParametersMap & | stereoParameters = ParametersMap() , |
||
const std::vector< float > & | roiRatios = std::vector<float>() |
||
) |
Create a XYZ cloud from the images contained in SensorData, one for each camera
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 |
stereoParameters,stereo | optional parameters (in case it is stereo data) |
roiRatios,[left,right,top,bottom] | region of interest (in ratios) of the image projected. |
Definition at line 854 of file util3d.cpp.
std::vector< pcl::PointCloud< pcl::PointXYZRGB >::Ptr > rtabmap::util3d::cloudsRGBFromSensorData | ( | const SensorData & | sensorData, |
int | decimation = 1 , |
||
float | maxDepth = 0.0f , |
||
float | minDepth = 0.0f , |
||
std::vector< pcl::IndicesPtr > * | validIndices = 0 , |
||
const ParametersMap & | stereoParameters = ParametersMap() , |
||
const std::vector< float > & | roiRatios = std::vector<float>() |
||
) |
Create an RGB cloud from the images contained in SensorData, one for each camera
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 |
stereoParameters,stereo | optional parameters (in case it is stereo data) |
roiRatios,[left,right,top,bottom] | region of interest (in ratios) of the image projected. |
Definition at line 1093 of file util3d.cpp.
std::list< std::list< int > > rtabmap::util3d::clusterPolygons | ( | const std::vector< std::set< int > > & | neighborPolygons, |
int | minClusterSize = 0 |
||
) |
Definition at line 131 of file util3d_surface.cpp.
LaserScan rtabmap::util3d::commonFiltering | ( | const LaserScan & | scan, |
int | downsamplingStep, | ||
float | rangeMin, | ||
float | rangeMax, | ||
float | voxelSize, | ||
int | normalK, | ||
float | normalRadius, | ||
bool | forceGroundNormalsUp | ||
) |
Definition at line 334 of file util3d_filtering.cpp.
LaserScan rtabmap::util3d::commonFiltering | ( | const LaserScan & | scan, |
int | downsamplingStep, | ||
float | rangeMin = 0.0f , |
||
float | rangeMax = 0.0f , |
||
float | voxelSize = 0.0f , |
||
int | normalK = 0 , |
||
float | normalRadius = 0.0f , |
||
float | groundNormalsUp = 0.0f |
||
) |
Do some filtering approaches and try to avoid converting between pcl and opencv and to avoid not needed operations like computing normals while the scan has already normals and voxel filtering is not used.
Definition at line 74 of file util3d_filtering.cpp.
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) |
||
) |
Definition at line 3061 of file util3d_surface.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) |
||
) |
Definition at line 3052 of file util3d_surface.cpp.
pcl::PointCloud< pcl::Normal >::Ptr rtabmap::util3d::computeFastOrganizedNormals2D | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
int | searchK = 5 , |
||
float | searchRadius = 0.0f , |
||
const Eigen::Vector3f & | viewPoint = Eigen::Vector3f(0,0,0) |
||
) |
Definition at line 3035 of file util3d_surface.cpp.
pcl::PointCloud< pcl::Normal >::Ptr rtabmap::util3d::computeFastOrganizedNormals2D | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
int | searchK = 5 , |
||
float | searchRadius = 0.0f , |
||
const Eigen::Vector3f & | viewPoint = Eigen::Vector3f(0,0,0) |
||
) |
Definition at line 3043 of file util3d_surface.cpp.
pcl::PointCloud<pcl::Normal>::Ptr rtabmap::util3d::computeFastOrganizedNormals2DImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
int | searchK, | ||
float | searchRadius, | ||
const Eigen::Vector3f & | viewPoint | ||
) |
Definition at line 2941 of file util3d_surface.cpp.
cv::Mat RTABMAP_CORE_EXPORT rtabmap::util3d::computeNormals | ( | const cv::Mat & | laserScan, |
int | searchK, | ||
float | searchRadius | ||
) |
LaserScan rtabmap::util3d::computeNormals | ( | const LaserScan & | laserScan, |
int | searchK, | ||
float | searchRadius | ||
) |
Definition at line 2681 of file util3d_surface.cpp.
pcl::PointCloud< pcl::Normal >::Ptr rtabmap::util3d::computeNormals | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
int | searchK = 20 , |
||
float | searchRadius = 0.0f , |
||
const Eigen::Vector3f & | viewPoint = Eigen::Vector3f(0,0,0) |
||
) |
Definition at line 2821 of file util3d_surface.cpp.
pcl::PointCloud< pcl::Normal >::Ptr rtabmap::util3d::computeNormals | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
int | searchK = 20 , |
||
float | searchRadius = 0.0f , |
||
const Eigen::Vector3f & | viewPoint = Eigen::Vector3f(0,0,0) |
||
) |
Definition at line 2794 of file util3d_surface.cpp.
pcl::PointCloud< pcl::Normal >::Ptr rtabmap::util3d::computeNormals | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
int | searchK = 20 , |
||
float | searchRadius = 0.0f , |
||
const Eigen::Vector3f & | viewPoint = Eigen::Vector3f(0,0,0) |
||
) |
Definition at line 2839 of file util3d_surface.cpp.
pcl::PointCloud< pcl::Normal >::Ptr rtabmap::util3d::computeNormals | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
int | searchK = 20 , |
||
float | searchRadius = 0.0f , |
||
const Eigen::Vector3f & | viewPoint = Eigen::Vector3f(0,0,0) |
||
) |
Definition at line 2812 of file util3d_surface.cpp.
pcl::PointCloud< pcl::Normal >::Ptr rtabmap::util3d::computeNormals | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
int | searchK = 20 , |
||
float | searchRadius = 0.0f , |
||
const Eigen::Vector3f & | viewPoint = Eigen::Vector3f(0,0,0) |
||
) |
Definition at line 2830 of file util3d_surface.cpp.
pcl::PointCloud< pcl::Normal >::Ptr rtabmap::util3d::computeNormals | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
int | searchK = 20 , |
||
float | searchRadius = 0.0f , |
||
const Eigen::Vector3f & | viewPoint = Eigen::Vector3f(0,0,0) |
||
) |
Definition at line 2803 of file util3d_surface.cpp.
pcl::PointCloud< pcl::Normal >::Ptr rtabmap::util3d::computeNormals2D | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
int | searchK = 5 , |
||
float | searchRadius = 0.0f , |
||
const Eigen::Vector3f & | viewPoint = Eigen::Vector3f(0,0,0) |
||
) |
Definition at line 2923 of file util3d_surface.cpp.
pcl::PointCloud< pcl::Normal >::Ptr rtabmap::util3d::computeNormals2D | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
int | searchK = 5 , |
||
float | searchRadius = 0.0f , |
||
const Eigen::Vector3f & | viewPoint = Eigen::Vector3f(0,0,0) |
||
) |
Definition at line 2931 of file util3d_surface.cpp.
pcl::PointCloud<pcl::Normal>::Ptr rtabmap::util3d::computeNormals2DImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
int | searchK, | ||
float | searchRadius, | ||
const Eigen::Vector3f & | viewPoint | ||
) |
Definition at line 2850 of file util3d_surface.cpp.
float rtabmap::util3d::computeNormalsComplexity | ( | const LaserScan & | scan, |
const Transform & | t = Transform::getIdentity() , |
||
cv::Mat * | pcaEigenVectors = 0 , |
||
cv::Mat * | pcaEigenValues = 0 |
||
) |
Definition at line 3100 of file util3d_surface.cpp.
float rtabmap::util3d::computeNormalsComplexity | ( | const pcl::PointCloud< pcl::Normal > & | normals, |
const Transform & | t = Transform::getIdentity() , |
||
bool | is2d = false , |
||
cv::Mat * | pcaEigenVectors = 0 , |
||
cv::Mat * | pcaEigenValues = 0 |
||
) |
Definition at line 3235 of file util3d_surface.cpp.
float rtabmap::util3d::computeNormalsComplexity | ( | const pcl::PointCloud< pcl::PointNormal > & | cloud, |
const Transform & | t = Transform::getIdentity() , |
||
bool | is2d = false , |
||
cv::Mat * | pcaEigenVectors = 0 , |
||
cv::Mat * | pcaEigenValues = 0 |
||
) |
Definition at line 3179 of file util3d_surface.cpp.
float rtabmap::util3d::computeNormalsComplexity | ( | const pcl::PointCloud< pcl::PointXYZINormal > & | cloud, |
const Transform & | t = Transform::getIdentity() , |
||
bool | is2d = false , |
||
cv::Mat * | pcaEigenVectors = 0 , |
||
cv::Mat * | pcaEigenValues = 0 |
||
) |
Definition at line 3291 of file util3d_surface.cpp.
float rtabmap::util3d::computeNormalsComplexity | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal > & | cloud, |
const Transform & | t = Transform::getIdentity() , |
||
bool | is2d = false , |
||
cv::Mat * | pcaEigenVectors = 0 , |
||
cv::Mat * | pcaEigenValues = 0 |
||
) |
Definition at line 3347 of file util3d_surface.cpp.
pcl::PointCloud<pcl::Normal>::Ptr rtabmap::util3d::computeNormalsImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
int | searchK, | ||
float | searchRadius, | ||
const Eigen::Vector3f & | viewPoint | ||
) |
Definition at line 2756 of file util3d_surface.cpp.
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 746 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 | maxCorrespondenceAngle, | ||
double & | variance, | ||
int & | correspondencesOut, | ||
bool | reciprocal | ||
) |
Definition at line 303 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, | ||
bool | reciprocal | ||
) |
Definition at line 362 of file util3d_registration.cpp.
void rtabmap::util3d::computeVarianceAndCorrespondences | ( | const pcl::PointCloud< pcl::PointXYZI >::ConstPtr & | cloudA, |
const pcl::PointCloud< pcl::PointXYZI >::ConstPtr & | cloudB, | ||
double | maxCorrespondenceDistance, | ||
double & | variance, | ||
int & | correspondencesOut, | ||
bool | reciprocal | ||
) |
Definition at line 373 of file util3d_registration.cpp.
void rtabmap::util3d::computeVarianceAndCorrespondences | ( | const pcl::PointCloud< pcl::PointXYZINormal >::ConstPtr & | cloudA, |
const pcl::PointCloud< pcl::PointXYZINormal >::ConstPtr & | cloudB, | ||
double | maxCorrespondenceDistance, | ||
double | maxCorrespondenceAngle, | ||
double & | variance, | ||
int & | correspondencesOut, | ||
bool | reciprocal | ||
) |
Definition at line 315 of file util3d_registration.cpp.
void rtabmap::util3d::computeVarianceAndCorrespondencesImpl | ( | const typename pcl::PointCloud< PointNormalT >::ConstPtr & | cloudA, |
const typename pcl::PointCloud< PointNormalT >::ConstPtr & | cloudB, | ||
double | maxCorrespondenceDistance, | ||
double | maxCorrespondenceAngle, | ||
double & | variance, | ||
int & | correspondencesOut, | ||
bool | reciprocal | ||
) |
Definition at line 241 of file util3d_registration.cpp.
void rtabmap::util3d::computeVarianceAndCorrespondencesImpl | ( | const typename pcl::PointCloud< PointT >::ConstPtr & | cloudA, |
const typename pcl::PointCloud< PointT >::ConstPtr & | cloudB, | ||
double | maxCorrespondenceDistance, | ||
double & | variance, | ||
int & | correspondencesOut, | ||
bool | reciprocal | ||
) |
Definition at line 328 of file util3d_registration.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 3372 of file util3d.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 3352 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::concatenateClouds | ( | const std::list< pcl::PointCloud< pcl::PointXYZ >::Ptr > & | clouds | ) |
Definition at line 3332 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::concatenateClouds | ( | const std::list< pcl::PointCloud< pcl::PointXYZRGB >::Ptr > & | clouds | ) |
Definition at line 3342 of file util3d.cpp.
void rtabmap::util3d::concatenateTextureMaterials | ( | pcl::TextureMesh & | mesh, |
const cv::Size & | imageSize, | ||
int | textureSize, | ||
int | maxTextures, | ||
float & | scale, | ||
std::vector< bool > * | materialsKept = 0 |
||
) |
Definition at line 1079 of file util3d_surface.cpp.
pcl::TextureMesh::Ptr rtabmap::util3d::concatenateTextureMeshes | ( | const std::list< pcl::TextureMesh::Ptr > & | meshes | ) |
Definition at line 1006 of file util3d_surface.cpp.
Definition at line 945 of file util3d_mapping.cpp.
Definition at line 904 of file util3d_mapping.cpp.
std::vector< std::vector< RTABMAP_PCL_INDEX > > rtabmap::util3d::convertPolygonsFromPCL | ( | const std::vector< pcl::Vertices > & | polygons | ) |
Definition at line 1227 of file util3d_surface.cpp.
std::vector< std::vector< std::vector< RTABMAP_PCL_INDEX > > > rtabmap::util3d::convertPolygonsFromPCL | ( | const std::vector< std::vector< pcl::Vertices > > & | polygons | ) |
Definition at line 1236 of file util3d_surface.cpp.
std::vector< pcl::Vertices > rtabmap::util3d::convertPolygonsToPCL | ( | const std::vector< std::vector< RTABMAP_PCL_INDEX > > & | polygons | ) |
Definition at line 1249 of file util3d_surface.cpp.
std::vector< std::vector< pcl::Vertices > > rtabmap::util3d::convertPolygonsToPCL | ( | const std::vector< std::vector< std::vector< RTABMAP_PCL_INDEX > > > & | tex_polygons | ) |
Definition at line 1258 of file util3d_surface.cpp.
int rtabmap::util3d::countUniquePairs | ( | const std::multimap< int, pcl::PointXYZ > & | wordsA, |
const std::multimap< int, pcl::PointXYZ > & | wordsB | ||
) |
Definition at line 209 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, | ||
const std::map< int, cv::Point3f > & | viewpoints, | ||
float | cellSize, | ||
bool | unknownSpaceFilled, | ||
float & | xMin, | ||
float & | yMin, | ||
float | minMapSize = 0.0f , |
||
float | scanMaxRange = 0.0f |
||
) |
Definition at line 554 of file util3d_mapping.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 528 of file util3d_mapping.cpp.
cv::Mat rtabmap::util3d::create2DMap | ( | const std::map< int, Transform > & | poses, |
const std::map< int, std::pair< cv::Mat, cv::Mat > > & | scans, | ||
const std::map< int, cv::Point3f > & | viewpoints, | ||
float | cellSize, | ||
bool | unknownSpaceFilled, | ||
float & | xMin, | ||
float & | yMin, | ||
float | minMapSize = 0.0f , |
||
float | scanMaxRange = 0.0f |
||
) |
Create 2d Occupancy grid (CV_8S) -1 = unknown 0 = empty space 100 = obstacle
poses | |
scans,should | be CV_32FC2 type! |
viewpoints | |
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 580 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, | ||
float | footprintRadius | ||
) |
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 191 of file util3d_mapping.cpp.
pcl::PolygonMesh::Ptr rtabmap::util3d::createMesh | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloudWithNormals, |
float | gp3SearchRadius = 0.025 , |
||
float | gp3Mu = 2.5 , |
||
int | gp3MaximumNearestNeighbors = 100 , |
||
float | gp3MaximumSurfaceAngle = M_PI/4 , |
||
float | gp3MinimumAngle = M_PI/18 , |
||
float | gp3MaximumAngle = 2*M_PI/3 , |
||
bool | gp3NormalConsistency = true |
||
) |
Definition at line 555 of file util3d_surface.cpp.
void 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). |
Definition at line 94 of file util3d_surface.cpp.
pcl::texture_mapping::CameraVector rtabmap::util3d::createTextureCameras | ( | const std::map< int, Transform > & | poses, |
const std::map< int, std::vector< CameraModel > > & | cameraModels, | ||
const std::map< int, cv::Mat > & | cameraDepths, | ||
const std::vector< float > & | roiRatios | ||
) |
Definition at line 598 of file util3d_surface.cpp.
pcl::TextureMesh::Ptr 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 > & | cameraDepths, | ||
float | maxDistance = 0.0f , |
||
float | maxDepthError = 0.0f , |
||
float | maxAngle = 0.0f , |
||
int | minClusterSize = 50 , |
||
const std::vector< float > & | roiRatios = std::vector<float>() , |
||
const ProgressState * | state = 0 , |
||
std::vector< std::map< int, pcl::PointXY > > * | vertexToPixels = 0 , |
||
bool | distanceToCamPolicy = false |
||
) |
Definition at line 675 of file util3d_surface.cpp.
pcl::TextureMesh::Ptr rtabmap::util3d::createTextureMesh | ( | const pcl::PolygonMesh::Ptr & | mesh, |
const std::map< int, Transform > & | poses, | ||
const std::map< int, std::vector< CameraModel > > & | cameraModels, | ||
const std::map< int, cv::Mat > & | cameraDepths, | ||
float | maxDistance = 0.0f , |
||
float | maxDepthError = 0.0f , |
||
float | maxAngle = 0.0f , |
||
int | minClusterSize = 50 , |
||
const std::vector< float > & | roiRatios = std::vector<float>() , |
||
const ProgressState * | state = 0 , |
||
std::vector< std::map< int, pcl::PointXY > > * | vertexToPixels = 0 , |
||
bool | distanceToCamPolicy = false |
||
) |
Definition at line 712 of file util3d_surface.cpp.
pcl::IndicesPtr rtabmap::util3d::cropBox | ( | const pcl::PCLPointCloud2::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Eigen::Vector4f & | min, | ||
const Eigen::Vector4f & | max, | ||
const Transform & | transform = Transform::getIdentity() , |
||
bool | negative = false |
||
) |
Definition at line 826 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointNormal >::Ptr rtabmap::util3d::cropBox | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
const Eigen::Vector4f & | min, | ||
const Eigen::Vector4f & | max, | ||
const Transform & | transform = Transform::getIdentity() , |
||
bool | negative = false |
||
) |
Definition at line 896 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::cropBox | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Eigen::Vector4f & | min, | ||
const Eigen::Vector4f & | max, | ||
const Transform & | transform = Transform::getIdentity() , |
||
bool | negative = false |
||
) |
Definition at line 848 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::cropBox | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
const Eigen::Vector4f & | min, | ||
const Eigen::Vector4f & | max, | ||
const Transform & | transform = Transform::getIdentity() , |
||
bool | negative = false |
||
) |
Definition at line 892 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::cropBox | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Eigen::Vector4f & | min, | ||
const Eigen::Vector4f & | max, | ||
const Transform & | transform = Transform::getIdentity() , |
||
bool | negative = false |
||
) |
Definition at line 844 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZI >::Ptr rtabmap::util3d::cropBox | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
const Eigen::Vector4f & | min, | ||
const Eigen::Vector4f & | max, | ||
const Transform & | transform = Transform::getIdentity() , |
||
bool | negative = false |
||
) |
Definition at line 904 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::cropBox | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Eigen::Vector4f & | min, | ||
const Eigen::Vector4f & | max, | ||
const Transform & | transform = Transform::getIdentity() , |
||
bool | negative = false |
||
) |
Definition at line 860 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZINormal >::Ptr rtabmap::util3d::cropBox | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
const Eigen::Vector4f & | min, | ||
const Eigen::Vector4f & | max, | ||
const Transform & | transform = Transform::getIdentity() , |
||
bool | negative = false |
||
) |
Definition at line 908 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::cropBox | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Eigen::Vector4f & | min, | ||
const Eigen::Vector4f & | max, | ||
const Transform & | transform = Transform::getIdentity() , |
||
bool | negative = false |
||
) |
Definition at line 864 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::cropBox | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const Eigen::Vector4f & | min, | ||
const Eigen::Vector4f & | max, | ||
const Transform & | transform = Transform::getIdentity() , |
||
bool | negative = false |
||
) |
Definition at line 900 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::cropBox | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Eigen::Vector4f & | min, | ||
const Eigen::Vector4f & | max, | ||
const Transform & | transform = Transform::getIdentity() , |
||
bool | negative = false |
||
) |
Definition at line 852 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr rtabmap::util3d::cropBox | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
const Eigen::Vector4f & | min, | ||
const Eigen::Vector4f & | max, | ||
const Transform & | transform = Transform::getIdentity() , |
||
bool | negative = false |
||
) |
Definition at line 912 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::cropBox | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Eigen::Vector4f & | min, | ||
const Eigen::Vector4f & | max, | ||
const Transform & | transform = Transform::getIdentity() , |
||
bool | negative = false |
||
) |
Definition at line 856 of file util3d_filtering.cpp.
pcl::PointCloud<PointT>::Ptr rtabmap::util3d::cropBoxImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
const Eigen::Vector4f & | min, | ||
const Eigen::Vector4f & | max, | ||
const Transform & | transform, | ||
bool | negative | ||
) |
Definition at line 870 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::cropBoxImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Eigen::Vector4f & | min, | ||
const Eigen::Vector4f & | max, | ||
const Transform & | transform, | ||
bool | negative | ||
) |
Definition at line 801 of file util3d_filtering.cpp.
void rtabmap::util3d::denseMeshPostProcessing | ( | pcl::PolygonMeshPtr & | mesh, |
float | meshDecimationFactor, | ||
int | maximumPolygons, | ||
const typename pcl::PointCloud< pointRGBT >::Ptr & | cloud, | ||
float | transferColorRadius, | ||
bool | coloredOutput, | ||
bool | cleanMesh, | ||
int | minClusterSize, | ||
ProgressState * | progressState | ||
) |
Definition at line 50 of file util3d_surface.hpp.
cv::Mat rtabmap::util3d::depthFromCloud | ( | const pcl::PointCloud< pcl::PointXYZRGBA > & | cloud, |
float & | fx, | ||
float & | fy, | ||
bool | depth16U = true |
||
) |
Definition at line 78 of file util3d.cpp.
LaserScan rtabmap::util3d::deskew | ( | const LaserScan & | input, |
double | inputStamp, | ||
const rtabmap::Transform & | velocity | ||
) |
Lidar deskewing.
input | lidar, format should have time channel |
input | stamp of the lidar |
velocity | in base frame |
velocity | stamp at which it has been computed |
Definition at line 3553 of file util3d.cpp.
Definition at line 398 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointNormal >::Ptr rtabmap::util3d::downsample | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
int | step | ||
) |
Definition at line 510 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 498 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZI >::Ptr rtabmap::util3d::downsample | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
int | step | ||
) |
Definition at line 506 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZINormal >::Ptr rtabmap::util3d::downsample | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
int | step | ||
) |
Definition at line 518 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 502 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr rtabmap::util3d::downsample | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
int | step | ||
) |
Definition at line 514 of file util3d_filtering.cpp.
pcl::PointCloud<PointT>::Ptr rtabmap::util3d::downsampleImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
int | step | ||
) |
Definition at line 426 of file util3d_filtering.cpp.
Definition at line 996 of file util3d_mapping.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 , |
||
int | varianceMedianRatio = 4 , |
||
float | maxVariance = 0 , |
||
const Transform & | guess = Transform::getIdentity() , |
||
const std::map< int, cv::Point3f > & | words3B = std::map<int, cv::Point3f>() , |
||
cv::Mat * | covariance = 0 , |
||
std::vector< int > * | matchesOut = 0 , |
||
std::vector< int > * | inliersOut = 0 , |
||
bool | splitLinearCovarianceComponents = false |
||
) |
Definition at line 59 of file util3d_motion_estimation.cpp.
Transform rtabmap::util3d::estimateMotion3DTo2D | ( | const std::map< int, cv::Point3f > & | words3A, |
const std::map< int, cv::KeyPoint > & | words2B, | ||
const std::vector< CameraModel > & | cameraModels, | ||
unsigned int | samplingPolicy = 0 , |
||
int | minInliers = 10 , |
||
int | iterations = 100 , |
||
double | reprojError = 5. , |
||
int | flagsPnP = 0 , |
||
int | pnpRefineIterations = 1 , |
||
int | varianceMedianRatio = 4 , |
||
float | maxVariance = 0 , |
||
const Transform & | guess = Transform::getIdentity() , |
||
const std::map< int, cv::Point3f > & | words3B = std::map<int, cv::Point3f>() , |
||
cv::Mat * | covariance = 0 , |
||
std::vector< int > * | matchesOut = 0 , |
||
std::vector< int > * | inliersOut = 0 , |
||
bool | splitLinearCovarianceComponents = false |
||
) |
Definition at line 291 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 , |
||
cv::Mat * | covariance = 0 , |
||
std::vector< int > * | matchesOut = 0 , |
||
std::vector< int > * | inliersOut = 0 |
||
) |
Definition at line 666 of file util3d_motion_estimation.cpp.
std::vector< pcl::IndicesPtr > rtabmap::util3d::extractClusters | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | clusterTolerance, | ||
int | minClusterSize, | ||
int | maxClusterSize = std::numeric_limits<int>::max() , |
||
int * | biggestClusterIndex = 0 |
||
) |
Definition at line 2233 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 2223 of file util3d_filtering.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 2151 of file util3d_filtering.cpp.
std::vector< pcl::IndicesPtr > rtabmap::util3d::extractClusters | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | clusterTolerance, | ||
int | minClusterSize, | ||
int | maxClusterSize = std::numeric_limits<int>::max() , |
||
int * | biggestClusterIndex = 0 |
||
) |
Definition at line 2263 of file util3d_filtering.cpp.
std::vector< pcl::IndicesPtr > rtabmap::util3d::extractClusters | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | clusterTolerance, | ||
int | minClusterSize, | ||
int | maxClusterSize = std::numeric_limits<int>::max() , |
||
int * | biggestClusterIndex = 0 |
||
) |
Definition at line 2273 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 2243 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 2161 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 2253 of file util3d_filtering.cpp.
std::vector<pcl::IndicesPtr> rtabmap::util3d::extractClustersImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | clusterTolerance, | ||
int | minClusterSize, | ||
int | maxClusterSize, | ||
int * | biggestClusterIndex | ||
) |
Definition at line 2173 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::extractIndices | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
bool | negative | ||
) |
Definition at line 2303 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 2299 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 2340 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::extractIndices | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
bool | negative | ||
) |
Definition at line 2315 of file util3d_filtering.cpp.
pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT rtabmap::util3d::extractIndices | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
bool | negative, | ||
bool | keepOrganized | ||
) |
pcl::IndicesPtr rtabmap::util3d::extractIndices | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
bool | negative | ||
) |
Definition at line 2319 of file util3d_filtering.cpp.
pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT rtabmap::util3d::extractIndices | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
bool | negative, | ||
bool | keepOrganized | ||
) |
pcl::IndicesPtr rtabmap::util3d::extractIndices | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
bool | negative | ||
) |
Definition at line 2307 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 2344 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 2311 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 2353 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::extractIndicesImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
bool | negative | ||
) |
Definition at line 2285 of file util3d_filtering.cpp.
pcl::PointCloud<PointT>::Ptr rtabmap::util3d::extractIndicesImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
bool | negative, | ||
bool | keepOrganized | ||
) |
Definition at line 2325 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 2368 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 2358 of file util3d_filtering.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 137 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 190 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 199 of file util3d_correspondences.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 44 of file util3d_correspondences.cpp.
|
inline |
Definition at line 168 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 65 of file util3d_correspondences.cpp.
void rtabmap::util3d::fillProjectedCloudHoles | ( | cv::Mat & | depthRegistered, |
bool | verticalDirection, | ||
bool | fillToBorder | ||
) |
Definition at line 2927 of file util3d.cpp.
std::vector< pcl::Vertices > rtabmap::util3d::filterCloseVerticesFromMesh | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr | cloud, |
const std::vector< pcl::Vertices > & | polygons, | ||
float | radius, | ||
float | angle, | ||
bool | keepLatestInRadius | ||
) |
Definition at line 458 of file util3d_surface.cpp.
std::vector< pcl::Vertices > rtabmap::util3d::filterInvalidPolygons | ( | const std::vector< pcl::Vertices > & | polygons | ) |
Definition at line 531 of file util3d_surface.cpp.
void rtabmap::util3d::filterMaxDepth | ( | pcl::PointCloud< pcl::PointXYZ > & | inliers1, |
pcl::PointCloud< pcl::PointXYZ > & | inliers2, | ||
float | maxDepth, | ||
char | depthAxis, | ||
bool | removeDuplicates | ||
) |
Definition at line 226 of file util3d_correspondences.cpp.
std::vector< int > rtabmap::util3d::filterNaNPointsFromMesh | ( | const pcl::PointCloud< pcl::PointXYZRGB > & | cloud, |
const std::vector< pcl::Vertices > & | polygons, | ||
pcl::PointCloud< pcl::PointXYZRGB > & | outputCloud, | ||
std::vector< pcl::Vertices > & | outputPolygons | ||
) |
Definition at line 415 of file util3d_surface.cpp.
std::vector< int > 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 | ||
) |
Definition at line 375 of file util3d_surface.cpp.
std::vector< int > 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 | ||
) |
Definition at line 335 of file util3d_surface.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 364 of file util3d_correspondences.cpp.
void rtabmap::util3d::findCorrespondences | ( | const std::multimap< int, cv::KeyPoint > & | wordsA, |
const std::multimap< int, cv::KeyPoint > & | wordsB, | ||
std::list< std::pair< cv::Point2f, cv::Point2f > > & | pairs | ||
) |
if a=[1 2 3 4 6 6], b=[1 1 2 4 5 6 6], results= [(2,2) (4,4)] realPairsCount = 5
Definition at line 300 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 318 of file util3d_correspondences.cpp.
void rtabmap::util3d::fixTextureMeshForVisualization | ( | pcl::TextureMesh & | textureMesh | ) |
Definition at line 2195 of file util3d_surface.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 950 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 983 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 987 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::frustumFilteringImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Transform & | cameraPose, | ||
float | horizontalFOV, | ||
float | verticalFOV, | ||
float | nearClipPlaneDistance, | ||
float | farClipPlaneDistance, | ||
bool | negative | ||
) |
Definition at line 918 of file util3d_filtering.cpp.
pcl::PointCloud<PointT>::Ptr rtabmap::util3d::frustumFilteringImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
const Transform & | cameraPose, | ||
float | horizontalFOV, | ||
float | verticalFOV, | ||
float | nearClipPlaneDistance, | ||
float | farClipPlaneDistance, | ||
bool | negative | ||
) |
Definition at line 956 of file util3d_filtering.cpp.
Definition at line 1075 of file util3d_surface.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 54 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 67 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 122 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 158 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, | ||
float | ransacReprojThreshold = 3.0f , |
||
float | ransacConfidence = 0.99f , |
||
const std::map< int, cv::Point3f > & | refGuess3D = std::map<int, cv::Point3f>() , |
||
double * | variance = 0 , |
||
std::vector< int > * | matchesOut = 0 |
||
) |
OpenCV five-point algorithm David Nistér. An efficient solution to the five-point relative pose problem. Pattern Analysis and Machine Intelligence, IEEE Transactions on, 26(6):756–770, 2004.
OpenCV five-point algorithm David Nistér. An efficient solution to the five-point relative pose problem. Pattern Analysis and Machine Intelligence, IEEE Transactions on, 26(6):756–770, 2004.
Definition at line 209 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 276 of file util3d_correspondences.cpp.
void rtabmap::util3d::getMinMax3D | ( | const cv::Mat & | laserScan, |
cv::Point3f & | min, | ||
cv::Point3f & | max | ||
) |
Definition at line 2613 of file util3d.cpp.
void rtabmap::util3d::getMinMax3D | ( | const cv::Mat & | laserScan, |
pcl::PointXYZ & | min, | ||
pcl::PointXYZ & | max | ||
) |
Definition at line 2640 of file util3d.cpp.
Transform rtabmap::util3d::icp | ( | const pcl::PointCloud< pcl::PointXYZ >::ConstPtr & | cloud_source, |
const pcl::PointCloud< pcl::PointXYZ >::ConstPtr & | cloud_target, | ||
double | maxCorrespondenceDistance, | ||
int | maximumIterations, | ||
bool & | hasConverged, | ||
pcl::PointCloud< pcl::PointXYZ > & | cloud_source_registered, | ||
float | epsilon = 0.0f , |
||
bool | icp2D = false |
||
) |
Definition at line 424 of file util3d_registration.cpp.
Transform rtabmap::util3d::icp | ( | const pcl::PointCloud< pcl::PointXYZI >::ConstPtr & | cloud_source, |
const pcl::PointCloud< pcl::PointXYZI >::ConstPtr & | cloud_target, | ||
double | maxCorrespondenceDistance, | ||
int | maximumIterations, | ||
bool & | hasConverged, | ||
pcl::PointCloud< pcl::PointXYZI > & | cloud_source_registered, | ||
float | epsilon = 0.0f , |
||
bool | icp2D = false |
||
) |
Definition at line 437 of file util3d_registration.cpp.
Transform rtabmap::util3d::icpImpl | ( | const typename pcl::PointCloud< PointT >::ConstPtr & | cloud_source, |
const typename pcl::PointCloud< PointT >::ConstPtr & | cloud_target, | ||
double | maxCorrespondenceDistance, | ||
int | maximumIterations, | ||
bool & | hasConverged, | ||
pcl::PointCloud< PointT > & | cloud_source_registered, | ||
float | epsilon, | ||
bool | icp2D | ||
) |
Definition at line 386 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 495 of file util3d_registration.cpp.
Transform rtabmap::util3d::icpPointToPlane | ( | const pcl::PointCloud< pcl::PointXYZINormal >::ConstPtr & | cloud_source, |
const pcl::PointCloud< pcl::PointXYZINormal >::ConstPtr & | cloud_target, | ||
double | maxCorrespondenceDistance, | ||
int | maximumIterations, | ||
bool & | hasConverged, | ||
pcl::PointCloud< pcl::PointXYZINormal > & | cloud_source_registered, | ||
float | epsilon = 0.0f , |
||
bool | icp2D = false |
||
) |
Definition at line 508 of file util3d_registration.cpp.
Transform rtabmap::util3d::icpPointToPlaneImpl | ( | const typename pcl::PointCloud< PointNormalT >::ConstPtr & | cloud_source, |
const typename pcl::PointCloud< PointNormalT >::ConstPtr & | cloud_target, | ||
double | maxCorrespondenceDistance, | ||
int | maximumIterations, | ||
bool & | hasConverged, | ||
pcl::PointCloud< PointNormalT > & | cloud_source_registered, | ||
float | epsilon, | ||
bool | icp2D | ||
) |
Definition at line 451 of file util3d_registration.cpp.
bool rtabmap::util3d::intersectRayMesh | ( | const Eigen::Vector3f & | origin, |
const Eigen::Vector3f & | dir, | ||
const typename pcl::PointCloud< PointT > & | cloud, | ||
const std::vector< pcl::Vertices > & | polygons, | ||
bool | ignoreBackFaces, | ||
float & | distance, | ||
Eigen::Vector3f & | normal, | ||
int & | index | ||
) |
Definition at line 322 of file util3d_surface.hpp.
bool rtabmap::util3d::intersectRayTriangle | ( | const Eigen::Vector3f & | p, |
const Eigen::Vector3f & | dir, | ||
const Eigen::Vector3f & | v0, | ||
const Eigen::Vector3f & | v1, | ||
const Eigen::Vector3f & | v2, | ||
float & | distance, | ||
Eigen::Vector3f & | normal | ||
) |
intersectRayTriangle(): find the 3D intersection of a ray with a triangle Input: p = origin of the ray dir = direction of the ray v0 = point 0 of the triangle v1 = point 1 of the triangle v2 = point 2 of the triangle Output: distance = distance from origin along ray direction normal = normal of the triangle (not normalized) Return: true = intersect in unique point inside the triangle
Intersection point can be computed with "I = p + dir*distance"
Copyright 2001 softSurfer, 2012 Dan Sunday This code may be freely used and modified for any purpose providing that this copyright notice is included with it. SoftSurfer makes no warranty for this code, and cannot be held liable for any real or imagined damage resulting from its use. Users of this code must verify correctness for their application.
Mathieu: Adapted for PCL format
Definition at line 3776 of file util3d_surface.cpp.
bool rtabmap::util3d::isFinite | ( | const cv::Point3f & | pt | ) |
Definition at line 3327 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScan2dFromPointCloud | ( | const pcl::PointCloud< pcl::PointNormal > & | cloud, |
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 2058 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScan2dFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZ > & | cloud, |
const pcl::PointCloud< pcl::Normal > & | normals, | ||
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 2098 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScan2dFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZ > & | cloud, |
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 1992 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScan2dFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZI > & | cloud, |
const pcl::PointCloud< pcl::Normal > & | normals, | ||
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 2184 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScan2dFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZI > & | cloud, |
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 2024 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScan2dFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZINormal > & | cloud, |
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 2142 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() |
||
) |
Simulate a laser scan rotating counterclockwise, using middle line of the depth image.
Definition at line 1321 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZ > rtabmap::util3d::laserScanFromDepthImages | ( | const cv::Mat & | depthImages, |
const std::vector< CameraModel > & | cameraModels, | ||
float | maxDepth, | ||
float | minDepth | ||
) |
Simulate a laser scan rotating counterclockwise, using middle line of the depth images. The last value of the scan is the most left value of the first depth image. The first value of the scan is the most right value of the last depth image.
Definition at line 1357 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScanFromPointCloud | ( | const pcl::PointCloud< pcl::PointNormal > & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 1460 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScanFromPointCloud | ( | const pcl::PointCloud< pcl::PointNormal > & | cloud, |
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 1456 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScanFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZ > & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 1394 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScanFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZ > & | cloud, |
const pcl::PointCloud< pcl::Normal > & | normals, | ||
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 1539 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScanFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZ > & | cloud, |
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 1390 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScanFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZI > & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 1661 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScanFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZI > & | cloud, |
const pcl::PointCloud< pcl::Normal > & | normals, | ||
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 1860 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScanFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZI > & | cloud, |
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 1656 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScanFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZINormal > & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 1911 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScanFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZINormal > & | cloud, |
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 1907 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScanFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZRGB > & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 1590 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScanFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZRGB > & | cloud, |
const pcl::PointCloud< pcl::Normal > & | normals, | ||
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 1725 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScanFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZRGB > & | cloud, |
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 1585 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScanFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal > & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 1777 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScanFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal > & | cloud, |
const Transform & | transform = Transform() , |
||
bool | filterNaNs = true |
||
) |
Definition at line 1773 of file util3d.cpp.
LaserScan rtabmap::util3d::laserScanFromPointCloud | ( | const PointCloud2T & | cloud, |
bool | filterNaNs, | ||
bool | is2D, | ||
const Transform & | transform | ||
) |
Definition at line 37 of file util3d.hpp.
Definition at line 2428 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::laserScanToPointCloud | ( | const LaserScan & | laserScan, |
const Transform & | transform = Transform() |
||
) |
Definition at line 2269 of file util3d.cpp.
pcl::PCLPointCloud2::Ptr rtabmap::util3d::laserScanToPointCloud2 | ( | const LaserScan & | laserScan, |
const Transform & | transform = Transform() |
||
) |
Definition at line 2230 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZI >::Ptr rtabmap::util3d::laserScanToPointCloudI | ( | const LaserScan & | laserScan, |
const Transform & | transform = Transform() , |
||
float | intensity = 0.0f |
||
) |
Definition at line 2349 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZINormal >::Ptr rtabmap::util3d::laserScanToPointCloudINormal | ( | const LaserScan & | laserScan, |
const Transform & | transform = Transform() , |
||
float | intensity = 0.0f |
||
) |
Definition at line 2402 of file util3d.cpp.
pcl::PointCloud< pcl::PointNormal >::Ptr rtabmap::util3d::laserScanToPointCloudNormal | ( | const LaserScan & | laserScan, |
const Transform & | transform = Transform() |
||
) |
Definition at line 2296 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::laserScanToPointCloudRGB | ( | const LaserScan & | laserScan, |
const Transform & | transform = Transform() , |
||
unsigned char | r = 100 , |
||
unsigned char | g = 100 , |
||
unsigned char | b = 100 |
||
) |
Definition at line 2322 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr rtabmap::util3d::laserScanToPointCloudRGBNormal | ( | const LaserScan & | laserScan, |
const Transform & | transform = Transform() , |
||
unsigned char | r = 100 , |
||
unsigned char | g = 100 , |
||
unsigned char | b = 100 |
||
) |
Definition at line 2376 of file util3d.cpp.
pcl::PointXYZI rtabmap::util3d::laserScanToPointI | ( | const LaserScan & | laserScan, |
int | index, | ||
float | intensity | ||
) |
Definition at line 2505 of file util3d.cpp.
pcl::PointXYZINormal rtabmap::util3d::laserScanToPointINormal | ( | const LaserScan & | laserScan, |
int | index, | ||
float | intensity | ||
) |
Definition at line 2579 of file util3d.cpp.
Definition at line 2443 of file util3d.cpp.
pcl::PointXYZRGB rtabmap::util3d::laserScanToPointRGB | ( | const LaserScan & | laserScan, |
int | index, | ||
unsigned char | r = 100 , |
||
unsigned char | g = 100 , |
||
unsigned char | b = 100 |
||
) |
Definition at line 2465 of file util3d.cpp.
pcl::PointXYZRGBNormal rtabmap::util3d::laserScanToPointRGBNormal | ( | const LaserScan & | laserScan, |
int | index, | ||
unsigned char | r, | ||
unsigned char | g, | ||
unsigned char | b | ||
) |
Definition at line 2531 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::loadBINCloud | ( | const std::string & | fileName | ) |
Definition at line 3444 of file util3d.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::loadBINCloud | ( | const std::string & | fileName, |
int | dim | ||
) |
Definition at line 3449 of file util3d.cpp.
cv::Mat rtabmap::util3d::loadBINScan | ( | const std::string & | fileName | ) |
Assume KITTI velodyne format Return scan 4 channels (format=XYZI).
Definition at line 3421 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 3512 of file util3d.cpp.
LaserScan rtabmap::util3d::loadScan | ( | const std::string & | path | ) |
Definition at line 3454 of file util3d.cpp.
cv::Mat rtabmap::util3d::mergeTextures | ( | pcl::TextureMesh & | mesh, |
const std::map< int, cv::Mat > & | images, | ||
const std::map< int, CameraModel > & | calibrations, | ||
const Memory * | memory = 0 , |
||
const DBDriver * | dbDriver = 0 , |
||
int | textureSize = 4096 , |
||
int | textureCount = 1 , |
||
const std::vector< std::map< int, pcl::PointXY > > & | vertexToPixels = std::vector<std::map<int, pcl::PointXY> >() , |
||
bool | gainCompensation = true , |
||
float | gainBeta = 10.0f , |
||
bool | gainRGB = true , |
||
bool | blending = true , |
||
int | blendingDecimation = 0 , |
||
int | brightnessContrastRatioLow = 0 , |
||
int | brightnessContrastRatioHigh = 0 , |
||
bool | exposureFusion = false , |
||
const ProgressState * | state = 0 , |
||
unsigned char | blankValue = 255 , |
||
std::map< int, std::map< int, cv::Vec4d > > * | gains = 0 , |
||
std::map< int, std::map< int, cv::Mat > > * | blendingGains = 0 , |
||
std::pair< float, float > * | contrastValues = 0 |
||
) |
Merge all textures in the mesh into "textureCount" textures of size "textureSize".
Definition at line 1438 of file util3d_surface.cpp.
cv::Mat rtabmap::util3d::mergeTextures | ( | pcl::TextureMesh & | mesh, |
const std::map< int, cv::Mat > & | images, | ||
const std::map< int, std::vector< CameraModel > > & | calibrations, | ||
const Memory * | memory = 0 , |
||
const DBDriver * | dbDriver = 0 , |
||
int | textureSize = 4096 , |
||
int | textureCount = 1 , |
||
const std::vector< std::map< int, pcl::PointXY > > & | vertexToPixels = std::vector<std::map<int, pcl::PointXY> >() , |
||
bool | gainCompensation = true , |
||
float | gainBeta = 10.0f , |
||
bool | gainRGB = true , |
||
bool | blending = true , |
||
int | blendingDecimation = 0 , |
||
int | brightnessContrastRatioLow = 0 , |
||
int | brightnessContrastRatioHigh = 0 , |
||
bool | exposureFusion = false , |
||
const ProgressState * | state = 0 , |
||
unsigned char | blankValue = 255 , |
||
std::map< int, std::map< int, cv::Vec4d > > * | gains = 0 , |
||
std::map< int, std::map< int, cv::Mat > > * | blendingGains = 0 , |
||
std::pair< float, float > * | contrastValues = 0 |
||
) |
Original code from OpenCV: GainCompensator
Original code from OpenCV: GainCompensator
Definition at line 1490 of file util3d_surface.cpp.
pcl::PolygonMesh::Ptr rtabmap::util3d::meshDecimation | ( | const pcl::PolygonMesh::Ptr & | mesh, |
float | factor | ||
) |
Definition at line 3761 of file util3d_surface.cpp.
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr 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 |
||
) |
Definition at line 3427 of file util3d_surface.cpp.
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr 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 |
||
) |
Definition at line 3403 of file util3d_surface.cpp.
bool rtabmap::util3d::multiBandTexturing | ( | const std::string & | outputOBJPath, |
const pcl::PCLPointCloud2 & | cloud, | ||
const std::vector< pcl::Vertices > & | polygons, | ||
const std::map< int, Transform > & | cameraPoses, | ||
const std::vector< std::map< int, pcl::PointXY > > & | vertexToPixels, | ||
const std::map< int, cv::Mat > & | images, | ||
const std::map< int, std::vector< CameraModel > > & | cameraModels, | ||
const Memory * | memory = 0 , |
||
const DBDriver * | dbDriver = 0 , |
||
int | textureSize = 8192 , |
||
const std::string & | textureFormat = "jpg" , |
||
const std::map< int, std::map< int, cv::Vec4d > > & | gains = std::map<int, std::map<int, cv::Vec4d> >() , |
||
const std::map< int, std::map< int, cv::Mat > > & | blendingGains = std::map<int, std::map<int, cv::Mat> >() , |
||
const std::pair< float, float > & | contrastValues = std::pair<float, float>(0,0) , |
||
bool | gainRGB = true |
||
) |
Definition at line 2234 of file util3d_surface.cpp.
bool rtabmap::util3d::multiBandTexturing | ( | const std::string & | outputOBJPath, |
const pcl::PCLPointCloud2 & | cloud, | ||
const std::vector< pcl::Vertices > & | polygons, | ||
const std::map< int, Transform > & | cameraPoses, | ||
const std::vector< std::map< int, pcl::PointXY > > & | vertexToPixels, | ||
const std::map< int, cv::Mat > & | images, | ||
const std::map< int, std::vector< CameraModel > > & | cameraModels, | ||
const Memory * | memory = 0 , |
||
const DBDriver * | dbDriver = 0 , |
||
unsigned int | textureSize = 8192 , |
||
unsigned int | textureDownscale = 2 , |
||
const std::string & | nbContrib = "1 5 10 0" , |
||
const std::string & | textureFormat = "jpg" , |
||
const std::map< int, std::map< int, cv::Vec4d > > & | gains = std::map<int, std::map<int, cv::Vec4d> >() , |
||
const std::map< int, std::map< int, cv::Mat > > & | blendingGains = std::map<int, std::map<int, cv::Mat> >() , |
||
const std::pair< float, float > & | contrastValues = std::pair<float, float>(0,0) , |
||
bool | gainRGB = true , |
||
unsigned int | unwrapMethod = 0 , |
||
bool | fillHoles = false , |
||
unsigned int | padding = 5 , |
||
double | bestScoreThreshold = 0.1 , |
||
double | angleHardThreshold = 90.0 , |
||
bool | forceVisibleByAllVertices = false |
||
) |
Texture mesh with AliceVision's multiband texturing approach. See also https://meshroom-manual.readthedocs.io/en/bibtex1/node-reference/nodes/Texturing.html.
outputOBJPath | Output OBJ path |
cloud | input Cloud of the mesh. |
polygons | Input polygons of the mesh. |
cameraPoses | Poses of the cameras. |
vertexToPixels | Output from createTextureMesh(). |
images | Images corresponding to cameraPoses, raw or compressed, can be empty if memory or dbDriver should be used. |
cameraModels | Camera calibrations corresponding to cameraPoses. |
memory | Should be set if images and dbDriver are not set. |
dbDriver | Should be set if images and memory are not set. |
textureSize | Output texture size 1024, 2048, 4096, 8192, 16384. |
textureDownscale | Downscaling to 4 or 8 will reduce the texture quality but speed up the computation time. Set Texture Downscale to 1 instead of 2 to get the maximum possible resolution with the resolution of your images. The output texture size will be divided by this value, e.g., with texture size of 8192 and downscale value of 2, the output will be 4096. |
nbContrib | number of contributions per frequency band for the multi-band blending (should be 4 values) |
textureFormat | Output texture format: "png" or "jpg". |
gains | Optional output of mergeTextures(). |
blendingGains | Optional output of mergeTextures(). |
contrastValues | Optional output of mergeTextures(). |
gainRGB | Apply gain compensation on each RGB channels separately, otherwise it is apply equally to all channels. |
unwrapMethod | Method to unwrap input mesh if it does not have UV coordinates 0=Basic (> 600k faces) fast and simple. Can generate multiple atlases 2=LSCM (<= 600k faces): optimize space. Generates one atlas 1=ABF (<= 300k faces): optimize space and stretch. Generates one atlas. |
fillHoles | Fill Texture holes with plausible values True/False. |
padding | Texture edge padding size in pixel (0-100). |
bestScoreThreshold | 0.0 to disable filtering based on threshold to relative best score (0.0-1.0). |
angleHardThreshold | 0.0 to disable angle hard threshold filtering (0.0, 180.0). |
forceVisibleByAllVertices | Triangle visibility is based on the union of vertices visibility. |
Definition at line 2271 of file util3d_surface.cpp.
pcl::IndicesPtr rtabmap::util3d::normalFiltering | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | angleMax, | ||
const Eigen::Vector4f & | normal, | ||
int | normalKSearch, | ||
const Eigen::Vector4f & | viewpoint, | ||
float | groundNormalsUp = 0.0f |
||
) |
Definition at line 2117 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, | ||
float | groundNormalsUp = 0.0f |
||
) |
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 2027 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::normalFiltering | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
float | angleMax, | ||
const Eigen::Vector4f & | normal, | ||
int | normalKSearch, | ||
const Eigen::Vector4f & | viewpoint, | ||
float | groundNormalsUp = 0.0f |
||
) |
For convenience.
Definition at line 1938 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::normalFiltering | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | angleMax, | ||
const Eigen::Vector4f & | normal, | ||
int | normalKSearch, | ||
const Eigen::Vector4f & | viewpoint, | ||
float | groundNormalsUp = 0.0f |
||
) |
Definition at line 2049 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::normalFiltering | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | angleMax, | ||
const Eigen::Vector4f & | normal, | ||
int | normalKSearch, | ||
const Eigen::Vector4f & | viewpoint, | ||
float | groundNormalsUp = 0.0f |
||
) |
Definition at line 2139 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, | ||
float | groundNormalsUp = 0.0f |
||
) |
Definition at line 2038 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, | ||
float | groundNormalsUp = 0.0f |
||
) |
Definition at line 1949 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, | ||
float | groundNormalsUp = 0.0f |
||
) |
Definition at line 2128 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::normalFilteringImpl | ( | const typename pcl::PointCloud< PointNormalT >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | angleMax, | ||
const Eigen::Vector4f & | normal, | ||
const Eigen::Vector4f & | viewpoint, | ||
float | groundNormalsUp | ||
) |
Definition at line 2062 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::normalFilteringImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | angleMax, | ||
const Eigen::Vector4f & | normal, | ||
int | normalKSearch, | ||
const Eigen::Vector4f & | viewpoint, | ||
float | groundNormalsUp | ||
) |
Definition at line 1963 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) |
||
) |
std::vector<pcl::Vertices> rtabmap::util3d::normalizePolygonsSide | ( | const typename pcl::PointCloud< pointT > & | cloud, |
const std::vector< pcl::Vertices > & | polygons, | ||
const pcl::PointXYZ & | viewPoint | ||
) |
Definition at line 20 of file util3d_surface.hpp.
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 306 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 345 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 231 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 261 of file util3d_mapping.hpp.
void rtabmap::util3d::occupancy2DFromLaserScan | ( | const cv::Mat & | scan, |
const cv::Point3f & | viewpoint, | ||
cv::Mat & | empty, | ||
cv::Mat & | occupied, | ||
float | cellSize, | ||
bool | unknownSpaceFilled = false , |
||
float | scanMaxRange = 0.0f |
||
) |
Definition at line 70 of file util3d_mapping.cpp.
void rtabmap::util3d::occupancy2DFromLaserScan | ( | const cv::Mat & | scan, |
cv::Mat & | empty, | ||
cv::Mat & | occupied, | ||
float | cellSize, | ||
bool | unknownSpaceFilled = false , |
||
float | scanMaxRange = 0.0f |
||
) |
Definition at line 50 of file util3d_mapping.cpp.
void rtabmap::util3d::occupancy2DFromLaserScan | ( | const cv::Mat & | scanHit, |
const cv::Mat & | scanNoHit, | ||
const cv::Point3f & | viewpoint, | ||
cv::Mat & | empty, | ||
cv::Mat & | occupied, | ||
float | cellSize, | ||
bool | unknownSpaceFilled = false , |
||
float | scanMaxRange = 0.0f |
||
) |
Definition at line 82 of file util3d_mapping.cpp.
std::vector< pcl::Vertices > rtabmap::util3d::organizedFastMesh | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
double | angleTolerance, | ||
bool | quad, | ||
int | trianglePixelSize, | ||
const Eigen::Vector3f & | viewpoint = Eigen::Vector3f(0,0,0) |
||
) |
Definition at line 168 of file util3d_surface.cpp.
std::vector< pcl::Vertices > 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) |
||
) |
Definition at line 206 of file util3d_surface.cpp.
std::vector< pcl::Vertices > 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) |
||
) |
Definition at line 244 of file util3d_surface.cpp.
pcl::IndicesPtr rtabmap::util3d::passThrough | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const std::string & | axis, | ||
float | min, | ||
float | max, | ||
bool | negative = false |
||
) |
Definition at line 742 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointNormal >::Ptr rtabmap::util3d::passThrough | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
const std::string & | axis, | ||
float | min, | ||
float | max, | ||
bool | negative = false |
||
) |
Definition at line 787 of file util3d_filtering.cpp.
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 730 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 775 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::passThrough | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const std::string & | axis, | ||
float | min, | ||
float | max, | ||
bool | negative = false |
||
) |
Definition at line 738 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZI >::Ptr rtabmap::util3d::passThrough | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
const std::string & | axis, | ||
float | min, | ||
float | max, | ||
bool | negative = false |
||
) |
Definition at line 783 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::passThrough | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const std::string & | axis, | ||
float | min, | ||
float | max, | ||
bool | negative = false |
||
) |
Definition at line 750 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZINormal >::Ptr rtabmap::util3d::passThrough | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
const std::string & | axis, | ||
float | min, | ||
float | max, | ||
bool | negative = false |
||
) |
Definition at line 795 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 734 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 779 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::passThrough | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const std::string & | axis, | ||
float | min, | ||
float | max, | ||
bool | negative = false |
||
) |
Definition at line 746 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr rtabmap::util3d::passThrough | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
const std::string & | axis, | ||
float | min, | ||
float | max, | ||
bool | negative = false |
||
) |
Definition at line 791 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::passThroughImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const std::string & | axis, | ||
float | min, | ||
float | max, | ||
bool | negative | ||
) |
Definition at line 708 of file util3d_filtering.cpp.
pcl::PointCloud<PointT>::Ptr rtabmap::util3d::passThroughImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
const std::string & | axis, | ||
float | min, | ||
float | max, | ||
bool | negative | ||
) |
Definition at line 756 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 2693 of file util3d.cpp.
cv::Mat rtabmap::util3d::projectCloudToCamera | ( | const cv::Size & | imageSize, |
const cv::Mat & | cameraMatrixK, | ||
const pcl::PCLPointCloud2::Ptr | laserScan, | ||
const rtabmap::Transform & | cameraTransform | ||
) |
Definition at line 2845 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 2778 of file util3d.cpp.
std::vector<std::pair< std::pair<int, int>, pcl::PointXY> > RTABMAP_CORE_EXPORT rtabmap::util3d::projectCloudToCameras | ( | const pcl::PointCloud< pcl::PointXYZINormal > & | cloud, |
const std::map< int, Transform > & | cameraPoses, | ||
const std::map< int, std::vector< CameraModel > > & | cameraModels, | ||
float | maxDistance = 0.0f , |
||
float | maxAngle = 0.0f , |
||
const std::vector< float > & | roiRatios = std::vector< float >() , |
||
const cv::Mat & | projMask = cv::Mat() , |
||
bool | distanceToCamPolicy = false , |
||
const ProgressState * | state = 0 |
||
) |
For each point, return pixel of the best camera (NodeID->CameraIndex) looking at it based on the policy and parameters
std::vector<std::pair< std::pair<int, int>, pcl::PointXY> > RTABMAP_CORE_EXPORT rtabmap::util3d::projectCloudToCameras | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal > & | cloud, |
const std::map< int, Transform > & | cameraPoses, | ||
const std::map< int, std::vector< CameraModel > > & | cameraModels, | ||
float | maxDistance = 0.0f , |
||
float | maxAngle = 0.0f , |
||
const std::vector< float > & | roiRatios = std::vector< float >() , |
||
const cv::Mat & | projMask = cv::Mat() , |
||
bool | distanceToCamPolicy = false , |
||
const ProgressState * | state = 0 |
||
) |
For each point, return pixel of the best camera (NodeID->CameraIndex) looking at it based on the policy and parameters
std::vector<std::pair< std::pair<int, int>, pcl::PointXY> > rtabmap::util3d::projectCloudToCameras | ( | const typename pcl::PointCloud< pcl::PointXYZINormal > & | cloud, |
const std::map< int, Transform > & | cameraPoses, | ||
const std::map< int, std::vector< CameraModel > > & | cameraModels, | ||
float | maxDistance, | ||
float | maxAngle, | ||
const std::vector< float > & | roiRatios, | ||
const cv::Mat & | projMask, | ||
bool | distanceToCamPolicy, | ||
const ProgressState * | state | ||
) |
Definition at line 3305 of file util3d.cpp.
std::vector<std::pair< std::pair<int, int>, pcl::PointXY> > rtabmap::util3d::projectCloudToCameras | ( | const typename pcl::PointCloud< pcl::PointXYZRGBNormal > & | cloud, |
const std::map< int, Transform > & | cameraPoses, | ||
const std::map< int, std::vector< CameraModel > > & | cameraModels, | ||
float | maxDistance, | ||
float | maxAngle, | ||
const std::vector< float > & | roiRatios, | ||
const cv::Mat & | projMask, | ||
bool | distanceToCamPolicy, | ||
const ProgressState * | state | ||
) |
Definition at line 3283 of file util3d.cpp.
std::vector<std::pair< std::pair<int, int>, pcl::PointXY> > rtabmap::util3d::projectCloudToCamerasImpl | ( | const typename pcl::PointCloud< PointT > & | cloud, |
const std::map< int, Transform > & | cameraPoses, | ||
const std::map< int, std::vector< CameraModel > > & | cameraModels, | ||
float | maxDistance, | ||
float | maxAngle, | ||
const std::vector< float > & | roiRatios, | ||
const cv::Mat & | projMask, | ||
bool | distanceToCamPolicy, | ||
const ProgressState * | state | ||
) |
For each point, return pixel of the best camera (NodeID->CameraIndex) looking at it based on the policy and parameters
Definition at line 3028 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 | depthErrorRatio = 0.02f |
||
) |
Definition at line 215 of file util3d.cpp.
Eigen::Vector3f rtabmap::util3d::projectDepthTo3DRay | ( | const cv::Size & | imageSize, |
float | x, | ||
float | y, | ||
float | cx, | ||
float | cy, | ||
float | fx, | ||
float | fy | ||
) |
Definition at line 246 of file util3d.cpp.
cv::Point3f rtabmap::util3d::projectDisparityTo3D | ( | const cv::Point2f & | pt, |
const cv::Mat & | disparity, | ||
const StereoCameraModel & | model | ||
) |
Definition at line 2674 of file util3d.cpp.
cv::Point3f rtabmap::util3d::projectDisparityTo3D | ( | const cv::Point2f & | pt, |
float | disparity, | ||
const StereoCameraModel & | model | ||
) |
Definition at line 2653 of file util3d.cpp.
pcl::IndicesPtr rtabmap::util3d::proportionalRadiusFiltering | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const std::vector< int > & | viewpointIndices, | ||
const std::map< int, Transform > & | viewpoints, | ||
float | factor = 0.01f , |
||
float | neighborScale = 2.0f |
||
) |
Definition at line 1372 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::proportionalRadiusFiltering | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
const std::vector< int > & | viewpointIndices, | ||
const std::map< int, Transform > & | viewpoints, | ||
float | factor = 0.01f , |
||
float | neighborScale = 2.0f |
||
) |
Definition at line 1200 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::proportionalRadiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const std::vector< int > & | viewpointIndices, | ||
const std::map< int, Transform > & | viewpoints, | ||
float | factor = 0.01f , |
||
float | neighborScale = 2.0f |
||
) |
Filter points based on distance from their viewpoint.
cloud | the input cloud. |
indices | the input indices of the cloud to check, if empty, all points in the cloud are checked. |
viewpointIndices | should be same size than the input cloud, it tells the viewpoint index in viewpoints for each point. |
viewpoints | the viewpoints. |
factor | will determine the search radius based on the distance from a point and its viewpoint. Setting it higher will filter points farther from accurate points (but processing time will be also higher). |
neighborScale | will scale the search radius of neighbors found around a point. Setting it higher will accept more noisy points close to accurate points (but processing time will be also higher). |
Definition at line 1362 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::proportionalRadiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
const std::vector< int > & | viewpointIndices, | ||
const std::map< int, Transform > & | viewpoints, | ||
float | factor = 0.01f , |
||
float | neighborScale = 2.0f |
||
) |
Definition at line 1190 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::proportionalRadiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const std::vector< int > & | viewpointIndices, | ||
const std::map< int, Transform > & | viewpoints, | ||
float | factor = 0.01f , |
||
float | neighborScale = 2.0f |
||
) |
Definition at line 1402 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::proportionalRadiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
const std::vector< int > & | viewpointIndices, | ||
const std::map< int, Transform > & | viewpoints, | ||
float | factor = 0.01f , |
||
float | neighborScale = 2.0f |
||
) |
Definition at line 1230 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::proportionalRadiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const std::vector< int > & | viewpointIndices, | ||
const std::map< int, Transform > & | viewpoints, | ||
float | factor = 0.01f , |
||
float | neighborScale = 2.0f |
||
) |
Definition at line 1412 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::proportionalRadiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
const std::vector< int > & | viewpointIndices, | ||
const std::map< int, Transform > & | viewpoints, | ||
float | factor = 0.01f , |
||
float | neighborScale = 2.0f |
||
) |
Definition at line 1240 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::proportionalRadiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const std::vector< int > & | viewpointIndices, | ||
const std::map< int, Transform > & | viewpoints, | ||
float | factor = 0.01f , |
||
float | neighborScale = 2.0f |
||
) |
Definition at line 1382 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::proportionalRadiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const std::vector< int > & | viewpointIndices, | ||
const std::map< int, Transform > & | viewpoints, | ||
float | factor = 0.01f , |
||
float | neighborScale = 2.0f |
||
) |
Definition at line 1210 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::proportionalRadiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const std::vector< int > & | viewpointIndices, | ||
const std::map< int, Transform > & | viewpoints, | ||
float | factor = 0.01f , |
||
float | neighborScale = 2.0f |
||
) |
Definition at line 1392 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::proportionalRadiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
const std::vector< int > & | viewpointIndices, | ||
const std::map< int, Transform > & | viewpoints, | ||
float | factor = 0.01f , |
||
float | neighborScale = 2.0f |
||
) |
Definition at line 1220 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::proportionalRadiusFilteringImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const std::vector< int > & | viewpointIndices, | ||
const std::map< int, Transform > & | viewpoints, | ||
float | factor, | ||
float | neighborScale | ||
) |
Definition at line 1252 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 1169 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::radiusFiltering | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
float | radiusSearch, | ||
int | minNeighborsInRadius | ||
) |
Definition at line 1092 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 1165 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::radiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
float | radiusSearch, | ||
int | minNeighborsInRadius | ||
) |
For convenience.
Definition at line 1087 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::radiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | radiusSearch, | ||
int | minNeighborsInRadius | ||
) |
Definition at line 1181 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::radiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
float | radiusSearch, | ||
int | minNeighborsInRadius | ||
) |
Definition at line 1107 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::radiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | radiusSearch, | ||
int | minNeighborsInRadius | ||
) |
Definition at line 1185 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::radiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
float | radiusSearch, | ||
int | minNeighborsInRadius | ||
) |
Definition at line 1112 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 1173 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::radiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
float | radiusSearch, | ||
int | minNeighborsInRadius | ||
) |
Definition at line 1097 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 1177 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::radiusFiltering | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
float | radiusSearch, | ||
int | minNeighborsInRadius | ||
) |
Definition at line 1102 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::radiusFilteringImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | radiusSearch, | ||
int | minNeighborsInRadius | ||
) |
Definition at line 1119 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointNormal >::Ptr rtabmap::util3d::randomSampling | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
int | samples | ||
) |
Definition at line 686 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 682 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZI >::Ptr rtabmap::util3d::randomSampling | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
int | samples | ||
) |
Definition at line 698 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZINormal >::Ptr rtabmap::util3d::randomSampling | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
int | samples | ||
) |
Definition at line 702 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 690 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr rtabmap::util3d::randomSampling | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
int | samples | ||
) |
Definition at line 694 of file util3d_filtering.cpp.
pcl::PointCloud<PointT>::Ptr rtabmap::util3d::randomSamplingImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
int | samples | ||
) |
Definition at line 670 of file util3d_filtering.cpp.
LaserScan rtabmap::util3d::rangeFiltering | ( | const LaserScan & | scan, |
float | rangeMin, | ||
float | rangeMax | ||
) |
Definition at line 347 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 822 of file util3d_mapping.cpp.
pcl::PCLPointCloud2::Ptr rtabmap::util3d::removeNaNFromPointCloud | ( | const pcl::PCLPointCloud2::Ptr & | cloud | ) |
Definition at line 1015 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::removeNaNFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud | ) |
Definition at line 1002 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZI >::Ptr rtabmap::util3d::removeNaNFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud | ) |
Definition at line 1010 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::removeNaNFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud | ) |
Definition at line 1006 of file util3d_filtering.cpp.
pcl::PointCloud<PointT>::Ptr rtabmap::util3d::removeNaNFromPointCloudImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud | ) |
Definition at line 994 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointNormal >::Ptr rtabmap::util3d::removeNaNNormalsFromPointCloud | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud | ) |
Definition at line 1070 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZINormal >::Ptr rtabmap::util3d::removeNaNNormalsFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud | ) |
Definition at line 1080 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr rtabmap::util3d::removeNaNNormalsFromPointCloud | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud | ) |
Definition at line 1075 of file util3d_filtering.cpp.
pcl::PointCloud<PointT>::Ptr rtabmap::util3d::removeNaNNormalsFromPointCloudImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud | ) |
Definition at line 1062 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 138 of file util3d.cpp.
cv::Mat RTABMAP_CORE_EXPORT rtabmap::util3d::rgbFromCloud | ( | const pcl::PointCloud< pcl::PointXYZRGBA > & | cloud, |
bool | bgrOrder = true |
||
) |
void rtabmap::util3d::savePCDWords | ( | const std::string & | fileName, |
const std::multimap< int, cv::Point3f > & | words, | ||
const Transform & | transform = Transform::getIdentity() |
||
) |
Definition at line 3402 of file util3d.cpp.
void rtabmap::util3d::savePCDWords | ( | const std::string & | fileName, |
const std::multimap< int, pcl::PointXYZ > & | words, | ||
const Transform & | transform = Transform::getIdentity() |
||
) |
Definition at line 3384 of file util3d.cpp.
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) , |
||
float | groundNormalsUp = 0 |
||
) |
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, | ||
float | groundNormalsUp | ||
) |
Definition at line 54 of file util3d_mapping.hpp.
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, | ||
float | groundNormalsUp | ||
) |
Definition at line 199 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 779 of file util3d_motion_estimation.cpp.
double rtabmap::util3d::sqr | ( | uchar | v | ) |
Definition at line 1433 of file util3d_surface.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 1713 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 1792 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 1679 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 1510 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::subtractFiltering | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const pcl::PointCloud< pcl::PointXYZINormal >::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 1690 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZINormal >::Ptr rtabmap::util3d::subtractFiltering | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | substractCloud, | ||
float | radiusSearch, | ||
float | maxAngle = M_PI/4.0f , |
||
int | minNeighborsInRadius = 1 |
||
) |
For convenience.
Definition at line 1523 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 1499 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 1423 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 |
||
) |
Definition at line 1701 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 |
||
) |
Definition at line 1536 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::subtractFilteringImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const typename pcl::PointCloud< PointT >::Ptr & | substractCloud, | ||
const pcl::IndicesPtr & | substractIndices, | ||
float | radiusSearch, | ||
float | maxAngle, | ||
int | minNeighborsInRadius | ||
) |
Definition at line 1551 of file util3d_filtering.cpp.
pcl::IndicesPtr rtabmap::util3d::subtractFilteringImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const typename pcl::PointCloud< PointT >::Ptr & | substractCloud, | ||
const pcl::IndicesPtr & | substractIndices, | ||
float | radiusSearch, | ||
int | minNeighborsInRadius | ||
) |
Definition at line 1437 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 , |
||
cv::Mat * | variance = 0 |
||
) |
Definition at line 63 of file util3d_registration.cpp.
Transform rtabmap::util3d::transformFromXYZCorrespondencesSVD | ( | const pcl::PointCloud< pcl::PointXYZ > & | cloud1, |
const pcl::PointCloud< pcl::PointXYZ > & | cloud2 | ||
) |
Definition at line 50 of file util3d_registration.cpp.
LaserScan rtabmap::util3d::transformLaserScan | ( | const LaserScan & | laserScan, |
const Transform & | transform | ||
) |
Definition at line 39 of file util3d_transforms.cpp.
cv::Point3d rtabmap::util3d::transformPoint | ( | const cv::Point3d & | pt, |
const Transform & | transform | ||
) |
Definition at line 221 of file util3d_transforms.cpp.
cv::Point3f rtabmap::util3d::transformPoint | ( | const cv::Point3f & | pt, |
const Transform & | transform | ||
) |
Definition at line 211 of file util3d_transforms.cpp.
pcl::PointNormal rtabmap::util3d::transformPoint | ( | const pcl::PointNormal & | point, |
const Transform & | transform | ||
) |
Definition at line 251 of file util3d_transforms.cpp.
pcl::PointXYZ rtabmap::util3d::transformPoint | ( | const pcl::PointXYZ & | pt, |
const Transform & | transform | ||
) |
Definition at line 231 of file util3d_transforms.cpp.
pcl::PointXYZI rtabmap::util3d::transformPoint | ( | const pcl::PointXYZI & | pt, |
const Transform & | transform | ||
) |
Definition at line 237 of file util3d_transforms.cpp.
pcl::PointXYZINormal rtabmap::util3d::transformPoint | ( | const pcl::PointXYZINormal & | point, |
const Transform & | transform | ||
) |
Definition at line 287 of file util3d_transforms.cpp.
pcl::PointXYZRGB rtabmap::util3d::transformPoint | ( | const pcl::PointXYZRGB & | pt, |
const Transform & | transform | ||
) |
Definition at line 243 of file util3d_transforms.cpp.
pcl::PointXYZRGBNormal rtabmap::util3d::transformPoint | ( | const pcl::PointXYZRGBNormal & | point, |
const Transform & | transform | ||
) |
Definition at line 268 of file util3d_transforms.cpp.
pcl::PointCloud< pcl::PointNormal >::Ptr rtabmap::util3d::transformPointCloud | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Transform & | transform | ||
) |
Definition at line 183 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 131 of file util3d_transforms.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::transformPointCloud | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Transform & | transform | ||
) |
Definition at line 156 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 107 of file util3d_transforms.cpp.
pcl::PointCloud< pcl::PointXYZI >::Ptr rtabmap::util3d::transformPointCloud | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Transform & | transform | ||
) |
Definition at line 165 of file util3d_transforms.cpp.
pcl::PointCloud< pcl::PointXYZI >::Ptr rtabmap::util3d::transformPointCloud | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
const Transform & | transform | ||
) |
Definition at line 115 of file util3d_transforms.cpp.
pcl::PointCloud< pcl::PointXYZINormal >::Ptr rtabmap::util3d::transformPointCloud | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Transform & | transform | ||
) |
Definition at line 201 of file util3d_transforms.cpp.
pcl::PointCloud< pcl::PointXYZINormal >::Ptr rtabmap::util3d::transformPointCloud | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
const Transform & | transform | ||
) |
Definition at line 147 of file util3d_transforms.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::util3d::transformPointCloud | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Transform & | transform | ||
) |
Definition at line 174 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 123 of file util3d_transforms.cpp.
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr rtabmap::util3d::transformPointCloud | ( | const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
const Transform & | transform | ||
) |
Definition at line 192 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 139 of file util3d_transforms.cpp.
|
inline |
Definition at line 141 of file util3d_filtering.h.
|
inline |
Definition at line 147 of file util3d_filtering.h.
|
inline |
Definition at line 153 of file util3d_filtering.h.
pcl::PointCloud< pcl::PointNormal >::Ptr rtabmap::util3d::voxelize | ( | const pcl::PointCloud< pcl::PointNormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | voxelSize | ||
) |
Definition at line 617 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 643 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZ >::Ptr rtabmap::util3d::voxelize | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | voxelSize | ||
) |
Definition at line 613 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 638 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZI >::Ptr rtabmap::util3d::voxelize | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | voxelSize | ||
) |
Definition at line 629 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZI >::Ptr rtabmap::util3d::voxelize | ( | const pcl::PointCloud< pcl::PointXYZI >::Ptr & | cloud, |
float | voxelSize | ||
) |
Definition at line 658 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZINormal >::Ptr rtabmap::util3d::voxelize | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | voxelSize | ||
) |
Definition at line 633 of file util3d_filtering.cpp.
pcl::PointCloud< pcl::PointXYZINormal >::Ptr rtabmap::util3d::voxelize | ( | const pcl::PointCloud< pcl::PointXYZINormal >::Ptr & | cloud, |
float | voxelSize | ||
) |
Definition at line 663 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 621 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 648 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 625 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 653 of file util3d_filtering.cpp.
pcl::PointCloud<PointT>::Ptr rtabmap::util3d::voxelizeImpl | ( | const typename pcl::PointCloud< PointT >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
float | voxelSize, | ||
int | level = 0 |
||
) |
Definition at line 524 of file util3d_filtering.cpp.