moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
propagation_distance_field.h
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2009, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Mrinal Kalakrishnan, Ken Anderson */
36
37#pragma once
38
41#include <vector>
42#include <Eigen/Core>
43#include <set>
44#include <octomap/octomap.h>
45#include <rclcpp/rclcpp.hpp>
46
47namespace EigenSTL
48{
49typedef std::vector<Eigen::Vector3i, Eigen::aligned_allocator<Eigen::Vector3i>> vector_Vector3i;
50}
51
52namespace distance_field
53{
59{
60 bool operator()(const Eigen::Vector3i& loc_1, const Eigen::Vector3i& loc_2) const
61 {
62 if (loc_1.z() != loc_2.z())
63 {
64 return (loc_1.z() < loc_2.z());
65 }
66 else if (loc_1.y() != loc_2.y())
67 {
68 return (loc_1.y() < loc_2.y());
69 }
70 else if (loc_1.x() != loc_2.x())
71 {
72 return (loc_1.x() < loc_2.x());
73 }
74 return false;
75 }
76};
77
83{
90
104 PropDistanceFieldVoxel(int distance_sq_positive, int distance_sq_negative);
105
108 Eigen::Vector3i closest_point_;
109 Eigen::Vector3i closest_negative_point_;
114 static const int UNINITIALIZED = -1;
116};
117
145{
146public:
172 PropagationDistanceField(double size_x, double size_y, double size_z, double resolution, double origin_x,
173 double origin_y, double origin_z, double max_distance,
174 bool propagate_negative_distances = false);
175
198 PropagationDistanceField(const octomap::OcTree& octree, const octomap::point3d& bbx_min,
199 const octomap::point3d& bbx_max, double max_distance,
200 bool propagate_negative_distances = false);
201
223 PropagationDistanceField(std::istream& stream, double max_distance, bool propagate_negative_distances = false);
230 {
231 }
232
246 void addPointsToField(const EigenSTL::vector_Vector3d& points) override;
247
267 void removePointsFromField(const EigenSTL::vector_Vector3d& points) override;
268
291 void updatePointsInField(const EigenSTL::vector_Vector3d& old_points,
292 const EigenSTL::vector_Vector3d& new_points) override;
293
299 void reset() override;
300
316 double getDistance(double x, double y, double z) const override;
317
333 double getDistance(int x, int y, int z) const override;
334
335 bool isCellValid(int x, int y, int z) const override;
336 int getXNumCells() const override;
337 int getYNumCells() const override;
338 int getZNumCells() const override;
339 bool gridToWorld(int x, int y, int z, double& world_x, double& world_y, double& world_z) const override;
340 bool worldToGrid(double world_x, double world_y, double world_z, int& x, int& y, int& z) const override;
341
358 bool writeToStream(std::ostream& stream) const override;
359
376 bool readFromStream(std::istream& stream) override;
377
378 // passthrough docs to DistanceField
379 double getUninitializedDistance() const override
380 {
381 return max_distance_;
382 }
383
395 const PropDistanceFieldVoxel& getCell(int x, int y, int z) const
396 {
397 return voxel_grid_->getCell(x, y, z);
398 }
399
418 const PropDistanceFieldVoxel* getNearestCell(int x, int y, int z, double& dist, Eigen::Vector3i& pos) const
419 {
420 const PropDistanceFieldVoxel* cell = &voxel_grid_->getCell(x, y, z);
421 if (cell->distance_square_ > 0)
422 {
423 dist = sqrt_table_[cell->distance_square_];
424 pos = cell->closest_point_;
425 const PropDistanceFieldVoxel* ncell = &voxel_grid_->getCell(pos.x(), pos.y(), pos.z());
426 return ncell == cell ? nullptr : ncell;
427 }
428 if (cell->negative_distance_square_ > 0)
429 {
430 dist = -sqrt_table_[cell->negative_distance_square_];
431 pos = cell->closest_negative_point_;
432 const PropDistanceFieldVoxel* ncell = &voxel_grid_->getCell(pos.x(), pos.y(), pos.z());
433 return ncell == cell ? nullptr : ncell;
434 }
435 dist = 0.0;
436 pos.x() = x;
437 pos.y() = y;
438 pos.z() = z;
439 return nullptr;
440 }
441
451 {
452 return max_distance_sq_;
453 }
454
455private:
457 typedef std::set<Eigen::Vector3i, CompareEigenVector3i, Eigen::aligned_allocator<Eigen::Vector3i>> VoxelSet;
464 void initialize();
465
471 void addNewObstacleVoxels(const EigenSTL::vector_Vector3i& voxel_points);
472
478 void removeObstacleVoxels(const EigenSTL::vector_Vector3i& voxel_points);
479
486 void propagatePositive();
487
494 void propagateNegative();
495
503 virtual double getDistance(const PropDistanceFieldVoxel& object) const;
504
515 int getDirectionNumber(int dx, int dy, int dz) const;
516
525 Eigen::Vector3i getLocationDifference(int directionNumber) const;
526
532 void initNeighborhoods();
533
539 void print(const VoxelSet& set);
540
546 void print(const EigenSTL::vector_Vector3d& points);
547
548 bool propagate_negative_;
553 std::vector<EigenSTL::vector_Vector3i> bucket_queue_;
558 std::vector<EigenSTL::vector_Vector3i> negative_bucket_queue_;
564 double max_distance_;
565 int max_distance_sq_;
567 std::vector<double> sqrt_table_;
581 std::vector<std::vector<EigenSTL::vector_Vector3i>> neighborhoods_;
582
583 EigenSTL::vector_Vector3i direction_number_to_direction_;
585};
586
588
599
603
604inline double PropagationDistanceField::getDistance(const PropDistanceFieldVoxel& object) const
605{
606 return sqrt_table_[object.distance_square_] - sqrt_table_[object.negative_distance_square_];
607}
608} // namespace distance_field
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...
const PropDistanceFieldVoxel & getCell(int x, int y, int z) const
Gets full cell data given an index.
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.
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.
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...
const PropDistanceFieldVoxel * getNearestCell(int x, int y, int z, double &dist, Eigen::Vector3i &pos) const
Gets nearest surface cell and returns distance to it.
VoxelGrid holds a dense 3D, axis-aligned set of data at a given resolution, where the data is supplie...
Definition voxel_grid.h:62
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.