44 #include <octomap/octomap.h>
45 #include <rclcpp/rclcpp.hpp>
49 typedef std::vector<Eigen::Vector3i, Eigen::aligned_allocator<Eigen::Vector3i>>
vector_Vector3i;
60 bool operator()(
const Eigen::Vector3i& loc_1,
const Eigen::Vector3i& loc_2)
const
62 if (loc_1.z() != loc_2.z())
63 return (loc_1.z() < loc_2.z());
64 else if (loc_1.y() != loc_2.y())
65 return (loc_1.y() < loc_2.y());
66 else if (loc_1.x() != loc_2.x())
67 return (loc_1.x() < loc_2.x());
167 double origin_y,
double origin_z,
double max_distance,
168 bool propagate_negative_distances =
false);
193 const octomap::point3d& bbx_max,
double max_distance,
194 bool propagate_negative_distances =
false);
286 const EigenSTL::vector_Vector3d& new_points)
override;
293 void reset()
override;
333 bool gridToWorld(
int x,
int y,
int z,
double& world_x,
double& world_y,
double& world_z)
const override;
334 bool worldToGrid(
double world_x,
double world_y,
double world_z,
int&
x,
int&
y,
int&
z)
const override;
375 return max_distance_;
391 return voxel_grid_->getCell(
x,
y,
z);
420 return ncell == cell ? nullptr : ncell;
427 return ncell == cell ? nullptr : ncell;
446 return max_distance_sq_;
451 typedef std::set<Eigen::Vector3i, CompareEigenVector3i, Eigen::aligned_allocator<Eigen::Vector3i>> VoxelSet;
480 void propagatePositive();
488 void propagateNegative();
509 int getDirectionNumber(
int dx,
int dy,
int dz)
const;
519 Eigen::Vector3i getLocationDifference(
int directionNumber)
const;
526 void initNeighborhoods();
533 void print(
const VoxelSet& set);
540 void print(
const EigenSTL::vector_Vector3d& points);
542 bool propagate_negative_;
547 std::vector<EigenSTL::vector_Vector3i> bucket_queue_;
552 std::vector<EigenSTL::vector_Vector3i> negative_bucket_queue_;
558 double max_distance_;
559 int max_distance_sq_;
561 std::vector<double> sqrt_table_;
575 std::vector<std::vector<EigenSTL::vector_Vector3i>> neighborhoods_;
584 : distance_square_(distance_square), negative_distance_square_(negative_distance_squared)
600 return sqrt_table_[
object.distance_square_] - sqrt_table_[
object.negative_distance_square_];
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
DistanceField is an abstract base class for computing distances from sets of 3D obstacle points....
A DistanceField implementation that uses a vector propagation method. Distances propagate outward fro...
void addPointsToField(const EigenSTL::vector_Vector3d &points) override
Add a set of obstacle points to the distance field, updating distance values accordingly....
void reset() override
Resets the entire distance field to max_distance for positive values and zero for negative values.
int getXNumCells() const override
Gets the number of cells along the X axis.
bool readFromStream(std::istream &stream) override
Reads, parameterizes, and populates the distance field based on the supplied stream.
int getMaximumDistanceSquared() const
Gets the maximum distance squared value.
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...
int getZNumCells() const override
Gets the number of cells along the Z axis.
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...
void removePointsFromField(const EigenSTL::vector_Vector3d &points) override
Remove a set of obstacle points from the distance field, updating distance values accordingly.
double getUninitializedDistance() const override
Gets a distance value for an invalid cell.
double getDistance(double x, double y, double z) const override
Get the distance value associated with the cell indicated by the world coordinate....
int getYNumCells() const override
Gets the number of cells along the Y axis.
const PropDistanceFieldVoxel & getCell(int x, int y, int z) const
Gets full cell data given an index.
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...
bool writeToStream(std::ostream &stream) const override
Writes the contents of the distance field to the supplied stream.
const PropDistanceFieldVoxel * getNearestCell(int x, int y, int z, double &dist, Eigen::Vector3i &pos) const
Gets nearest surface cell and returns distance to it.
~PropagationDistanceField() override
Empty destructor.
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...
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...
VoxelGrid holds a dense 3D, axis-aligned set of data at a given resolution, where the data is supplie...
std::vector< Eigen::Vector3i, Eigen::aligned_allocator< Eigen::Vector3i > > vector_Vector3i
Namespace for holding classes that generate distance fields.
Struct for sorting type Eigen::Vector3i for use in sorted std containers. Sorts in z order,...
bool operator()(const Eigen::Vector3i &loc_1, const Eigen::Vector3i &loc_2) const
Structure that holds voxel information for the DistanceField. Will be used in VoxelGrid.
Eigen::Vector3i closest_point_
Closest occupied cell.
Eigen::Vector3i closest_negative_point_
Closest unoccupied cell.
int update_direction_
Direction from which this voxel was updated for occupied distance propagation.
static const int UNINITIALIZED
Value that represents an uninitialized voxel.
int negative_update_direction_
Direction from which this voxel was updated for negative distance propagation.
int negative_distance_square_
Distance in cells to the nearest unoccupied cell, squared.
PropDistanceFieldVoxel()
Constructor. All fields left uninitialized.
int distance_square_
Distance in cells to the closest obstacle, squared.