Public Member Functions | Protected Member Functions | Private Attributes
distance_field::DistanceField< T > Class Template Reference

A VoxelGrid that can convert a set of obstacle points into a distance field. More...

#include <distance_field.h>

Inheritance diagram for distance_field::DistanceField< T >:
Inheritance graph
[legend]

List of all members.

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_

Detailed Description

template<typename T>
class distance_field::DistanceField< T >

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.


Constructor & Destructor Documentation

template<typename T>
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,
default_object 
)

Constructor for the VoxelGrid.

Parameters:
size_xSize (x axis) of the container in meters
size_ySize (y axis) of the container in meters
size_zSize (z axis) of the container in meters
resolution,:resolution (size of a single cell) in meters
origin_xOrigin (x axis) of the container
origin_yOrigin (y axis) of the container
origin_zOrigin (z axis) of the container
default_objectThe object to return for an out-of-bounds query

Definition at line 182 of file distance_field.h.

template<typename T >
distance_field::DistanceField< T >::~DistanceField ( ) [virtual]

Definition at line 176 of file distance_field.h.


Member Function Documentation

template<typename T >
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.

template<typename T>
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.

template<typename T >
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.

template<typename T>
virtual double distance_field::DistanceField< T >::getDistance ( const T &  object) const [protected, pure virtual]
template<typename T >
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.

template<typename T >
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.

template<typename T >
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.

Parameters:
markersthe marker array to be published

Definition at line 279 of file distance_field.h.

template<typename T >
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.

Parameters:
markerthe marker to be published

Definition at line 227 of file distance_field.h.

template<typename T >
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.

Parameters:
typethe plane to show (XZ, XY, YZ)
lengththe size along the first axis in meters.
widththe size along the second axis in meters.
heightthe position along the orthogonal axis to the plane, in meters.
markerthe marker to be published

Definition at line 361 of file distance_field.h.

template<typename T>
virtual void distance_field::DistanceField< T >::reset ( ) [pure virtual]

Member Data Documentation

template<typename T>
int distance_field::DistanceField< T >::inv_twice_resolution_ [private]

Definition at line 170 of file distance_field.h.


The documentation for this class was generated from the following file:


distance_field
Author(s): Mrinal Kalakrishnan / mail@mrinal.net
autogenerated on Fri Dec 6 2013 21:11:00