Namespaces | Functions
util3d_mapping.h File Reference
#include "rtabmap/core/RtabmapExp.h"
#include <opencv2/core/core.hpp>
#include <map>
#include <rtabmap/core/Transform.h>
#include <pcl/pcl_base.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include "rtabmap/core/impl/util3d_mapping.hpp"
Include dependency graph for util3d_mapping.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 rtabmap
 
 rtabmap::util3d
 

Functions

cv::Mat RTABMAP_EXP rtabmap::util3d::convertImage8U2Map (const cv::Mat &map8U, bool pgmFormat=false)
 
cv::Mat RTABMAP_EXP rtabmap::util3d::convertMap2Image8U (const cv::Mat &map8S, bool pgmFormat=false)
 
cv::Mat RTABMAP_EXP 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)
 
cv::Mat RTABMAP_EXP rtabmap::util3d::create2DMapFromOccupancyLocalMaps (const std::map< int, Transform > &poses, const std::map< int, std::pair< cv::Mat, cv::Mat > > &occupancy, float cellSize, float &xMin, float &yMin, float minMapSize=0.0f, bool erode=false, float footprintRadius=0.0f)
 
cv::Mat RTABMAP_EXP rtabmap::util3d::erodeMap (const cv::Mat &map)
 
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)
 
void RTABMAP_EXP 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)
 
template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::projectCloudOnXYPlane (const typename pcl::PointCloud< PointT > &cloud)
 
void RTABMAP_EXP rtabmap::util3d::rayTrace (const cv::Point2i &start, const cv::Point2i &end, cv::Mat &grid, bool stopOnObstacle)
 
 rtabmap::util3d::RTABMAP_DEPRECATED (void RTABMAP_EXP occupancy2DFromLaserScan(const cv::Mat &scan, cv::Mat &empty, cv::Mat &occupied, float cellSize, bool unknownSpaceFilled=false, float scanMaxRange=0.0f),"Use interface with \"viewpoint\" parameter to make sure the ray tracing origin is from the sensor and not the base.")
 
 rtabmap::util3d::RTABMAP_DEPRECATED (void RTABMAP_EXP occupancy2DFromLaserScan(const cv::Mat &scan, const cv::Point3f &viewpoint, cv::Mat &empty, cv::Mat &occupied, float cellSize, bool unknownSpaceFilled=false, float scanMaxRange=0.0f),"Use interface with scanHit/scanNoHit parameters: scanNoHit set to null matrix has the same functionality than this method.")
 
 rtabmap::util3d::RTABMAP_DEPRECATED (cv::Mat RTABMAP_EXP create2DMap(const std::map< int, Transform > &poses, const std::map< int, pcl::PointCloud< pcl::PointXYZ >::Ptr > &scans, float cellSize, bool unknownSpaceFilled, float &xMin, float &yMin, float minMapSize=0.0f, float scanMaxRange=0.0f),"Use interface with \"viewpoints\" parameter to make sure the ray tracing origin is from the sensor and not the base.")
 
 rtabmap::util3d::RTABMAP_DEPRECATED (cv::Mat RTABMAP_EXP 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),"Use interface with cv::Mat scans.")
 
template<typename PointT >
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))
 
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)
 


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:37:07