#include <rtabmap/core/util3d_filtering.h>
#include <rtabmap/core/util3d.h>
#include <pcl/common/common.h>
#include <pcl/common/centroid.h>
#include <pcl/common/io.h>
Go to the source code of this file.
Namespaces | |
namespace | rtabmap |
namespace | rtabmap::util3d |
Functions | |
template<typename PointT > | |
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) |
template<typename PointT > | |
void | rtabmap::util3d::occupancy2DFromCloud3D (const typename pcl::PointCloud< PointT >::Ptr &cloud, cv::Mat &ground, cv::Mat &obstacles, float cellSize, float groundNormalAngle, int minClusterSize, bool segmentFlatObstacles, float maxGroundHeight) |
template<typename PointT > | |
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) |
template<typename PointT > | |
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) |
template<typename PointT > | |
pcl::PointCloud< PointT >::Ptr | rtabmap::util3d::projectCloudOnXYPlane (const typename pcl::PointCloud< PointT > &cloud) |
template<typename PointT > | |
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) |
template<typename PointT > | |
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) |