20 SignedDistanceField::SignedDistanceField()
21 : maxDistance_(
std::numeric_limits<float>::max()),
22 zIndexStartHeight_(0.0),
33 const double heightClearance)
41 float minHeight = map.minCoeffOfFinites();
43 float maxHeight = map.maxCoeffOfFinites();
47 for (
size_t i = 0; i < map.size(); ++i) {
48 if (std::isnan(map(i))) map(i) = valueForEmptyCells;
52 maxHeight += heightClearance;
55 Matrix sdfLayer = Matrix::Zero(map.rows(), map.cols());
56 std::vector<Matrix> sdf;
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;
68 if ((sdfObstacleFree.array() >=
INF).any()) sdf2d = sdfObstacle;
69 else sdf2d = sdfObstacle - sdfObstacleFree;
71 for (
size_t i = 0; i < sdfElevationAbove.size(); ++i) {
72 if(sdfElevationAbove(i) ==
maxDistance_ && map(i) <= h) sdfElevationAbove(i) = h - map(i);
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));
78 data_.push_back(sdfLayer);
86 for (
int y = 0;
y < input->
height();
y++) {
87 for (
int x = 0;
x < input->
width();
x++) {
95 Matrix result(data.rows(), data.cols());
99 for (
int x = 0;
x < out->
width();
x++) {
108 double xCenter =
size_.x() / 2.0;
109 double yCenter =
size_.y() / 2.0;
114 i = std::min(i,
size_.x() - 1);
116 j = std::min(j,
size_.y() - 1);
118 k = std::min(k, (
int)
data_.size() - 1);
119 return data_[k](i, j);
124 double xCenter =
size_.x() / 2.0;
125 double yCenter =
size_.y() / 2.0;
130 i = std::min(i,
size_.x() - 1);
132 j = std::min(j,
size_.y() - 1);
134 k = std::min(k, (
int)
data_.size() - 1);
140 return data_[k](i, j) + gradient.dot(error);
145 double xCenter =
size_.x() / 2.0;
146 double yCenter =
size_.y() / 2.0;
151 i = std::min(i,
size_.x() - 2);
153 j = std::min(j,
size_.y() - 2);
155 k = std::min(k, (
int)
data_.size() - 2);
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++) {
bool getPosition(const Index &index, Position &position) const
TFSIMD_FORCE_INLINE const tfScalar & y() const
Eigen::Vector3d Position3
virtual ~SignedDistanceField()
double getResolution() const
std::vector< Matrix > data_
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)
const float lowestHeight_
Vector3 getDistanceGradientAt(const Position3 &position) const
Matrix getPlanarSignedDistanceField(Eigen::Matrix< bool, Eigen::Dynamic, Eigen::Dynamic > &data) const
double getDistanceAt(const Position3 &position) const
const Size & getSize() const