Namespaces | |
| internal | |
Classes | |
| struct | Gridmap3dLookup |
Functions | |
| void | columnwiseCentralDifference (const Matrix &data, Matrix ¢ralDifference, float resolution) |
| float | equidistancePoint (float q, float fq, float p, float fp) |
| bool | isEqualSdf (const Matrix &sdf0, const Matrix &sdf1, float tol) |
| void | layerCentralDifference (const Matrix &data_km1, const Matrix &data_kp1, Matrix &result, float resolution) |
| void | layerFiniteDifference (const Matrix &data_k, const Matrix &data_kp1, Matrix &result, float resolution) |
| Matrix | naiveSignedDistanceAtHeight (const Matrix &elevationMap, float height, float resolution) |
| Matrix | naiveSignedDistanceFromOccupancy (const Eigen::Matrix< bool, -1, -1 > &occupancyGrid, float resolution) |
| Eigen::Matrix< bool, -1, -1 > | occupancyAtHeight (const Matrix &elevationMap, float height) |
| float | pixelBorderDistance (float i, float j) |
| Matrix | signedDistanceAtHeight (const Matrix &elevationMap, float height, float resolution, float minHeight, float maxHeight) |
| void | signedDistanceAtHeightTranspose (const Matrix &elevationMap, Matrix &sdfTranspose, Matrix &tmp, Matrix &tmpTranspose, float height, float resolution, float minHeight, float maxHeight) |
| Matrix | signedDistanceFromOccupancy (const Eigen::Matrix< bool, -1, -1 > &occupancyGrid, float resolution) |
| float | squarePixelBorderDistance (float i, float j, float f) |
Variables | |
| constexpr float | INF = std::numeric_limits<float>::infinity() |
| Distance value that is considered infinite. More... | |
|
inline |
Takes the columnwise central difference of a matrix. Uses single sided difference at the boundaries. diff = (col(i+1) - col(i-1)) / (2 * resolution)
| data | [in] : data to take the difference of. |
| centralDifference | [out] : matrix to store the result in. |
| resolution | [in] : scaling of the distance between two columns. |
Definition at line 24 of file DistanceDerivatives.hpp.
|
inline |
Return the point s in pixel space that is equally far from p and q (taking into account offsets fp, and fq) It is the solution to the following equation: squarePixelBorderDistance(s, q, fq) == squarePixelBorderDistance(s, p, fp)
Definition at line 89 of file PixelBorderDistance.hpp.
|
inline |
Definition at line 19 of file naiveSignedDistance.hpp.
|
inline |
Takes the central difference between layers result = (data_{k+1} - data{k-1}) / (2.0 * resolution)
Definition at line 56 of file DistanceDerivatives.hpp.
|
inline |
Takes the finite difference between layers result = (data_{k+1} - data{k}) / resolution
Definition at line 47 of file DistanceDerivatives.hpp.
|
inline |
Definition at line 37 of file naiveSignedDistance.hpp.
|
inline |
Definition at line 76 of file naiveSignedDistance.hpp.
|
inline |
Definition at line 14 of file naiveSignedDistance.hpp.
|
inline |
Returns distance between the center of a pixel and the border of an other pixel. Returns zero if the center is inside the other pixel. Pixels are assumed to have size 1.0F
| i | : location of pixel 1 |
| j | : location of pixel 2 |
Definition at line 26 of file PixelBorderDistance.hpp.
| Matrix grid_map::signed_distance_field::signedDistanceAtHeight | ( | const Matrix & | elevationMap, |
| float | height, | ||
| float | resolution, | ||
| float | minHeight, | ||
| float | maxHeight | ||
| ) |
Computes the signed distance field at a specified height for a given elevation map.
| elevationMap | : elevation data. |
| height | : height to generate the signed distance at. |
| resolution | : resolution of the elevation map. (The true distance [m] between cells in world frame) |
| minHeight | : the lowest height contained in elevationMap |
| maxHeight | : the maximum height contained in elevationMap |
Definition at line 263 of file SignedDistance2d.cpp.
| void grid_map::signed_distance_field::signedDistanceAtHeightTranspose | ( | const Matrix & | elevationMap, |
| Matrix & | sdfTranspose, | ||
| Matrix & | tmp, | ||
| Matrix & | tmpTranspose, | ||
| float | height, | ||
| float | resolution, | ||
| float | minHeight, | ||
| float | maxHeight | ||
| ) |
Same as above, but returns the sdf in transposed form. Also takes temporary variables from outside to prevent memory allocation.
| elevationMap | : elevation data. |
| sdfTranspose | : [output] resulting sdf in transposed form (automatically allocated if of wrong size) |
| tmp | : temporary of size elevationMap (automatically allocated if of wrong size) |
| tmpTranspose | : temporary of size elevationMap transpose (automatically allocated if of wrong size) |
| height | : height to generate the signed distance at. |
| resolution | : resolution of the elevation map. (The true distance [m] between cells in world frame) |
| minHeight | : the lowest height contained in elevationMap |
| maxHeight | : the maximum height contained in elevationMap |
Definition at line 242 of file SignedDistance2d.cpp.
| Matrix grid_map::signed_distance_field::signedDistanceFromOccupancy | ( | const Eigen::Matrix< bool, -1, -1 > & | occupancyGrid, |
| float | resolution | ||
| ) |
Gets the 2D signed distance from an occupancy grid. Returns +INF if there are no obstacles, and -INF if there are only obstacles
| occupancyGrid | : occupancy grid with true = obstacle, false = free space |
| resolution | : resolution of the grid. |
Definition at line 272 of file SignedDistance2d.cpp.
|
inline |
Returns square pixelBorderDistance, adding offset f.
Definition at line 33 of file PixelBorderDistance.hpp.