NormalVectorsFilter.cpp
Go to the documentation of this file.
1 /*
2  * NormalVectorsFilter.cpp
3  *
4  * Created on: May 05, 2015
5  * Author: Peter Fankhauser, Martin Wermelinger
6  * Institute: ETH Zurich, ANYbotics
7  */
8 
10 
13 
14 #include <Eigen/Dense>
15 #include <stdexcept>
16 
17 using namespace filters;
18 
19 namespace grid_map {
20 
21 template<typename T>
23  : method_(Method::Raster),
24  estimationRadius_(0.0)
25 {
26 }
27 
28 template<typename T>
30 {
31 }
32 
33 template<typename T>
35 {
36  if (!FilterBase<T>::getParam(std::string("radius"), estimationRadius_)) {
37  ROS_DEBUG("Normal vectors filter did not find parameter `radius`.");
39  } else {
41  if (estimationRadius_ < 0.0) {
42  ROS_ERROR("Normal vectors filter estimation radius must be greater than zero.");
43  return false;
44  }
45  ROS_DEBUG("Normal vectors estimation radius = %f", estimationRadius_);
46  }
47 
48  std::string normalVectorPositiveAxis;
49  if (!FilterBase<T>::getParam(std::string("normal_vector_positive_axis"), normalVectorPositiveAxis)) {
50  ROS_ERROR("Normal vectors filter did not find parameter `normal_vector_positive_axis`.");
51  return false;
52  }
53  if (normalVectorPositiveAxis == "z") {
54  normalVectorPositiveAxis_ = Vector3::UnitZ();
55  } else if (normalVectorPositiveAxis == "y") {
56  normalVectorPositiveAxis_ = Vector3::UnitY();
57  } else if (normalVectorPositiveAxis == "x") {
58  normalVectorPositiveAxis_ = Vector3::UnitX();
59  } else {
60  ROS_ERROR("The normal vector positive axis '%s' is not valid.", normalVectorPositiveAxis.c_str());
61  return false;
62  }
63 
64  if (!FilterBase < T > ::getParam(std::string("input_layer"), inputLayer_)) {
65  ROS_ERROR("Normal vectors filter did not find parameter `input_layer`.");
66  return false;
67  }
68  ROS_DEBUG("Normal vectors filter input layer is = %s.", inputLayer_.c_str());
69 
70  if (!FilterBase < T > ::getParam(std::string("output_layers_prefix"), outputLayersPrefix_)) {
71  ROS_ERROR("Normal vectors filter did not find parameter `output_layers_prefix`.");
72  return false;
73  }
74  ROS_DEBUG("Normal vectors filter output_layer = %s.", outputLayersPrefix_.c_str());
75 
76  return true;
77 }
78 
79 template<typename T>
80 bool NormalVectorsFilter<T>::update(const T& mapIn, T& mapOut)
81 {
82  std::vector<std::string> normalVectorsLayers;
83  normalVectorsLayers.push_back(outputLayersPrefix_ + "x");
84  normalVectorsLayers.push_back(outputLayersPrefix_ + "y");
85  normalVectorsLayers.push_back(outputLayersPrefix_ + "z");
86 
87  mapOut = mapIn;
88  for (const auto& layer : normalVectorsLayers) mapOut.add(layer);
89  switch (method_) {
90  case Method::Area:
92  break;
93  case Method::Raster:
95  break;
96  }
97 
98  return true;
99 }
100 
101 template<typename T>
102 void NormalVectorsFilter<T>::computeWithArea(GridMap& map, const std::string& inputLayer, const std::string& outputLayersPrefix)
103 {
104  // For each cell in requested area.
105  for (GridMapIterator iterator(map);
106  !iterator.isPastEnd(); ++iterator) {
107  // Check if this is an empty cell (hole in the map).
108  if (!map.isValid(*iterator, inputLayer_)) continue;
109 
110  // Requested position (center) of circle in map.
111  Position center;
112  map.getPosition(*iterator, center);
113 
114  // Prepare data computation.
115  const int maxNumberOfCells = pow(ceil(2 * estimationRadius_ / map.getResolution()), 2);
116  Eigen::MatrixXd points(3, maxNumberOfCells);
117 
118  // Gather surrounding data.
119  size_t nPoints = 0;
120  for (CircleIterator iterator(map, center, estimationRadius_); !iterator.isPastEnd(); ++iterator) {
121  if (!map.isValid(*iterator, inputLayer_)) continue;
122  Position3 point;
123  map.getPosition3(inputLayer_, *iterator, point);
124  points.col(nPoints) = point;
125  nPoints++;
126  }
127  points.conservativeResize(3, nPoints); // TODO Eigen version?
128 
129  // Compute Eigenvectors.
130  const Position3 mean = points.leftCols(nPoints).rowwise().sum() / nPoints;
131  const Eigen::MatrixXd NN = points.leftCols(nPoints).colwise() - mean;
132 
133  const Eigen::Matrix3d covarianceMatrix(NN * NN.transpose());
134  Vector3 eigenvalues = Vector3::Ones();
135  Eigen::Matrix3d eigenvectors = Eigen::Matrix3d::Identity();
136  // Ensure that the matrix is suited for eigenvalues calculation.
137  if (covarianceMatrix.fullPivHouseholderQr().rank() >= 3) {
138  const Eigen::EigenSolver<Eigen::MatrixXd> solver(covarianceMatrix);
139  eigenvalues = solver.eigenvalues().real();
140  eigenvectors = solver.eigenvectors().real();
141  } else {
142  ROS_DEBUG("Covariance matrix needed for eigen decomposition is degenerated. Expected cause: no noise in data (nPoints = %i)", (int) nPoints);
143  // Use z-axis as default surface normal. // TODO Make dependend on surfaceNormalPositiveAxis_;
144  eigenvalues.z() = 0.0;
145  }
146  // Keep the smallest Eigenvector as normal vector.
147  int smallestId(0);
148  double smallestValue(std::numeric_limits<double>::max());
149  for (int j = 0; j < eigenvectors.cols(); j++) {
150  if (eigenvalues(j) < smallestValue) {
151  smallestId = j;
152  smallestValue = eigenvalues(j);
153  }
154  }
155  Vector3 eigenvector = eigenvectors.col(smallestId);
156  if (eigenvector.dot(normalVectorPositiveAxis_) < 0.0) eigenvector = -eigenvector;
157  map.at(outputLayersPrefix_ + "x", *iterator) = eigenvector.x();
158  map.at(outputLayersPrefix_ + "y", *iterator) = eigenvector.y();
159  map.at(outputLayersPrefix_ + "z", *iterator) = eigenvector.z();
160  }
161 }
162 
163 template<typename T>
164 void NormalVectorsFilter<T>::computeWithRaster(GridMap& map, const std::string& inputLayer, const std::string& outputLayersPrefix)
165 {
166  throw std::runtime_error("NormalVectorsFilter::computeWithRaster() is not yet implemented!");
167  // TODO: http://www.flipcode.com/archives/Calculating_Vertex_Normals_for_Height_Maps.shtml
168 }
169 
170 } /* namespace */
171 
void computeWithRaster(GridMap &map, const std::string &inputLayer, const std::string &outputLayersPrefix)
std::string outputLayersPrefix_
Output layer name.
bool getPosition(const Index &index, Position &position) const
virtual bool update(const T &mapIn, T &mapOut)
std::string inputLayer_
Input layer name.
bool isValid(const Index &index) const
Eigen::Vector3d Position3
Eigen::Vector3d normalVectorPositiveAxis_
Normal vector positive axis.
double getResolution() const
Eigen::Vector2d Position
float & at(const std::string &layer, const Index &index)
double estimationRadius_
Radius of submap for normal vector estimation.
Eigen::Vector3d Vector3
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_ERROR(...)
bool getPosition3(const std::string &layer, const Index &index, Position3 &position) const
void computeWithArea(GridMap &map, const std::string &inputLayer, const std::string &outputLayersPrefix)
#define ROS_DEBUG(...)


grid_map_filters
Author(s): Péter Fankhauser , Martin Wermelinger
autogenerated on Tue Jun 25 2019 20:02:22