Class GridMapPclLoader

Nested Relationships

Nested Types

Class Documentation

class GridMapPclLoader

Public Types

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

Public Functions

explicit GridMapPclLoader(const rclcpp::Logger &node_logger)

Constructor

Parameters:

node[in] logging interface.

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

Loads the point cloud into memory

Parameters:

fullpath[in] to the point cloud.

void setInputCloud(Pointcloud::ConstPtr inputCloud)

Allows the user to set the input cloud

Parameters:

pointer[in] to the input point cloud.

void 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.

void 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.

void addLayerFromInputCloud(const std::string &layer)

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

Parameters:

Layer[in] name that will be added

const grid_map::GridMap &getGridMap() const

Get a const reference to a grid map

Parameters:

grid[out] map

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

Saves a point cloud to a pcd file.

Parameters:

full[in] path to the output cloud

void loadParameters(const std::string &filename)

Load algorithm’s parameters.

Parameters:

full[in] path to the config file with parameters

Friends

friend class grid_map_pcl_test::GridMapPclLoaderTest_CalculateElevation_Test