A VoxelGrid that can convert a set of obstacle points into a distance field. More...
#include <distance_field.h>
Public Member Functions | |
void | addCollisionMapToField (const arm_navigation_msgs::CollisionMap &collision_map) |
Adds the points in a collision map to the distance field. | |
virtual void | addPointsToField (const std::vector< tf::Vector3 > &points)=0 |
Add (and expand) a set of points to the distance field. | |
DistanceField (double size_x, double size_y, double size_z, double resolution, double origin_x, double origin_y, double origin_z, T default_object) | |
Constructor for the VoxelGrid. | |
double | getDistance (double x, double y, double z) const |
Gets the distance to the closest obstacle at the given location. | |
double | getDistanceFromCell (int x, int y, int z) const |
Gets the distance to the closest obstacle at the given integer cell location. | |
double | getDistanceGradient (double x, double y, double z, double &gradient_x, double &gradient_y, double &gradient_z) const |
Gets the distance at a location and the gradient of the field. | |
void | getGradientMarkers (double min_radius, double max_radius, const std::string &frame_id, const ros::Time stamp, std::vector< visualization_msgs::Marker > &markers) |
Get an array of markers that can be published to rviz. | |
void | getIsoSurfaceMarkers (double min_radius, double max_radius, const std::string &frame_id, const ros::Time stamp, const tf::Transform &cur, visualization_msgs::Marker &marker) |
Get an iso-surface for visualizaion in rviz. | |
void | getPlaneMarkers (PlaneVisualizationType type, double length, double width, double height, tf::Vector3 origin, const std::string &frame_id, const ros::Time stamp, visualization_msgs::Marker &marker) |
Gets a set of markers to rviz along the specified plane. | |
virtual void | reset ()=0 |
Resets the distance field to the max_distance. | |
virtual | ~DistanceField () |
Protected Member Functions | |
virtual double | getDistance (const T &object) const =0 |
Private Attributes | |
int | inv_twice_resolution_ |
A VoxelGrid that can convert a set of obstacle points into a distance field.
It computes the distance transform of the input points, and stores the distance to the closest obstacle in each voxel. Also available is the location of the closest point, and the gradient of the field at a point. Expansion of obstacles is performed upto a given radius.
This is an abstract base class, current implementations include PropagationDistanceField and PFDistanceField.
Definition at line 74 of file distance_field.h.
distance_field::DistanceField< T >::DistanceField | ( | double | size_x, |
double | size_y, | ||
double | size_z, | ||
double | resolution, | ||
double | origin_x, | ||
double | origin_y, | ||
double | origin_z, | ||
T | default_object | ||
) |
Constructor for the VoxelGrid.
size_x | Size (x axis) of the container in meters |
size_y | Size (y axis) of the container in meters |
size_z | Size (z axis) of the container in meters |
resolution,: | resolution (size of a single cell) in meters |
origin_x | Origin (x axis) of the container |
origin_y | Origin (y axis) of the container |
origin_z | Origin (z axis) of the container |
default_object | The object to return for an out-of-bounds query |
Definition at line 182 of file distance_field.h.
distance_field::DistanceField< T >::~DistanceField | ( | ) | [virtual] |
Definition at line 176 of file distance_field.h.
void distance_field::DistanceField< T >::addCollisionMapToField | ( | const arm_navigation_msgs::CollisionMap & | collision_map | ) |
Adds the points in a collision map to the distance field.
Definition at line 344 of file distance_field.h.
virtual void distance_field::DistanceField< T >::addPointsToField | ( | const std::vector< tf::Vector3 > & | points | ) | [pure virtual] |
Add (and expand) a set of points to the distance field.
This function will incrementally add the given points and update the distance field correspondingly. Use the reset() function if you need to remove all points and start afresh.
Implemented in distance_field::SignedPropagationDistanceField, and distance_field::PropagationDistanceField.
double distance_field::DistanceField< T >::getDistance | ( | double | x, |
double | y, | ||
double | z | ||
) | const |
Gets the distance to the closest obstacle at the given location.
Definition at line 190 of file distance_field.h.
virtual double distance_field::DistanceField< T >::getDistance | ( | const T & | object | ) | const [protected, pure virtual] |
double distance_field::DistanceField< T >::getDistanceFromCell | ( | int | x, |
int | y, | ||
int | z | ||
) | const |
Gets the distance to the closest obstacle at the given integer cell location.
Definition at line 221 of file distance_field.h.
double distance_field::DistanceField< T >::getDistanceGradient | ( | double | x, |
double | y, | ||
double | z, | ||
double & | gradient_x, | ||
double & | gradient_y, | ||
double & | gradient_z | ||
) | const |
Gets the distance at a location and the gradient of the field.
Definition at line 196 of file distance_field.h.
void distance_field::DistanceField< T >::getGradientMarkers | ( | double | min_radius, |
double | max_radius, | ||
const std::string & | frame_id, | ||
const ros::Time | stamp, | ||
std::vector< visualization_msgs::Marker > & | markers | ||
) |
Get an array of markers that can be published to rviz.
Gets the gradient of the distance field as visualization markers for rviz.
markers | the marker array to be published |
Definition at line 279 of file distance_field.h.
void distance_field::DistanceField< T >::getIsoSurfaceMarkers | ( | double | min_radius, |
double | max_radius, | ||
const std::string & | frame_id, | ||
const ros::Time | stamp, | ||
const tf::Transform & | cur, | ||
visualization_msgs::Marker & | marker | ||
) |
Get an iso-surface for visualizaion in rviz.
Gets an iso-surface containing points between min_radius and max_radius as visualization markers.
marker | the marker to be published |
Definition at line 227 of file distance_field.h.
void distance_field::DistanceField< T >::getPlaneMarkers | ( | distance_field::PlaneVisualizationType | type, |
double | length, | ||
double | width, | ||
double | height, | ||
tf::Vector3 | origin, | ||
const std::string & | frame_id, | ||
const ros::Time | stamp, | ||
visualization_msgs::Marker & | marker | ||
) |
Gets a set of markers to rviz along the specified plane.
type | the plane to show (XZ, XY, YZ) |
length | the size along the first axis in meters. |
width | the size along the second axis in meters. |
height | the position along the orthogonal axis to the plane, in meters. |
marker | the marker to be published |
Definition at line 361 of file distance_field.h.
virtual void distance_field::DistanceField< T >::reset | ( | ) | [pure virtual] |
Resets the distance field to the max_distance.
Implemented in distance_field::SignedPropagationDistanceField, distance_field::PropagationDistanceField, and distance_field::PFDistanceField.
int distance_field::DistanceField< T >::inv_twice_resolution_ [private] |
Definition at line 170 of file distance_field.h.