Go to the documentation of this file.
48 typedef std::vector<Eigen::Vector3i, Eigen::aligned_allocator<Eigen::Vector3i>>
vector_Vector3i;
59 bool operator()(
const Eigen::Vector3i& loc_1,
const Eigen::Vector3i& loc_2)
const
61 if (loc_1.z() != loc_2.z())
62 return (loc_1.z() < loc_2.z());
63 else if (loc_1.y() != loc_2.y())
64 return (loc_1.y() < loc_2.y());
65 else if (loc_1.x() != loc_2.x())
66 return (loc_1.x() < loc_2.x());
108 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
166 double origin_y,
double origin_z,
double max_distance,
167 bool propagate_negative_distances =
false);
193 bool propagate_negative_distances =
false);
292 void reset()
override;
309 double getDistance(
double x,
double y,
double z)
const override;
326 double getDistance(
int x,
int y,
int z)
const override;
328 bool isCellValid(
int x,
int y,
int z)
const override;
332 bool gridToWorld(
int x,
int y,
int z,
double& world_x,
double& world_y,
double& world_z)
const override;
333 bool worldToGrid(
double world_x,
double world_y,
double world_z,
int& x,
int& y,
int& z)
const override;
419 return ncell == cell ? nullptr : ncell;
426 return ncell == cell ? nullptr : ncell;
450 typedef std::set<Eigen::Vector3i, CompareEigenVector3i, Eigen::aligned_allocator<Eigen::Vector3i>>
VoxelSet;
583 : distance_square_(distance_square), negative_distance_square_(negative_distance_squared)
int max_distance_sq_
Holds maximum distance squared in cells.
void addNewObstacleVoxels(const EigenSTL::vector_Vector3i &voxel_points)
Adds a valid set of integer points to the voxel grid.
void print(const VoxelSet &set)
Debug function that prints all voxels in a set to ROS_DEBUG_NAMED.
std::vector< double > sqrt_table_
Precomputed square root table for faster distance lookups.
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 dist...
Eigen::Vector3i getLocationDifference(int directionNumber) const
Helper function that gets change values given single number representing update direction.
bool gridToWorld(int x, int y, int z, double &world_x, double &world_y, double &world_z) const override
Converts from an set of integer indices to a world location given the origin and resolution parameter...
std::set< Eigen::Vector3i, CompareEigenVector3i, Eigen::aligned_allocator< Eigen::Vector3i > > VoxelSet
A DistanceField implementation that uses a vector propagation method. Distances propagate outward fro...
int getMaximumDistanceSquared() const
Gets the maximum distance squared value.
~PropagationDistanceField() override
Empty destructor.
std::vector< EigenSTL::vector_Vector3i > bucket_queue_
Structure used to hold propagation frontier.
Eigen::Vector3i closest_point_
Closest occupied cell.
void reset() override
Resets the entire distance field to max_distance for positive values and zero for negative values.
void addPointsToField(const EigenSTL::vector_Vector3d &points) override
Add a set of obstacle points to the distance field, updating distance values accordingly....
Eigen::Vector3i closest_negative_point_
Closest unoccupied cell.
bool isCellValid(int x, int y, int z) const override
Determines whether or not the cell associated with the supplied indices is valid for this distance fi...
bool propagate_negative_
Whether or not to propagate negative distances.
VoxelGrid< PropDistanceFieldVoxel >::Ptr voxel_grid_
Actual container for distance data.
bool worldToGrid(double world_x, double world_y, double world_z, int &x, int &y, int &z) const override
Converts from a world location to a set of integer indices. Should return false if the world location...
Struct for sorting type Eigen::Vector3i for use in sorted std containers. Sorts in z order,...
void removeObstacleVoxels(const EigenSTL::vector_Vector3i &voxel_points)
Removes a valid set of integer points from the voxel grid.
VoxelGrid holds a dense 3D, axis-aligned set of data at a given resolution, where the data is supplie...
std::vector< EigenSTL::vector_Vector3i > negative_bucket_queue_
Data member that holds points from which to propagate in the negative, where each vector holds points...
bool operator()(const Eigen::Vector3i &loc_1, const Eigen::Vector3i &loc_2) const
std::vector< Eigen::Vector3i, Eigen::aligned_allocator< Eigen::Vector3i > > vector_Vector3i
DistanceField is an abstract base class for computing distances from sets of 3D obstacle points....
int update_direction_
Direction from which this voxel was updated for occupied distance propagation.
void updatePointsInField(const EigenSTL::vector_Vector3d &old_points, const EigenSTL::vector_Vector3d &new_points) override
This function will remove any obstacle points that are in the old point set but not the new point set...
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
static const int UNINITIALIZED
Value that represents an unitialized voxel.
EigenSTL::vector_Vector3i direction_number_to_direction_
Holds conversion from direction number to integer changes.
double getDistance(double x, double y, double z) const override
Get the distance value associated with the cell indicated by the world coordinate....
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,...
void initNeighborhoods()
Helper function for computing location and neighborhood information in 27 connected voxel grid.
double max_distance_
Holds maximum distance
bool writeToStream(std::ostream &stream) const override
Writes the contents of the distance field to the supplied stream.
Namespace for holding classes that generate distance fields.
int getYNumCells() const override
Gets the number of cells along the Y axis.
std::vector< std::vector< EigenSTL::vector_Vector3i > > neighborhoods_
Holds information on neighbor direction, with 27 different directions. Shows where to propagate given...
int distance_square_
Distance in cells to the closest obstacle, squared.
void initialize()
Initializes the field, resetting the voxel grid and building a sqrt lookup table for efficiency based...
int negative_distance_square_
Distance in cells to the nearest unoccupied cell, squared.
void removePointsFromField(const EigenSTL::vector_Vector3d &points) override
Remove a set of obstacle points from the distance field, updating distance values accordingly.
void propagateNegative()
Propagates inward to a maximum distance given the contents of the negative_bucket_queue_,...
int negative_update_direction_
Direction from which this voxel was updated for negative distance propagation.
double getUninitializedDistance() const override
Gets a distance value for an invalid cell.
int getZNumCells() const override
Gets the number of cells along the Z axis.
bool readFromStream(std::istream &stream) override
Reads, parameterizes, and populates the distance field based on the supplied stream.
const PropDistanceFieldVoxel & getCell(int x, int y, int z) const
Gets full cell data given an index.
const PropDistanceFieldVoxel * getNearestCell(int x, int y, int z, double &dist, Eigen::Vector3i &pos) const
Gets nearest surface cell and returns distance to it.
PropDistanceFieldVoxel()
Constructor. All fields left uninitialized.
void propagatePositive()
Propagates outward to the maximum distance given the contents of the bucket_queue_,...
int getXNumCells() const override
Gets the number of cells along the X axis.
Structure that holds voxel information for the DistanceField. Will be used in VoxelGrid.
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:15