GridMapPclLoader.cpp
Go to the documentation of this file.
1 /*
2  * GridMapPclLoader.cpp
3  *
4  * Created on: Aug 26, 2019
5  * Author: Edo Jelavic
6  * Institute: ETH Zurich, Robotic Systems Lab
7  */
8 
9 #include <chrono>
10 
11 #ifdef GRID_MAP_PCL_OPENMP_FOUND
12 #include <omp.h>
13 #endif
14 
15 #include <pcl/common/io.h>
16 #include <ros/console.h>
17 
19 
21 #include "grid_map_pcl/helpers.hpp"
22 
23 namespace grid_map {
24 
26  return workingGridMap_;
27 }
28 
29 void GridMapPclLoader::loadCloudFromPcdFile(const std::string& filename) {
30  Pointcloud::Ptr inputCloud(new pcl::PointCloud<pcl::PointXYZ>);
31  inputCloud = grid_map_pcl::loadPointcloudFromPcd(filename);
32  setInputCloud(inputCloud);
33 }
34 
35 void GridMapPclLoader::setInputCloud(Pointcloud::ConstPtr inputCloud) {
36  setRawInputCloud(inputCloud);
37  setWorkingCloud(inputCloud);
38 }
39 
40 void GridMapPclLoader::setRawInputCloud(Pointcloud::ConstPtr rawInputCloud) {
41  rawInputCloud_.reset();
42  Pointcloud::Ptr temp(new Pointcloud());
43  pcl::copyPointCloud(*rawInputCloud, *temp);
44  rawInputCloud_ = temp;
45 }
46 
47 void GridMapPclLoader::setWorkingCloud(Pointcloud::ConstPtr workingCloud) {
48  workingCloud_.reset();
49  Pointcloud::Ptr temp(new Pointcloud());
50  pcl::copyPointCloud(*workingCloud, *temp);
51  workingCloud_ = temp;
52 }
53 
55  // Preprocess: Remove outliers, downsample cloud, transform cloud
56  ROS_INFO_STREAM("Preprocessing of the pointcloud started");
57 
60  setWorkingCloud(filteredCloud);
61  }
62 
65  setWorkingCloud(downsampledCloud);
66  }
67 
69  setWorkingCloud(transformedCloud);
70  ROS_INFO_STREAM("Preprocessing and filtering finished");
71 }
72 
75  const double resolution = params_.get().gridMap_.resolution_;
76  if (resolution < 1e-4) {
77  throw std::runtime_error("Desired grid map resolution is zero");
78  }
79 
80  // find point cloud dimensions
81  // min and max coordinate in x,y and z direction
82  pcl::PointXYZ minBound;
83  pcl::PointXYZ maxBound;
84  pcl::getMinMax3D(*workingCloud_, minBound, maxBound);
85 
86  // from min and max points we can compute the length
87  grid_map::Length length = grid_map::Length(maxBound.x - minBound.x, maxBound.y - minBound.y);
88 
89  // we put the center of the grid map to be in the middle of the point cloud
90  grid_map::Position position = grid_map::Position((maxBound.x + minBound.x) / 2.0, (maxBound.y + minBound.y) / 2.0);
91  workingGridMap_.setGeometry(length, resolution, position);
92 
93  ROS_INFO_STREAM("Grid map dimensions: " << workingGridMap_.getLength()(0) << " x " << workingGridMap_.getLength()(1));
94  ROS_INFO_STREAM("Grid map resolution: " << workingGridMap_.getResolution());
95  ROS_INFO_STREAM("Grid map num cells: " << workingGridMap_.getSize()(0) << " x " << workingGridMap_.getSize()(1));
96  ROS_INFO_STREAM("Initialized map geometry");
97 }
98 
99 void GridMapPclLoader::addLayerFromInputCloud(const std::string& layer) {
100  ROS_INFO_STREAM("Started adding layer: " << layer);
101  // Preprocess: allocate memory in the internal data structure
103  workingGridMap_.add(layer);
104  grid_map::Matrix& gridMapData = workingGridMap_.get(layer);
105  unsigned int linearGridMapSize = workingGridMap_.getSize().prod();
106 
107 #ifndef GRID_MAP_PCL_OPENMP_FOUND
108  ROS_WARN_STREAM("OpemMP not found, defaulting to single threaded implementation");
109 #else
110  omp_set_num_threads(params_.get().numThreads_);
111 #pragma omp parallel for schedule(dynamic, 10)
112 #endif
113  // Iterate through grid map and calculate the corresponding height based on the point cloud
114  for (unsigned int linearIndex = 0; linearIndex < linearGridMapSize; ++linearIndex) {
115  processGridMapCell(linearIndex, &gridMapData);
116  }
117  ROS_INFO_STREAM("Finished adding layer: " << layer);
118 }
119 
120 void GridMapPclLoader::processGridMapCell(const unsigned int linearGridMapIndex, grid_map::Matrix* gridMapData) {
121  // Get grid map index from linear index and check if enough points lie within the cell
122  const grid_map::Index index(grid_map::getIndexFromLinearIndex(linearGridMapIndex, workingGridMap_.getSize()));
123 
124  Pointcloud::Ptr pointsInsideCellBorder(new Pointcloud());
125  pointsInsideCellBorder = getPointcloudInsideGridMapCellBorder(index);
126  const bool isTooFewPointsInCell = pointsInsideCellBorder->size() < params_.get().gridMap_.minCloudPointsPerCell_;
127  if (isTooFewPointsInCell) {
128  ROS_WARN_STREAM_THROTTLE(10.0, "Less than " << params_.get().gridMap_.minCloudPointsPerCell_ << " points in a cell");
129  return;
130  }
131  auto& clusterHeights = clusterHeightsWithingGridMapCell_[index(0)][index(1)];
132  calculateElevationFromPointsInsideGridMapCell(pointsInsideCellBorder, clusterHeights);
133  if (clusterHeights.empty()) {
134  (*gridMapData)(index(0), index(1)) = std::nan("1");
135  } else {
136  (*gridMapData)(index(0), index(1)) = params_.get().clusterExtraction_.useMaxHeightAsCellElevation_
137  ? *(std::max_element(clusterHeights.begin(), clusterHeights.end()))
138  : *(std::min_element(clusterHeights.begin(), clusterHeights.end()));
139  }
140 }
141 
142 void GridMapPclLoader::calculateElevationFromPointsInsideGridMapCell(Pointcloud::ConstPtr cloud, std::vector<float>& heights) const {
143  heights.clear();
144  // Extract point cloud cluster from point cloud and return if none is found.
145  std::vector<Pointcloud::Ptr> clusterClouds = pointcloudProcessor_.extractClusterCloudsFromPointcloud(cloud);
146  const bool isNoClustersFound = clusterClouds.empty();
147  if (isNoClustersFound) {
148  ROS_WARN_STREAM_THROTTLE(10.0, "No clusters found in the grid map cell");
149  return;
150  }
151 
152  // Extract mean z value of cluster vector and return smallest height value
153  heights.reserve(clusterClouds.size());
154 
155  std::transform(clusterClouds.begin(), clusterClouds.end(), std::back_inserter(heights),
156  [this](Pointcloud::ConstPtr cloud) -> double { return grid_map_pcl::calculateMeanOfPointPositions(cloud).z(); });
157 }
158 
159 GridMapPclLoader::Pointcloud::Ptr GridMapPclLoader::getPointcloudInsideGridMapCellBorder(const grid_map::Index& index) const {
160  return pointcloudWithinGridMapCell_[index.x()][index.y()];
161 }
162 
163 void GridMapPclLoader::loadParameters(const std::string& filename) {
164  params_.loadParameters(filename);
166 }
167 
168 void GridMapPclLoader::savePointCloudAsPcdFile(const std::string& filename) const {
170 }
171 
175 }
176 
178  const unsigned int dimX = workingGridMap_.getSize().x() + 1;
179  const unsigned int dimY = workingGridMap_.getSize().y() + 1;
180 
181  // resize vectors
182  pointcloudWithinGridMapCell_.resize(dimX);
184 
185  // allocate pointClouds
186  for (unsigned int i = 0; i < dimX; ++i) {
187  pointcloudWithinGridMapCell_[i].resize(dimY);
188  clusterHeightsWithingGridMapCell_[i].resize(dimY);
189  for (unsigned int j = 0; j < dimY; ++j) {
190  pointcloudWithinGridMapCell_[i][j].reset(new Pointcloud());
191  clusterHeightsWithingGridMapCell_[i][j].clear();
192  }
193  }
194 }
195 
197  // For each point in input point cloud, find which grid map
198  // cell does it belong to. Then copy that point in the
199  // right cell in the matrix of point clouds data structure.
200  // This allows for faster access in the clustering stage.
201  for (unsigned int i = 0; i < workingCloud_->points.size(); ++i) {
202  const Point& point = workingCloud_->points[i];
203  const double x = point.x;
204  const double y = point.y;
205  grid_map::Index index;
207  pointcloudWithinGridMapCell_[index.x()][index.y()]->push_back(point);
208  }
209 }
210 } // namespace grid_map
const Length & getLength() const
std::vector< Pointcloud::Ptr > extractClusterCloudsFromPointcloud(Pointcloud::ConstPtr inputCloud) const
void loadParameters(const std::string &filename)
Eigen::Array2i Index
void setGeometry(const Length &length, const double resolution, const Position &position=Position::Zero())
bool loadParameters(const std::string &filename)
void processGridMapCell(const unsigned int linearGridMapIndex, grid_map::Matrix *gridMapData)
Pointcloud::Ptr applyRigidBodyTransformation(Pointcloud::ConstPtr inputCloud) const
Pointcloud::Ptr getPointcloudInsideGridMapCellBorder(const grid_map::Index &index) const
void calculateElevationFromPointsInsideGridMapCell(Pointcloud::ConstPtr cloud, std::vector< float > &heights) const
void setWorkingCloud(Pointcloud::ConstPtr workingCloud)
Eigen::MatrixXf Matrix
void setRawInputCloud(Pointcloud::ConstPtr rawInputCloud)
std::vector< std::vector< Pointcloud::Ptr > > pointcloudWithinGridMapCell_
Eigen::Vector3d calculateMeanOfPointPositions(Pointcloud::ConstPtr inputCloud)
Definition: helpers.cpp:138
Pointcloud::Ptr downsampleInputCloud(Pointcloud::ConstPtr inputCloud) const
TFSIMD_FORCE_INLINE const tfScalar & y() const
void loadCloudFromPcdFile(const std::string &filename)
void loadParameters(const std::string &filename)
grid_map::GridMap workingGridMap_
double getResolution() const
Eigen::Vector2d Position
::pcl::PointCloud< Point > Pointcloud
void addLayerFromInputCloud(const std::string &layer)
const Matrix & get(const std::string &layer) const
void setInputCloud(Pointcloud::ConstPtr inputCloud)
grid_map_pcl::PointcloudProcessor pointcloudProcessor_
TFSIMD_FORCE_INLINE const tfScalar & x() const
Pointcloud::Ptr loadPointcloudFromPcd(const std::string &filename)
Definition: helpers.cpp:148
Index getIndexFromLinearIndex(const size_t linearIndex, const Size &bufferSize, const bool rowMajor=false)
#define ROS_WARN_STREAM(args)
static void savePointCloudAsPcdFile(const std::string &filename, const Pointcloud &cloud)
#define ROS_WARN_STREAM_THROTTLE(rate, args)
void savePointCloudAsPcdFile(const std::string &filename) const
void add(const std::string &layer, const double value=NAN)
std::vector< std::vector< std::vector< float > > > clusterHeightsWithingGridMapCell_
#define ROS_INFO_STREAM(args)
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
Pointcloud::Ptr removeOutliersFromInputCloud(Pointcloud::ConstPtr inputCloud) const
bool getIndex(const Position &position, Index &index) const
const grid_map::GridMap & getGridMap() const
Eigen::Array2d Length
const Size & getSize() const
grid_map_pcl::PclLoaderParameters params_


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