Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
grid_map::GridMapPclLoader Class Reference

#include <GridMapPclLoader.hpp>

Public Types

using Point = ::pcl::PointXYZ
 
using Pointcloud = ::pcl::PointCloud< Point >
 

Public Member Functions

void addLayerFromInputCloud (const std::string &layer)
 
const std::vector< std::vector< std::vector< float > > > & getClusterHeightsWithingGridMapCell () const
 
const grid_map::GridMapgetGridMap () const
 
const grid_map_pcl::PclLoaderParameters::ParametersgetParameters () const
 
grid_map::GridMapgetWorkingGridMap ()
 
 GridMapPclLoader ()=default
 
void initializeGridMapGeometryFromInputCloud ()
 
void loadCloudFromPcdFile (const std::string &filename)
 
void loadParameters (const std::string &filename)
 
void preProcessInputCloud ()
 
void savePointCloudAsPcdFile (const std::string &filename) const
 
void setInputCloud (Pointcloud::ConstPtr inputCloud)
 
 ~GridMapPclLoader ()=default
 

Protected Member Functions

void allocateSpaceForCloudsInsideCells ()
 
void calculateElevationFromPointsInsideGridMapCell (Pointcloud::ConstPtr cloud, std::vector< float > &heights) const
 
void dispatchWorkingCloudToGridMapCells ()
 
Pointcloud::Ptr getPointcloudInsideGridMapCellBorder (const grid_map::Index &index) const
 
void preprocessGridMapCells ()
 
void processGridMapCell (const unsigned int linearGridMapIndex, grid_map::Matrix *gridMapData)
 
void setRawInputCloud (Pointcloud::ConstPtr rawInputCloud)
 
void setWorkingCloud (Pointcloud::ConstPtr workingCloud)
 

Protected Attributes

std::vector< std::vector< std::vector< float > > > clusterHeightsWithingGridMapCell_
 
grid_map_pcl::PclLoaderParameters params_
 
grid_map_pcl::PointcloudProcessor pointcloudProcessor_
 
std::vector< std::vector< Pointcloud::Ptr > > pointcloudWithinGridMapCell_
 
Pointcloud::Ptr rawInputCloud_
 
Pointcloud::Ptr workingCloud_
 
grid_map::GridMap workingGridMap_
 

Friends

class grid_map_pcl_test::GridMapPclLoaderTest_CalculateElevation_Test
 

Detailed Description

Definition at line 35 of file GridMapPclLoader.hpp.

Member Typedef Documentation

using grid_map::GridMapPclLoader::Point = ::pcl::PointXYZ

Definition at line 39 of file GridMapPclLoader.hpp.

Definition at line 40 of file GridMapPclLoader.hpp.

Constructor & Destructor Documentation

grid_map::GridMapPclLoader::GridMapPclLoader ( )
default
grid_map::GridMapPclLoader::~GridMapPclLoader ( )
default

Member Function Documentation

void grid_map::GridMapPclLoader::addLayerFromInputCloud ( const std::string &  layer)

Adds a layer in the grid map. The algorithm is described above.

Parameters
[in]Layername that will be added

Definition at line 99 of file GridMapPclLoader.cpp.

void grid_map::GridMapPclLoader::allocateSpaceForCloudsInsideCells ( )
protected

Allocates space for the point clouds. These point clouds are then filled by dispatchWorkingCloudToGridMapCells function.

Definition at line 177 of file GridMapPclLoader.cpp.

void grid_map::GridMapPclLoader::calculateElevationFromPointsInsideGridMapCell ( Pointcloud::ConstPtr  cloud,
std::vector< float > &  heights 
) const
protected

Given a point cloud it computes the elevation from it. The algorithm is suited for 2.5 D maps. Function finds all the clusters and for each of them it computes a mean of point positions. Then it looks at z value of the means and takes the lowest one.

Parameters
[in]pointcloud that is entirely contained inside a grid map cell
Returns
elevation value computed from the input point cloud. It will return NaN if no clusters have been found or an empty cloud is passed in.

Definition at line 142 of file GridMapPclLoader.cpp.

void grid_map::GridMapPclLoader::dispatchWorkingCloudToGridMapCells ( )
protected

Makes a matrix of empty point clouds where each cell in the matrix corresponds to a cell in the grid map. The functions iterates over the working point cloud, checks for each point which cell in the grid map it falls within and then adds that point to the correct point cloud in the matrix of point clouds. The decision which cell in the matrix point cloud a point belongs to or not is made by looking at the xy coordinates of the point in the input point cloud and x-y borders of the cell in the grid map.

Definition at line 196 of file GridMapPclLoader.cpp.

const std::vector<std::vector<std::vector<float> > >& grid_map::GridMapPclLoader::getClusterHeightsWithingGridMapCell ( ) const
inline
Returns
A const reference to the internal multiple heights representation.

Definition at line 102 of file GridMapPclLoader.hpp.

const grid_map::GridMap & grid_map::GridMapPclLoader::getGridMap ( ) const

Get a const reference to a grid map

Parameters
[out]gridmap

Definition at line 25 of file GridMapPclLoader.cpp.

const grid_map_pcl::PclLoaderParameters::Parameters& grid_map::GridMapPclLoader::getParameters ( ) const
inline
Returns
the parameters.

Definition at line 96 of file GridMapPclLoader.hpp.

