GridMapPclLoader.hpp
Go to the documentation of this file.
1 /*
2  * GridMapPclLoader.hpp
3  *
4  * Created on: Aug 26, 2019
5  * Author: Edo Jelavic
6  * Institute: ETH Zurich, Robotic Systems Lab
7  */
8 
9 #pragma once
10 
11 #include <array>
12 #include <memory>
13 #include <string>
14 
16 
19 
20 namespace grid_map {
21 
22 namespace grid_map_pcl_test {
23 class GridMapPclLoaderTest_CalculateElevation_Test;
24 }
25 /*
26  * Computes elevation of a grid map from a raw point cloud.
27  * The algorithm divides the point cloud into cells (in x and y direction)
28  * that are the same size as the grid map cells. Then it looks for clusters
29  * of points in each of those cells and computes their mean. Mean of a cluster
30  * with minimal z value out of all clusters inside a cell is taken to
31  * be the elevation in the grid map. This allows the algorithm to also work
32  * indoors. All the calculations are performed in the point cloud frame.
33  */
34 
36  friend class grid_map_pcl_test::GridMapPclLoaderTest_CalculateElevation_Test;
37 
38  public:
39  using Point = ::pcl::PointXYZ;
40  using Pointcloud = ::pcl::PointCloud<Point>;
41 
42  GridMapPclLoader() = default;
43  ~GridMapPclLoader() = default;
44 
49  void loadCloudFromPcdFile(const std::string& filename);
50 
55  void setInputCloud(Pointcloud::ConstPtr inputCloud);
56 
62  void preProcessInputCloud();
63 
69  void initializeGridMapGeometryFromInputCloud();
70 
75  void addLayerFromInputCloud(const std::string& layer);
76 
81  const grid_map::GridMap& getGridMap() const;
82 
87  void savePointCloudAsPcdFile(const std::string& filename) const;
88 
93  void loadParameters(const std::string& filename);
94 
96  const grid_map_pcl::PclLoaderParameters::Parameters& getParameters() const { return params_.get(); }
97 
99  grid_map::GridMap& getWorkingGridMap() { return workingGridMap_; }
100 
102  const std::vector<std::vector<std::vector<float>>>& getClusterHeightsWithingGridMapCell() const {
103  return clusterHeightsWithingGridMapCell_;
104  }
105 
106  protected:
114  void setWorkingCloud(Pointcloud::ConstPtr workingCloud);
115 
123  void setRawInputCloud(Pointcloud::ConstPtr rawInputCloud);
124 
125  // processing the grid map
126 
132  Pointcloud::Ptr getPointcloudInsideGridMapCellBorder(const grid_map::Index& index) const;
133 
143  void processGridMapCell(const unsigned int linearGridMapIndex, grid_map::Matrix* gridMapData);
144 
153  void calculateElevationFromPointsInsideGridMapCell(Pointcloud::ConstPtr cloud, std::vector<float>& heights) const;
154 
160  void preprocessGridMapCells();
161 
166  void allocateSpaceForCloudsInsideCells();
167 
177  void dispatchWorkingCloudToGridMapCells();
178 
179  // Matrix of point clouds. Each point cloud has only points that fall within a grid map cell.
180  std::vector<std::vector<Pointcloud::Ptr>> pointcloudWithinGridMapCell_;
181 
182  // Matrix of cluster-height-vectors. Dimensions: x, y, cluster_index.
183  std::vector<std::vector<std::vector<float>>> clusterHeightsWithingGridMapCell_;
184 
185  // Point cloud that pcl filters have been applied to (it can change).
186  Pointcloud::Ptr workingCloud_;
187 
188  // Copy of the raw point cloud. This cloud will not be changed by pcl filters.
189  Pointcloud::Ptr rawInputCloud_;
190 
191  // Grid map computed from working point cloud.
193 
194  // Parameters for the algorithm. Also includes parameters for the pcl filters.
196 
197  // Class that handles point cloud processing
199 };
200 
201 } // namespace grid_map
Eigen::Array2i Index
Eigen::MatrixXf Matrix
std::vector< std::vector< Pointcloud::Ptr > > pointcloudWithinGridMapCell_
grid_map::GridMap workingGridMap_
::pcl::PointCloud< Point > Pointcloud
grid_map::GridMap & getWorkingGridMap()
grid_map_pcl::PointcloudProcessor pointcloudProcessor_
const std::vector< std::vector< std::vector< float > > > & getClusterHeightsWithingGridMapCell() const
const grid_map_pcl::PclLoaderParameters::Parameters & getParameters() const
std::vector< std::vector< std::vector< float > > > clusterHeightsWithingGridMapCell_
grid_map_pcl::PclLoaderParameters params_


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