SignedDistanceField.cpp
Go to the documentation of this file.
1 /*
2  * SignedDistanceField.hpp
3  *
4  * Created on: Aug 16, 2017
5  * Authors: Takahiro Miki, Peter Fankhauser
6  * Institute: ETH Zurich, ANYbotics
7  */
8 
11 
13 
14 #include <limits>
15 
16 using namespace distance_transform;
17 
18 namespace grid_map {
19 
20 SignedDistanceField::SignedDistanceField()
21  : maxDistance_(std::numeric_limits<float>::max()),
22  zIndexStartHeight_(0.0),
23  resolution_(0.0),
24  lowestHeight_(-1e5) // We need some precision.
25 {
26 }
27 
29 {
30 }
31 
32 void SignedDistanceField::calculateSignedDistanceField(const GridMap& gridMap, const std::string& layer,
33  const double heightClearance)
34 {
35  data_.clear();
36  resolution_ = gridMap.getResolution();
37  position_ = gridMap.getPosition();
38  size_ = gridMap.getSize();
39  Matrix map = gridMap.get(layer); // Copy!
40 
41  float minHeight = map.minCoeffOfFinites();
42  if (!std::isfinite(minHeight)) minHeight = lowestHeight_;
43  float maxHeight = map.maxCoeffOfFinites();
44  if (!std::isfinite(maxHeight)) maxHeight = lowestHeight_;
45 
46  const float valueForEmptyCells = lowestHeight_; // maxHeight, minHeight (TODO Make this an option).
47  for (size_t i = 0; i < map.size(); ++i) {
48  if (std::isnan(map(i))) map(i) = valueForEmptyCells;
49  }
50 
51  // Height range of the signed distance field is higher than the max height.
52  maxHeight += heightClearance;
53 
54  Matrix sdfElevationAbove = Matrix::Ones(map.rows(), map.cols()) * maxDistance_;
55  Matrix sdfLayer = Matrix::Zero(map.rows(), map.cols());
56  std::vector<Matrix> sdf;
57  zIndexStartHeight_ = minHeight;
58 
59  // Calculate signed distance field from bottom.
60  for (float h = minHeight; h < maxHeight; h += resolution_) {
61  Eigen::Matrix<bool, Eigen::Dynamic, Eigen::Dynamic> obstacleFreeField = map.array() < h;
62  Eigen::Matrix<bool, Eigen::Dynamic, Eigen::Dynamic> obstacleField = obstacleFreeField.array() < 1;
63  Matrix sdfObstacle = getPlanarSignedDistanceField(obstacleField);
64  Matrix sdfObstacleFree = getPlanarSignedDistanceField(obstacleFreeField);
65  Matrix sdf2d;
66  // If 2d sdfObstacleFree calculation failed, neglect this SDF
67  // to avoid extreme small distances (-INF).
68  if ((sdfObstacleFree.array() >= INF).any()) sdf2d = sdfObstacle;
69  else sdf2d = sdfObstacle - sdfObstacleFree;
70  sdf2d *= resolution_;
71  for (size_t i = 0; i < sdfElevationAbove.size(); ++i) {
72  if(sdfElevationAbove(i) == maxDistance_ && map(i) <= h) sdfElevationAbove(i) = h - map(i);
73  else if(sdfElevationAbove(i) != maxDistance_ && map(i) <= h) sdfElevationAbove(i) = sdfLayer(i) + resolution_;
74  if (sdf2d(i) == 0) sdfLayer(i) = h - map(i);
75  else if (sdf2d(i) < 0) sdfLayer(i) = -std::min(fabs(sdf2d(i)), fabs(map(i) - h));
76  else sdfLayer(i) = std::min(sdf2d(i), sdfElevationAbove(i));
77  }
78  data_.push_back(sdfLayer);
79  }
80 }
81 
82 grid_map::Matrix SignedDistanceField::getPlanarSignedDistanceField(Eigen::Matrix<bool, Eigen::Dynamic, Eigen::Dynamic>& data) const
83 {
84  image<uchar> *input = new image<uchar>(data.rows(), data.cols(), true);
85 
86  for (int y = 0; y < input->height(); y++) {
87  for (int x = 0; x < input->width(); x++) {
88  imRef(input, x, y) = data(x, y);
89  }
90  }
91 
92  // Compute dt.
93  image<float> *out = dt(input);
94 
95  Matrix result(data.rows(), data.cols());
96 
97  // Take square roots.
98  for (int y = 0; y < out->height(); y++) {
99  for (int x = 0; x < out->width(); x++) {
100  result(x, y) = sqrt(imRef(out, x, y));
101  }
102  }
103  return result;
104 }
105 
106 double SignedDistanceField::getDistanceAt(const Position3& position) const
107 {
108  double xCenter = size_.x() / 2.0;
109  double yCenter = size_.y() / 2.0;
110  int i = std::round(xCenter - (position.x() - position_.x()) / resolution_);
111  int j = std::round(yCenter - (position.y() - position_.y()) / resolution_);
112  int k = std::round((position.z() - zIndexStartHeight_) / resolution_);
113  i = std::max(i, 0);
114  i = std::min(i, size_.x() - 1);
115  j = std::max(j, 0);
116  j = std::min(j, size_.y() - 1);
117  k = std::max(k, 0);
118  k = std::min(k, (int)data_.size() - 1);
119  return data_[k](i, j);
120 }
121 
123 {
124  double xCenter = size_.x() / 2.0;
125  double yCenter = size_.y() / 2.0;
126  int i = std::round(xCenter - (position.x() - position_.x()) / resolution_);
127  int j = std::round(yCenter - (position.y() - position_.y()) / resolution_);
128  int k = std::round((position.z() - zIndexStartHeight_) / resolution_);
129  i = std::max(i, 0);
130  i = std::min(i, size_.x() - 1);
131  j = std::max(j, 0);
132  j = std::min(j, size_.y() - 1);
133  k = std::max(k, 0);
134  k = std::min(k, (int)data_.size() - 1);
135  Vector3 gradient = getDistanceGradientAt(position);
136  double xp = position_.x() + ((size_.x() - i) - xCenter) * resolution_;
137  double yp = position_.y() + ((size_.y() - j) - yCenter) * resolution_;
138  double zp = zIndexStartHeight_ + k * resolution_;
139  Vector3 error = position - Vector3(xp, yp, zp);
140  return data_[k](i, j) + gradient.dot(error);
141 }
142 
144 {
145  double xCenter = size_.x() / 2.0;
146  double yCenter = size_.y() / 2.0;
147  int i = std::round(xCenter - (position.x() - position_.x()) / resolution_);
148  int j = std::round(yCenter - (position.y() - position_.y()) / resolution_);
149  int k = std::round((position.z() - zIndexStartHeight_) / resolution_);
150  i = std::max(i, 1);
151  i = std::min(i, size_.x() - 2);
152  j = std::max(j, 1);
153  j = std::min(j, size_.y() - 2);
154  k = std::max(k, 1);
155  k = std::min(k, (int)data_.size() - 2);
156  double dx = (data_[k](i - 1, j) - data_[k](i + 1, j)) / (2 * resolution_);
157  double dy = (data_[k](i, j - 1) - data_[k](i, j + 1)) / (2 * resolution_);
158  double dz = (data_[k + 1](i, j) - data_[k - 1](i, j)) / (2 * resolution_);
159  return Vector3(dx, dy, dz);
160 }
161 
162 void SignedDistanceField::convertToPointCloud(pcl::PointCloud<pcl::PointXYZI>& points) const
163 {
164  double xCenter = size_.x() / 2.0;
165  double yCenter = size_.y() / 2.0;
166  for (int z = 0; z < data_.size(); z++){
167  for (int y = 0; y < size_.y(); y++) {
168  for (int x = 0; x < size_.x(); x++) {
169  double xp = position_.x() + ((size_.x() - x) - xCenter) * resolution_;
170  double yp = position_.y() + ((size_.y() - y) - yCenter) * resolution_;
171  double zp = zIndexStartHeight_ + z * resolution_;
172  pcl::PointXYZI p;
173  p.x = xp;
174  p.y = yp;
175  p.z = zp;
176  p.intensity = data_[z](x, y);
177  points.push_back(p);
178  }
179  }
180  }
181  return;
182 }
183 
184 } /* namespace */
bool getPosition(const Index &index, Position &position) const
int width() const
Definition: image.h:44
Eigen::MatrixXf Matrix
TFSIMD_FORCE_INLINE const tfScalar & y() const
static float * dt(float *f, int n)
Definition: dt.h:33
Eigen::Vector3d Position3
#define imRef(im, x, y)
Definition: image.h:60
double getResolution() const
int height() const
Definition: image.h:47
const Matrix & get(const std::string &layer) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
void convertToPointCloud(pcl::PointCloud< pcl::PointXYZI > &points) const
TFSIMD_FORCE_INLINE const tfScalar & z() const
double getInterpolatedDistanceAt(const Position3 &position) const
void calculateSignedDistanceField(const GridMap &gridMap, const std::string &layer, const double heightClearance)
Vector3 getDistanceGradientAt(const Position3 &position) const
const double INF
Definition: dt.h:30
Matrix getPlanarSignedDistanceField(Eigen::Matrix< bool, Eigen::Dynamic, Eigen::Dynamic > &data) const
Eigen::Vector3d Vector3
double getDistanceAt(const Position3 &position) const
const Size & getSize() const


grid_map_sdf
Author(s): Takahiro Miki , Péter Fankhauser
autogenerated on Tue Jun 25 2019 20:02:30