A DistanceField implementation that uses a vector propagation method. Distances propagate outward from occupied cells, or inwards from unoccupied cells if negative distances are to be computed, which is optional. Outward and inward propagation only occur to a desired maximum distance - cells that are more than this maximum distance from the nearest cell will have maximum distance measurements. More...
#include <propagation_distance_field.h>
Public Member Functions | |
virtual void | addPointsToField (const EigenSTL::vector_Vector3d &points) |
Add a set of obstacle points to the distance field, updating distance values accordingly. The distance field may already contain obstacle cells. | |
const PropDistanceFieldVoxel & | getCell (int x, int y, int z) const |
Gets full cell data given an index. | |
virtual double | getDistance (double x, double y, double z) const |
Get the distance value associated with the cell indicated by the world coordinate. If the cell is invalid, max_distance will be returned. If running without negative distances, all obstacle cells will have zero distance. If running with negative distances, the distance will be between -max_distance and max_distance, with no values having a 0 distance. | |
virtual double | getDistance (int x, int y, int z) const |
Get the distance value associated with the cell indicated by the index coordinates. If the cell is invalid, max_distance will be returned. If running without negative distances, all obstacle cells will have zero distance. If running with negative distances, the distance will be between -max_distance and max_distance, with no values having a 0 distance. | |
int | getMaximumDistanceSquared () const |
Gets the maximum distance squared value. | |
const PropDistanceFieldVoxel * | getNearestCell (int x, int y, int z, double &dist, Eigen::Vector3i &pos) const |
Gets nearest surface cell and returns distance to it. | |
virtual double | getUninitializedDistance () const |
Gets a distance value for an invalid cell. | |
virtual int | getXNumCells () const |
Gets the number of cells along the X axis. | |
virtual int | getYNumCells () const |
Gets the number of cells along the Y axis. | |
virtual int | getZNumCells () const |
Gets the number of cells along the Z axis. | |
virtual bool | gridToWorld (int x, int y, int z, double &world_x, double &world_y, double &world_z) const |
Converts from an set of integer indices to a world location given the origin and resolution parameters. | |
virtual bool | isCellValid (int x, int y, int z) const |
Determines whether or not the cell associated with the supplied indices is valid for this distance field. | |
PropagationDistanceField (double size_x, double size_y, double size_z, double resolution, double origin_x, double origin_y, double origin_z, double max_distance, bool propagate_negative_distances=false) | |
Constructor that initializes entire distance field to empty - all cells will be assigned maximum distance values. All units are arbitrary but are assumed for documentation purposes to represent meters. | |
PropagationDistanceField (const octomap::OcTree &octree, const octomap::point3d &bbx_min, const octomap::point3d &bbx_max, double max_distance, bool propagate_negative_distances=false) | |
Constructor based on an OcTree and bounding box information. A distance field will be constructed with dimensions based on the supplied bounding box at the resolution of the OcTree. All octree obstacle cells will be added to the resulting distance field using the DistanceField::addOcTreeToField function. | |
PropagationDistanceField (std::istream &stream, double max_distance, bool propagate_negative_distances=false) | |
Constructor that takes an istream and reads the contents of a saved distance field, adding all obstacle points and running propagation given the arguments for max_distance and propagate_negative_distances. Calls the function readFromStream. | |
virtual bool | readFromStream (std::istream &stream) |
Reads, parameterizes, and populates the distance field based on the supplied stream. | |
virtual void | removePointsFromField (const EigenSTL::vector_Vector3d &points) |
Remove a set of obstacle points from the distance field, updating distance values accordingly. | |
virtual void | reset () |
Resets the entire distance field to max_distance for positive values and zero for negative values. | |
virtual void | updatePointsInField (const EigenSTL::vector_Vector3d &old_points, const EigenSTL::vector_Vector3d &new_points) |
This function will remove any obstacle points that are in the old point set but not the new point set, and add any obstacle points that are in the new block set but not the old block set. Any points that are in both sets are left unchanged. For more information see DistanceField::updatePointsInField. | |
virtual bool | worldToGrid (double world_x, double world_y, double world_z, int &x, int &y, int &z) const |
Converts from a world location to a set of integer indices. Should return false if the world location is not valid in the distance field, and should populate the index values in either case. | |
virtual bool | writeToStream (std::ostream &stream) const |
Writes the contents of the distance field to the supplied stream. | |
virtual | ~PropagationDistanceField () |
Empty destructor. | |
Private Types | |
typedef std::set < Eigen::Vector3i, compareEigen_Vector3i > | VoxelSet |
Typedef for set of integer indices. | |
Private Member Functions | |
void | addNewObstacleVoxels (const std::vector< Eigen::Vector3i > &voxel_points) |
Adds a valid set of integer points to the voxel grid. | |
int | getDirectionNumber (int dx, int dy, int dz) const |
Helper function to get a single number in a 27 connected 3D voxel grid given dx, dy, and dz values. | |
virtual double | getDistance (const PropDistanceFieldVoxel &object) const |
Determines distance based on actual voxel data. | |
Eigen::Vector3i | getLocationDifference (int directionNumber) const |
Helper function that gets change values given single number representing update direction. | |
void | initialize () |
Initializes the field, resetting the voxel grid and building a sqrt lookup table for efficiency based on max_distance_. | |
void | initNeighborhoods () |
Helper function for computing location and neighborhood information in 27 connected voxel grid. | |
void | print (const VoxelSet &set) |
Debug function that prints all voxels in a set to logDebug. | |
void | print (const EigenSTL::vector_Vector3d &points) |
Debug function that prints all points in a vector to logDebug. | |
void | propagateNegative () |
Propagates inward to a maximum distance given the contents of the negative_bucket_queue_, and clears the negative_bucket_queue_. | |
void | propagatePositive () |
Propagates outward to the maximum distance given the contents of the bucket_queue_, and clears the bucket_queue_. | |
void | removeObstacleVoxels (const std::vector< Eigen::Vector3i > &voxel_points) |
Removes a valid set of integer points from the voxel grid. | |
Static Private Member Functions | |
static int | eucDistSq (Eigen::Vector3i point1, Eigen::Vector3i point2) |
Computes squared distance between two 3D integer points. | |
Private Attributes | |
std::vector< std::vector < Eigen::Vector3i > > | bucket_queue_ |
Structure used to hold propagation frontier. | |
std::vector< Eigen::Vector3i > | direction_number_to_direction_ |
Holds conversion from direction number to integer changes. | |
double | max_distance_ |
Holds maximum distance. | |
int | max_distance_sq_ |
Holds maximum distance squared in cells. | |
std::vector< std::vector < Eigen::Vector3i > > | negative_bucket_queue_ |
Data member that holds points from which to propagate in the negative, where each vector holds points that are a particular integer distance from the closest unoccupied points. | |
std::vector< std::vector < std::vector< Eigen::Vector3i > > > | neighborhoods_ |
Holds information on neighbor direction, with 27 different directions. Shows where to propagate given an integer distance and an update direction. | |
bool | propagate_negative_ |
Whether or not to propagate negative distances. | |
std::vector< double > | sqrt_table_ |
Precomputed square root table for faster distance lookups. | |
boost::shared_ptr< VoxelGrid < PropDistanceFieldVoxel > > | voxel_grid_ |
Actual container for distance data. |
A DistanceField implementation that uses a vector propagation method. Distances propagate outward from occupied cells, or inwards from unoccupied cells if negative distances are to be computed, which is optional. Outward and inward propagation only occur to a desired maximum distance - cells that are more than this maximum distance from the nearest cell will have maximum distance measurements.
This class uses a VoxelGrid to hold all data. One important decision that must be made on construction is whether or not to create a signed version of the distance field. If the distance field is unsigned, it means that the minumum obstacle distance is 0, a value that will be assigned to all obstacle cells. Gradient queries for obstacle cells will not give useful information, as the gradient at an obstacle cell will point to the cell itself. If this behavior is acceptable, then the performance of this mode will be more efficient, as no propagation will occur for obstacle cells. The other option is to calculate signed distances. In this case, negative distances up to the maximum distance are calculated for obstacle volumes. This distance encodes the distance of an obstacle cell to the nearest unoccupied obstacle voxel. Furthmore, gradients pointing out of the volume will be produced. Depending on the data, calculating this data can significantly impact the time it takes to add and remove obstacle cells.
Definition at line 134 of file propagation_distance_field.h.
typedef std::set<Eigen::Vector3i, compareEigen_Vector3i> distance_field::PropagationDistanceField::VoxelSet [private] |
Typedef for set of integer indices.
Definition at line 455 of file propagation_distance_field.h.
distance_field::PropagationDistanceField::PropagationDistanceField | ( | double | size_x, |
double | size_y, | ||
double | size_z, | ||
double | resolution, | ||
double | origin_x, | ||
double | origin_y, | ||
double | origin_z, | ||
double | max_distance, | ||
bool | propagate_negative_distances = false |
||
) |
Constructor that initializes entire distance field to empty - all cells will be assigned maximum distance values. All units are arbitrary but are assumed for documentation purposes to represent meters.
[in] | size_x | The X dimension in meters of the volume to represent |
[in] | size_y | The Y dimension in meters of the volume to represent |
[in] | size_z | The Z dimension in meters of the volume to represent |
[in] | resolution | The resolution in meters of the volume |
[in] | origin_x | The minimum X point of the volume |
[in] | origin_y | The minimum Y point of the volume |
[in] | origin_z | The minimum Z point of the volume |
[in] | max_distance | The maximum distance to which to propagate distance values. Cells that are greater than this distance will be assigned the maximum distance value. |
[in] | propagate_negative_distances | Whether or not to propagate negative distances. If false, no propagation occurs, and all obstacle cells will be assigned zero distance. See the PropagationDistanceField description for more information on the implications of this. |
Definition at line 47 of file propagation_distance_field.cpp.
distance_field::PropagationDistanceField::PropagationDistanceField | ( | const octomap::OcTree & | octree, |
const octomap::point3d & | bbx_min, | ||
const octomap::point3d & | bbx_max, | ||
double | max_distance, | ||
bool | propagate_negative_distances = false |
||
) |
Constructor based on an OcTree and bounding box information. A distance field will be constructed with dimensions based on the supplied bounding box at the resolution of the OcTree. All octree obstacle cells will be added to the resulting distance field using the DistanceField::addOcTreeToField function.
[in] | octree | The OcTree from which to construct the distance field |
[in] | bbx_min | The minimum world coordinates of the bounding box |
[in] | bbx_max | The maximum world coordinates of the bounding box |
[in] | max_distance | The maximum distance to which to propagate distance values. Cells that are greater than this distance will be assigned the maximum distance value. |
[in] | propagate_negative_distances | Whether or not to propagate negative distances. If false, no propagation occurs, and all obstacle cells will be assigned zero distance. See the PropagationDistanceField description for more information on the implications of this. |
Definition at line 59 of file propagation_distance_field.cpp.
distance_field::PropagationDistanceField::PropagationDistanceField | ( | std::istream & | stream, |
double | max_distance, | ||
bool | propagate_negative_distances = false |
||
) |
Constructor that takes an istream and reads the contents of a saved distance field, adding all obstacle points and running propagation given the arguments for max_distance and propagate_negative_distances. Calls the function readFromStream.
[in] | stream | The stream from which to read the data |
[in] | max_distance | The maximum distance to which to propagate distance values. Cells that are greater than this distance will be assigned the maximum distance value. |
[in] | propagate_negative_distances | Whether or not to propagate negative distances. If false, no propagation occurs, and all obstacle cells will be assigned zero distance. See the PropagationDistanceField description for more information on the implications of this. |
Definition at line 78 of file propagation_distance_field.cpp.
virtual distance_field::PropagationDistanceField::~PropagationDistanceField | ( | ) | [inline, virtual] |
Empty destructor.
Definition at line 229 of file propagation_distance_field.h.
void distance_field::PropagationDistanceField::addNewObstacleVoxels | ( | const std::vector< Eigen::Vector3i > & | voxel_points | ) | [private] |
Adds a valid set of integer points to the voxel grid.
voxel_points | Valid set of voxel points for addition |
Definition at line 245 of file propagation_distance_field.cpp.
void distance_field::PropagationDistanceField::addPointsToField | ( | const EigenSTL::vector_Vector3d & | points | ) | [virtual] |
Add a set of obstacle points to the distance field, updating distance values accordingly. The distance field may already contain obstacle cells.
The function first checks that each location represents a valid point - only valid points will be added. It takes the vector of valid points and performs positive propagation on them. If the class has been set up to propagate negative distance, those will also be propagated.
[in] | points | The set of obstacle points to add |
Implements distance_field::DistanceField.
Definition at line 200 of file propagation_distance_field.cpp.
int distance_field::PropagationDistanceField::eucDistSq | ( | Eigen::Vector3i | point1, |
Eigen::Vector3i | point2 | ||
) | [static, private] |
Computes squared distance between two 3D integer points.
point1 | Point 1 for distance |
point2 | Point 2 for distance |
Definition at line 109 of file propagation_distance_field.cpp.
const PropDistanceFieldVoxel& distance_field::PropagationDistanceField::getCell | ( | int | x, |
int | y, | ||
int | z | ||
) | const [inline] |
Gets full cell data given an index.
x,y,z MUST be valid or data corruption (SEGFAULTS) will occur.
[in] | x | The integer X location |
[in] | y | The integer Y location |
[in] | z | The integer Z location |
Definition at line 393 of file propagation_distance_field.h.
int distance_field::PropagationDistanceField::getDirectionNumber | ( | int | dx, |
int | dy, | ||
int | dz | ||
) | const [private] |
Helper function to get a single number in a 27 connected 3D voxel grid given dx, dy, and dz values.
dx | The change in the X direction |
dy | The change in the X direction |
dz | The change in the Z direction |
Definition at line 600 of file propagation_distance_field.cpp.
double distance_field::PropagationDistanceField::getDistance | ( | double | x, |
double | y, | ||
double | z | ||
) | const [virtual] |
Get the distance value associated with the cell indicated by the world coordinate. If the cell is invalid, max_distance will be returned. If running without negative distances, all obstacle cells will have zero distance. If running with negative distances, the distance will be between -max_distance and max_distance, with no values having a 0 distance.
[in] | x | The X location of the cell |
[in] | y | The X location of the cell |
[in] | z | The X location of the cell |
Implements distance_field::DistanceField.
Definition at line 610 of file propagation_distance_field.cpp.
double distance_field::PropagationDistanceField::getDistance | ( | int | x, |
int | y, | ||
int | z | ||
) | const [virtual] |
Get the distance value associated with the cell indicated by the index coordinates. If the cell is invalid, max_distance will be returned. If running without negative distances, all obstacle cells will have zero distance. If running with negative distances, the distance will be between -max_distance and max_distance, with no values having a 0 distance.
[in] | x | The integer X location |
[in] | y | The integer Y location |
[in] | z | The integer Z location |
Implements distance_field::DistanceField.
Definition at line 615 of file propagation_distance_field.cpp.
double distance_field::PropagationDistanceField::getDistance | ( | const PropDistanceFieldVoxel & | object | ) | const [inline, private, virtual] |
Determines distance based on actual voxel data.
object | Actual voxel data |
Definition at line 606 of file propagation_distance_field.h.
Eigen::Vector3i distance_field::PropagationDistanceField::getLocationDifference | ( | int | directionNumber | ) | const [private] |
Helper function that gets change values given single number representing update direction.
directionNumber | Direction number 0-26 |
Definition at line 605 of file propagation_distance_field.cpp.
int distance_field::PropagationDistanceField::getMaximumDistanceSquared | ( | ) | const [inline] |
Gets the maximum distance squared value.
Produced by taking the ceiling of the maximum distance divided by the resolution, and then squaring that value.
Definition at line 448 of file propagation_distance_field.h.
const PropDistanceFieldVoxel* distance_field::PropagationDistanceField::getNearestCell | ( | int | x, |
int | y, | ||
int | z, | ||
double & | dist, | ||
Eigen::Vector3i & | pos | ||
) | const [inline] |
Gets nearest surface cell and returns distance to it.
x,y,z MUST be valid or data corruption (SEGFAULTS) will occur.
[in] | x | The integer X location of the starting cell |
[in] | y | The integer Y location of the starting cell |
[in] | z | The integer Z location of the starting cell |
[out] | dist | if starting cell is inside, the negative distance to the nearest outside cell if starting cell is outside, the positive distance to the nearest inside cell if nearby cell is unknown, zero |
[out] | pos | the position of the nearest cell |
Definition at line 416 of file propagation_distance_field.h.
virtual double distance_field::PropagationDistanceField::getUninitializedDistance | ( | ) | const [inline, virtual] |
Gets a distance value for an invalid cell.
Implements distance_field::DistanceField.
Definition at line 377 of file propagation_distance_field.h.
int distance_field::PropagationDistanceField::getXNumCells | ( | ) | const [virtual] |
Gets the number of cells along the X axis.
Implements distance_field::DistanceField.
Definition at line 625 of file propagation_distance_field.cpp.
int distance_field::PropagationDistanceField::getYNumCells | ( | ) | const [virtual] |
Gets the number of cells along the Y axis.
Implements distance_field::DistanceField.
Definition at line 630 of file propagation_distance_field.cpp.
int distance_field::PropagationDistanceField::getZNumCells | ( | ) | const [virtual] |
Gets the number of cells along the Z axis.
Implements distance_field::DistanceField.
Definition at line 635 of file propagation_distance_field.cpp.
bool distance_field::PropagationDistanceField::gridToWorld | ( | int | x, |
int | y, | ||
int | z, | ||
double & | world_x, | ||
double & | world_y, | ||
double & | world_z | ||
) | const [virtual] |
Converts from an set of integer indices to a world location given the origin and resolution parameters.
[in] | x | The integer X location |
[in] | y | The integer Y location |
[in] | z | The integer Z location |
[out] | world_x | The computed world X location |
[out] | world_y | The computed world X location |
[out] | world_z | The computed world X location |
Implements distance_field::DistanceField.
Definition at line 640 of file propagation_distance_field.cpp.
void distance_field::PropagationDistanceField::initialize | ( | ) | [private] |
Initializes the field, resetting the voxel grid and building a sqrt lookup table for efficiency based on max_distance_.
Definition at line 88 of file propagation_distance_field.cpp.
void distance_field::PropagationDistanceField::initNeighborhoods | ( | ) | [private] |
Helper function for computing location and neighborhood information in 27 connected voxel grid.
Definition at line 542 of file propagation_distance_field.cpp.
bool distance_field::PropagationDistanceField::isCellValid | ( | int | x, |
int | y, | ||
int | z | ||
) | const [virtual] |
Determines whether or not the cell associated with the supplied indices is valid for this distance field.
[in] | x | The X index of the cell |
[in] | y | The Y index of the cell |
[in] | z | The Z index of the cell |
Implements distance_field::DistanceField.
Definition at line 620 of file propagation_distance_field.cpp.
void distance_field::PropagationDistanceField::print | ( | const VoxelSet & | set | ) | [private] |
Debug function that prints all voxels in a set to logDebug.
set | Voxel set to print |
Definition at line 117 of file propagation_distance_field.cpp.
void distance_field::PropagationDistanceField::print | ( | const EigenSTL::vector_Vector3d & | points | ) | [private] |
Debug function that prints all points in a vector to logDebug.
points | Points to print |
Definition at line 129 of file propagation_distance_field.cpp.
void distance_field::PropagationDistanceField::propagateNegative | ( | ) | [private] |
Propagates inward to a maximum distance given the contents of the negative_bucket_queue_, and clears the negative_bucket_queue_.
Definition at line 463 of file propagation_distance_field.cpp.
void distance_field::PropagationDistanceField::propagatePositive | ( | ) | [private] |
Propagates outward to the maximum distance given the contents of the bucket_queue_, and clears the bucket_queue_.
Definition at line 404 of file propagation_distance_field.cpp.
bool distance_field::PropagationDistanceField::readFromStream | ( | std::istream & | stream | ) | [virtual] |
Reads, parameterizes, and populates the distance field based on the supplied stream.
This function assumes that the file begins with ASCII data, and that the binary data has been written in bit formulation and compressed using Zlib. The function will reinitialize all data members based on the data in the file, using preset values for max_distance_ and propagate_negative_distances_. All occupied cells will be added to the distance field.
[in] | stream | The stream from which to read |
Implements distance_field::DistanceField.
Definition at line 685 of file propagation_distance_field.cpp.
void distance_field::PropagationDistanceField::removeObstacleVoxels | ( | const std::vector< Eigen::Vector3i > & | voxel_points | ) | [private] |
Removes a valid set of integer points from the voxel grid.
voxel_points | Valid set of voxel points for removal |
Definition at line 322 of file propagation_distance_field.cpp.
void distance_field::PropagationDistanceField::removePointsFromField | ( | const EigenSTL::vector_Vector3d & | points | ) | [virtual] |
Remove a set of obstacle points from the distance field, updating distance values accordingly.
This function is relatively less efficient than adding points to the field in terms of positive distances - adding a given number of points will be less comptationally expensive than removing the same number of points. This is due to the nature of the propagation algorithm - when removing sets of cells, we must search outward from the freed cells and then propagate inward. Negative distances can be propagated more efficiently, as propagation can occur outward from newly freed cells without requiring a search step. If the set of occupied points that remain after removal is small it may be more efficient to call reset and then to add the remaining points rather than removing a set of points.
[in] | points | The set of obstacle points that will be set as free |
Implements distance_field::DistanceField.
Definition at line 221 of file propagation_distance_field.cpp.
void distance_field::PropagationDistanceField::reset | ( | ) | [virtual] |
Resets the entire distance field to max_distance for positive values and zero for negative values.
Implements distance_field::DistanceField.
Definition at line 522 of file propagation_distance_field.cpp.
void distance_field::PropagationDistanceField::updatePointsInField | ( | const EigenSTL::vector_Vector3d & | old_points, |
const EigenSTL::vector_Vector3d & | new_points | ||
) | [virtual] |
This function will remove any obstacle points that are in the old point set but not the new point set, and add any obstacle points that are in the new block set but not the old block set. Any points that are in both sets are left unchanged. For more information see DistanceField::updatePointsInField.
The implementation of this function finds the set of points that are in the old_points and not the new_points, and the in the new_points and not the old_points using std::set_difference. It then calls a removal function on the former set, and an addition function on the latter set.
If there is no overlap between the old_points and the new_points it is more efficient to first call removePointsFromField on the old_points and then addPointsToField on the new points - this does not require computing set differences.
[in] | old_points | The set of points that all should be obstacle cells in the distance field |
[in] | new_points | The set of points, all of which are intended to be obstacle points in the distance field |
Implements distance_field::DistanceField.
Definition at line 142 of file propagation_distance_field.cpp.
bool distance_field::PropagationDistanceField::worldToGrid | ( | double | world_x, |
double | world_y, | ||
double | world_z, | ||
int & | x, | ||
int & | y, | ||
int & | z | ||
) | const [virtual] |
Converts from a world location to a set of integer indices. Should return false if the world location is not valid in the distance field, and should populate the index values in either case.
[in] | world_x | The world X location |
[in] | world_y | The world Y location |
[in] | world_z | The world Z location |
[out] | x | The computed integer X location |
[out] | y | The computed integer X location |
[out] | z | The computed integer X location |
Implements distance_field::DistanceField.
Definition at line 646 of file propagation_distance_field.cpp.
bool distance_field::PropagationDistanceField::writeToStream | ( | std::ostream & | stream | ) | const [virtual] |
Writes the contents of the distance field to the supplied stream.
This function writes the resolution, size, and origin parameters to the file in ASCII. It then writes the occupancy data only in bit form (with values or 1 representing occupancy, and 0 representing empty space). It further runs Zlib compression on the binary data before actually writing to disk. The max_distance and propagate_negative_distances values are not written to file, and the distances themselves will need to be recreated on load.
[out] | stream | The stream to which to write the distance field contents. |
Implements distance_field::DistanceField.
Definition at line 651 of file propagation_distance_field.cpp.
std::vector<std::vector<Eigen::Vector3i> > distance_field::PropagationDistanceField::bucket_queue_ [private] |
Structure used to hold propagation frontier.
Data member that holds points from which to propagate, where each vector holds points that are a particular integer distance from the closest obstacle points
Definition at line 562 of file propagation_distance_field.h.
std::vector<Eigen::Vector3i > distance_field::PropagationDistanceField::direction_number_to_direction_ [private] |
Holds conversion from direction number to integer changes.
Definition at line 585 of file propagation_distance_field.h.
double distance_field::PropagationDistanceField::max_distance_ [private] |
Holds maximum distance.
Definition at line 566 of file propagation_distance_field.h.
Holds maximum distance squared in cells.
Definition at line 567 of file propagation_distance_field.h.
std::vector<std::vector<Eigen::Vector3i> > distance_field::PropagationDistanceField::negative_bucket_queue_ [private] |
Data member that holds points from which to propagate in the negative, where each vector holds points that are a particular integer distance from the closest unoccupied points.
Definition at line 564 of file propagation_distance_field.h.
std::vector<std::vector<std::vector<Eigen::Vector3i > > > distance_field::PropagationDistanceField::neighborhoods_ [private] |
Holds information on neighbor direction, with 27 different directions. Shows where to propagate given an integer distance and an update direction.
[0] - for expansion of d=0 [1] - for expansion of d>=1 Under this, we have the 27 directions Then, a list of neighborhoods for each direction
Definition at line 583 of file propagation_distance_field.h.
Whether or not to propagate negative distances.
Definition at line 557 of file propagation_distance_field.h.
std::vector<double> distance_field::PropagationDistanceField::sqrt_table_ [private] |
Precomputed square root table for faster distance lookups.
Definition at line 569 of file propagation_distance_field.h.
boost::shared_ptr<VoxelGrid<PropDistanceFieldVoxel> > distance_field::PropagationDistanceField::voxel_grid_ [private] |
Actual container for distance data.
Definition at line 559 of file propagation_distance_field.h.