Namespaces | Classes | Functions | Variables
grid_map::signed_distance_field Namespace Reference

Namespaces

 internal
 

Classes

struct  Gridmap3dLookup
 

Functions

void columnwiseCentralDifference (const Matrix &data, Matrix &centralDifference, 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...
 

Function Documentation

◆ columnwiseCentralDifference()

void grid_map::signed_distance_field::columnwiseCentralDifference ( const Matrix data,
Matrix centralDifference,
float  resolution 
)
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)

Parameters
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.

◆ equidistancePoint()

float grid_map::signed_distance_field::equidistancePoint ( float  q,
float  fq,
float  p,
float  fp 
)
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.

◆ isEqualSdf()

bool grid_map::signed_distance_field::isEqualSdf ( const Matrix sdf0,
const Matrix sdf1,
float  tol 
)
inline

Definition at line 19 of file naiveSignedDistance.hpp.

◆ layerCentralDifference()

void grid_map::signed_distance_field::layerCentralDifference ( const Matrix data_km1,
const Matrix data_kp1,
Matrix result,
float  resolution 
)
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.

◆ layerFiniteDifference()

void grid_map::signed_distance_field::layerFiniteDifference ( const Matrix data_k,
const Matrix data_kp1,
Matrix result,
float  resolution 
)
inline

Takes the finite difference between layers result = (data_{k+1} - data{k}) / resolution

Definition at line 47 of file DistanceDerivatives.hpp.

◆ naiveSignedDistanceAtHeight()

Matrix grid_map::signed_distance_field::naiveSignedDistanceAtHeight ( const Matrix elevationMap,
float  height,
float  resolution 
)
inline

Definition at line 37 of file naiveSignedDistance.hpp.

◆ naiveSignedDistanceFromOccupancy()

Matrix grid_map::signed_distance_field::naiveSignedDistanceFromOccupancy ( const Eigen::Matrix< bool, -1, -1 > &  occupancyGrid,
float  resolution 
)
inline

Definition at line 76 of file naiveSignedDistance.hpp.

◆ occupancyAtHeight()

Eigen::Matrix<bool, -1, -1> grid_map::signed_distance_field::occupancyAtHeight ( const Matrix elevationMap,
float  height 
)
inline

Definition at line 14 of file naiveSignedDistance.hpp.

◆ pixelBorderDistance()

float grid_map::signed_distance_field::pixelBorderDistance ( float  i,
float  j 
)
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

Parameters
i: location of pixel 1
j: location of pixel 2
Returns
: absolute distance between center of pixel 1 and the border of pixel 2

Definition at line 26 of file PixelBorderDistance.hpp.

◆ signedDistanceAtHeight()

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.

Parameters
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
Returns
The signed distance field at the query height.

Definition at line 263 of file SignedDistance2d.cpp.

◆ signedDistanceAtHeightTranspose()

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.

Parameters
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.

◆ signedDistanceFromOccupancy()

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

Parameters
occupancyGrid: occupancy grid with true = obstacle, false = free space
resolution: resolution of the grid.
Returns
signed distance for each point in the grid to the occupancy border.

Definition at line 272 of file SignedDistance2d.cpp.

◆ squarePixelBorderDistance()

float grid_map::signed_distance_field::squarePixelBorderDistance ( float  i,
float  j,
float  f 
)
inline

Returns square pixelBorderDistance, adding offset f.

Definition at line 33 of file PixelBorderDistance.hpp.

Variable Documentation

◆ INF

constexpr float grid_map::signed_distance_field::INF = std::numeric_limits<float>::infinity()

Distance value that is considered infinite.

Definition at line 18 of file Utils.hpp.



grid_map_sdf
Author(s): Takahiro Miki , Péter Fankhauser
autogenerated on Wed Jul 5 2023 02:23:42