GridMapPclLoader::Pointcloud::Ptr grid_map::GridMapPclLoader::getPointcloudInsideGridMapCellBorder ( const grid_map::Index index) const
protected
Parameters
[in]indexof a cell in the grid map
Returns
Point cloud made from points in the working point cloud that fall within the requested cell in the grid map.

Definition at line 159 of file GridMapPclLoader.cpp.

grid_map::GridMap& grid_map::GridMapPclLoader::getWorkingGridMap ( )
inline
Returns
A reference to the internal gridMap.

Definition at line 99 of file GridMapPclLoader.hpp.

void grid_map::GridMapPclLoader::initializeGridMapGeometryFromInputCloud ( )

Initializes the geometry of a grid map from an input cloud. This will set the center of the map and the dimensions in x and y direction. This method will clear any layers that the working grid map might have had.

Definition at line 73 of file GridMapPclLoader.cpp.

void grid_map::GridMapPclLoader::loadCloudFromPcdFile ( const std::string &  filename)

Loads the point cloud into memory

Parameters
[in]fullpathto the point cloud.

Definition at line 29 of file GridMapPclLoader.cpp.

void grid_map::GridMapPclLoader::loadParameters ( const std::string &  filename)

Load algorithm's parameters.

Parameters
[in]fullpath to the config file with parameters

Definition at line 163 of file GridMapPclLoader.cpp.

void grid_map::GridMapPclLoader::preprocessGridMapCells ( )
protected

Allocates space for the point clouds and dispatches points to the right location in the point cloud matrix. The function merely calls allocateSpaceForCloudsInsideCells and dispatchWorkingCloudToGridMapCells.

Definition at line 172 of file GridMapPclLoader.cpp.

void grid_map::GridMapPclLoader::preProcessInputCloud ( )

Preprocessing of the input cloud. It removes the outliers, downsamples the cloud and applies a rigid body transform. Parameters are specified in the config file.

Definition at line 54 of file GridMapPclLoader.cpp.

void grid_map::GridMapPclLoader::processGridMapCell ( const unsigned int  linearGridMapIndex,
grid_map::Matrix gridMapData 
)
protected

Calculates the elevation at the linear index. The algorithm is applied for each cell after the pre-processing has been done. This function is designed such that it can be called in a parallel for loop. There are no race conditions since each thread processed different set of grid map cells.

Parameters
[in]linearindex of a grid map cell currently being processed
[out]matrixof elevation values which need to be computed

Definition at line 120 of file GridMapPclLoader.cpp.

void grid_map::GridMapPclLoader::savePointCloudAsPcdFile ( const std::string &  filename) const

Saves a point cloud to a pcd file.

Parameters
[in]fullpath to the output cloud

Definition at line 168 of file GridMapPclLoader.cpp.

void grid_map::GridMapPclLoader::setInputCloud ( Pointcloud::ConstPtr  inputCloud)

Allows the user to set the input cloud

Parameters
[in]pointerto the input point cloud.

Definition at line 35 of file GridMapPclLoader.cpp.

void grid_map::GridMapPclLoader::setRawInputCloud ( Pointcloud::ConstPtr  rawInputCloud)
protected

Copies the input cloud in to the memory. This cloud will not change. Should you need to do any other operations where you want to have the access to the raw point cloud (before applying filters) you can use use the corresponding variable in the class.

Parameters
[in]pointerto the pcl point cloud

Definition at line 40 of file GridMapPclLoader.cpp.

void grid_map::GridMapPclLoader::setWorkingCloud ( Pointcloud::ConstPtr  workingCloud)
protected

Copies the input cloud into the memory. This cloud is expected to be changed if you run the pcl filters. For example if you run the statistical outlier removal, it will remove some points from the cloud

Parameters
[in]pointerto the pcl point cloud

Definition at line 47 of file GridMapPclLoader.cpp.

Friends And Related Function Documentation

friend class grid_map_pcl_test::GridMapPclLoaderTest_CalculateElevation_Test
friend

Definition at line 36 of file GridMapPclLoader.hpp.

Member Data Documentation

std::vector<std::vector<std::vector<float> > > grid_map::GridMapPclLoader::clusterHeightsWithingGridMapCell_
protected

Definition at line 183 of file GridMapPclLoader.hpp.

grid_map_pcl::PclLoaderParameters grid_map::GridMapPclLoader::params_
protected

Definition at line 195 of file GridMapPclLoader.hpp.

grid_map_pcl::PointcloudProcessor grid_map::GridMapPclLoader::pointcloudProcessor_
protected

Definition at line 198 of file GridMapPclLoader.hpp.

std::vector<std::vector<Pointcloud::Ptr> > grid_map::GridMapPclLoader::pointcloudWithinGridMapCell_
protected

Definition at line 180 of file GridMapPclLoader.hpp.

Pointcloud::Ptr grid_map::GridMapPclLoader::rawInputCloud_
protected

Definition at line 189 of file GridMapPclLoader.hpp.

Pointcloud::Ptr grid_map::GridMapPclLoader::workingCloud_
protected

Definition at line 186 of file GridMapPclLoader.hpp.

grid_map::GridMap grid_map::GridMapPclLoader::workingGridMap_
protected

Definition at line 192 of file GridMapPclLoader.hpp.


The documentation for this class was generated from the following files:


grid_map_pcl
Author(s): Dominic Jud , Edo Jelavic
autogenerated on Tue Jun 1 2021 02:13:43