Skip to content

Commit 794884f

Browse files
author
Jay Herpin
committed
Backport SignedDistance2d 2D SDF helpers from master
Copies SignedDistance2d.{hpp,cpp}, Utils.hpp, and PixelBorderDistance.hpp verbatim from master, where they were introduced by 91ba880, and adds the new translation unit to grid_map_sdf's add_library list. No behavioral changes to existing code. Pure additions; only external symbol referenced by the new files is grid_map_core/TypeDefs.hpp, already a dep of grid_map_sdf.
1 parent 7ae2472 commit 794884f

5 files changed

Lines changed: 475 additions & 0 deletions

File tree

grid_map_sdf/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@ set(dependencies
3939

4040
## Declare a cpp library
4141
add_library(${PROJECT_NAME}
42+
src/SignedDistance2d.cpp
4243
src/SignedDistanceField.cpp
4344
)
4445

Lines changed: 104 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,104 @@
1+
/*
2+
* PixelBorderDistance.h
3+
*
4+
* Created on: Aug 7, 2020
5+
* Author: Ruben Grandia
6+
* Institute: ETH Zurich
7+
*/
8+
9+
#pragma once
10+
11+
#include <algorithm>
12+
#include <cassert>
13+
#include <cmath>
14+
15+
namespace grid_map {
16+
namespace signed_distance_field {
17+
18+
/**
19+
* Returns distance between the center of a pixel and the border of an other pixel.
20+
* Returns zero if the center is inside the other pixel.
21+
* Pixels are assumed to have size 1.0F
22+
* @param i : location of pixel 1
23+
* @param j : location of pixel 2
24+
* @return : absolute distance between center of pixel 1 and the border of pixel 2
25+
*/
26+
inline float pixelBorderDistance(float i, float j) {
27+
return std::max(std::abs(i - j) - 0.5F, 0.0F);
28+
}
29+
30+
/**
31+
* Returns square pixelBorderDistance, adding offset f.
32+
*/
33+
inline float squarePixelBorderDistance(float i, float j, float f) {
34+
const float d{pixelBorderDistance(i, j)};
35+
return d * d + f;
36+
}
37+
38+
namespace internal {
39+
40+
/**
41+
* Return equidistancepoint between origin and pixel p (with p > 0) with offset fp
42+
*/
43+
inline float intersectionPointRightSideOfOrigin(float p, float fp) {
44+
/*
45+
* There are 5 different solutions
46+
* In decreasing order:
47+
* sol 1 in [p^2, inf]
48+
* sol 2 in [bound, p^2]
49+
* sol 3 in [-bound, bound]
50+
* sol 4 in [-p^2, -bound]
51+
* sol 5 in [-inf, -p^2]
52+
*/
53+
const float pSquared{p * p};
54+
if (fp > pSquared) {
55+
return (pSquared + p + fp) / (2.0F * p); // sol 1
56+
} else if (fp < -pSquared) {
57+
return (pSquared - p + fp) / (2.0F * p); // sol 5
58+
} else {
59+
const float bound{pSquared - 2.0F * p + 1.0F}; // Always positive because (p > 0)
60+
if (fp > bound) {
61+
return 0.5F + std::sqrt(fp); // sol 2
62+
} else if (fp < -bound) {
63+
return p - 0.5F - std::sqrt(-fp); // sol 4
64+
} else {
65+
return (pSquared - p + fp) / (2.0F * p - 2.0F); // sol 3
66+
}
67+
}
68+
}
69+
70+
/**
71+
* Return equidistancepoint between origin and pixel p with offset fp
72+
*/
73+
inline float intersectionOffsetFromOrigin(float p, float fp) {
74+
if (p > 0.0F) {
75+
return intersectionPointRightSideOfOrigin(p, fp);
76+
} else {
77+
// call with negative p and flip the result
78+
return -intersectionPointRightSideOfOrigin(-p, fp);
79+
}
80+
}
81+
82+
} // namespace internal
83+
84+
/**
85+
* Return the point s in pixel space that is equally far from p and q (taking into account offsets fp, and fq)
86+
* It is the solution to the following equation:
87+
* squarePixelBorderDistance(s, q, fq) == squarePixelBorderDistance(s, p, fp)
88+
*/
89+
inline float equidistancePoint(float q, float fq, float p, float fp) {
90+
assert(q == p ||
91+
std::abs(q - p) >= 1.0F); // Check that q and p are proper pixel locations: either the same pixel or non-overlapping pixels
92+
assert((q == p) ? fp == fq : true); // Check when q and p are equal, the offsets are also equal
93+
94+
if (fp == fq) { // quite common case when both pixels are of the same class (occupied / free)
95+
return 0.5F * (p + q);
96+
} else {
97+
float df{fp - fq};
98+
float dr{p - q};
99+
return internal::intersectionOffsetFromOrigin(dr, df) + q;
100+
}
101+
}
102+
103+
} // namespace signed_distance_field
104+
} // namespace grid_map
Lines changed: 59 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,59 @@
1+
/*
2+
* SignedDistance2d.h
3+
*
4+
* Created on: Jul 10, 2020
5+
* Author: Ruben Grandia
6+
* Institute: ETH Zurich
7+
*/
8+
9+
#pragma once
10+
11+
#include <vector>
12+
13+
#include <grid_map_core/TypeDefs.hpp>
14+
15+
#include "Utils.hpp"
16+
17+
namespace grid_map {
18+
namespace signed_distance_field {
19+
20+
/**
21+
* Computes the signed distance field at a specified height for a given elevation map.
22+
*
23+
* @param elevationMap : elevation data.
24+
* @param height : height to generate the signed distance at.
25+
* @param resolution : resolution of the elevation map. (The true distance [m] between cells in world frame)
26+
* @param minHeight : the lowest height contained in elevationMap
27+
* @param maxHeight : the maximum height contained in elevationMap
28+
* @return The signed distance field at the query height.
29+
*/
30+
Matrix signedDistanceAtHeight(const Matrix& elevationMap, float height, float resolution, float minHeight, float maxHeight);
31+
32+
/**
33+
* Same as above, but returns the sdf in transposed form.
34+
* Also takes temporary variables from outside to prevent memory allocation.
35+
*
36+
* @param elevationMap : elevation data.
37+
* @param sdfTranspose : [output] resulting sdf in transposed form (automatically allocated if of wrong size)
38+
* @param tmp : temporary of size elevationMap (automatically allocated if of wrong size)
39+
* @param tmpTranspose : temporary of size elevationMap transpose (automatically allocated if of wrong size)
40+
* @param height : height to generate the signed distance at.
41+
* @param resolution : resolution of the elevation map. (The true distance [m] between cells in world frame)
42+
* @param minHeight : the lowest height contained in elevationMap
43+
* @param maxHeight : the maximum height contained in elevationMap
44+
*/
45+
void signedDistanceAtHeightTranspose(const Matrix& elevationMap, Matrix& sdfTranspose, Matrix& tmp, Matrix& tmpTranspose, float height,
46+
float resolution, float minHeight, float maxHeight);
47+
48+
/**
49+
* Gets the 2D signed distance from an occupancy grid.
50+
* Returns +INF if there are no obstacles, and -INF if there are only obstacles
51+
*
52+
* @param occupancyGrid : occupancy grid with true = obstacle, false = free space
53+
* @param resolution : resolution of the grid.
54+
* @return signed distance for each point in the grid to the occupancy border.
55+
*/
56+
Matrix signedDistanceFromOccupancy(const Eigen::Matrix<bool, -1, -1>& occupancyGrid, float resolution);
57+
58+
} // namespace signed_distance_field
59+
} // namespace grid_map
Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,21 @@
1+
/*
2+
* Utils.h
3+
*
4+
* Created on: Jul 10, 2020
5+
* Author: Ruben Grandia
6+
* Institute: ETH Zurich
7+
*/
8+
9+
#pragma once
10+
11+
namespace grid_map {
12+
namespace signed_distance_field {
13+
14+
// Check existence of inf
15+
static_assert(std::numeric_limits<float>::has_infinity, "float does not support infinity");
16+
17+
//! Distance value that is considered infinite.
18+
constexpr float INF = std::numeric_limits<float>::infinity();
19+
20+
} // namespace signed_distance_field
21+
} // namespace grid_map

0 commit comments

Comments
 (0)