Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
collision_detection Namespace Reference

Generic interface to collision detection. More...

Namespaces

 AllowedCollision
 Any pair of bodies can have a collision state associated to it.
 
 BodyTypes
 The types of bodies that are considered for collision.
 
 DistanceRequestTypes
 

Classes

class  AllowedCollisionMatrix
 Definition of a structure for the allowed collision matrix. All elements in the collision world are referred to by their names. This class represents which collisions are allowed to happen and which are not. More...
 
class  BodyDecomposition
 
struct  BodyDecompositionCache
 
struct  CollisionData
 
class  CollisionDetectorAllocator
 An allocator for a compatible CollisionWorld/CollisionRobot pair. More...
 
class  CollisionDetectorAllocatorAllValid
 An allocator for AllValid collision detectors. More...
 
class  CollisionDetectorAllocatorDistanceField
 An allocator for Distance Field collision detectors. More...
 
class  CollisionDetectorAllocatorFCL
 An allocator for FCL collision detectors. More...
 
class  CollisionDetectorAllocatorHybrid
 An allocator for Hybrid collision detectors. More...
 
class  CollisionDetectorAllocatorTemplate
 Template class to make it easy to create an allocator for a specific CollisionWorld/CollisionRobot pair. More...
 
struct  CollisionGeometryData
 
class  CollisionPlugin
 Plugin API for loading a custom collision detection robot/world. More...
 
struct  CollisionRequest
 Representation of a collision checking request. More...
 
struct  CollisionResult
 Representation of a collision checking result. More...
 
class  CollisionRobot
 This class represents a collision model of the robot and can be used for self collision checks (to check if the robot is in collision with itself) or in collision checks with a different robot. Collision checks with the environment are performed using the CollisionWorld class. More...
 
class  CollisionRobotAllValid
 
class  CollisionRobotDistanceField
 
class  CollisionRobotDistanceFieldROS
 
class  CollisionRobotFCL
 
class  CollisionRobotHybrid
 
class  CollisionRobotHybridROS
 
struct  CollisionSphere
 
class  CollisionWorld
 Perform collision checking with the environment. The collision world maintains a representation of the environment that the robot is operating in. More...
 
class  CollisionWorldAllValid
 
class  CollisionWorldDistanceField
 
class  CollisionWorldFCL
 
class  CollisionWorldHybrid
 
struct  Contact
 Definition of a contact point. More...
 
struct  CostSource
 When collision costs are computed, this structure contains information about the partial cost incurred in a particular volume. More...
 
struct  DistanceData
 
struct  DistanceFieldCacheEntry
 
struct  DistanceRequest
 
struct  DistanceResult
 
struct  DistanceResultsData
 
struct  FCLGeometry
 
struct  FCLManager
 
struct  FCLObject
 
struct  FCLShapeCache
 
struct  GradientInfo
 
struct  GroupStateRepresentation
 
struct  IfSameType
 
struct  IfSameType< T, T >
 
class  PosedBodyPointDecomposition
 
class  PosedBodyPointDecompositionVector
 
class  PosedBodySphereDecomposition
 
class  PosedBodySphereDecompositionVector
 
class  PosedDistanceField
 
struct  ProximityInfo
 
class  World
 Maintain a representation of the environment. More...
 
class  WorldDiff
 Maintain a diff list of changes that have happened to a World. More...
 

Typedefs

typedef BodyTypes::Type BodyType
 The types of bodies that are considered for collision. More...
 
typedef boost::function< bool(collision_detection::Contact &)> DecideContactFn
 Signature of predicate that decides whether a contact is allowed or not (when AllowedCollision::Type is CONDITIONAL) More...
 
typedef std::map< const std::pair< std::string, std::string >, std::vector< DistanceResultsData > > DistanceMap
 
typedef DistanceRequestTypes::DistanceRequestType DistanceRequestType
 
typedef std::shared_ptr< const fcl::CollisionObject > FCLCollisionObjectConstPtr
 
typedef std::shared_ptr< fcl::CollisionObject > FCLCollisionObjectPtr
 

Enumerations

enum  CollisionType { NONE = 0, SELF = 1, INTRA = 2, ENVIRONMENT = 3 }
 

Functions

static bool andDecideContact (const DecideContactFn &f1, const DecideContactFn &f2, Contact &contact)
 
void cleanCollisionGeometryCache ()
 
bool collisionCallback (fcl::CollisionObject *o1, fcl::CollisionObject *o2, void *data)
 
void contactToMsg (const Contact &contact, moveit_msgs::ContactInformation &msg)
 
void costSourceToMsg (const CostSource &cost_source, moveit_msgs::CostSource &msg)
 
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, const robot_model::LinkModel *link, int shape_index)
 
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, const robot_state::AttachedBody *ab, int shape_index)
 
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, const World::Object *obj)
 
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, double scale, double padding, const robot_model::LinkModel *link, int shape_index)
 
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, double scale, double padding, const robot_state::AttachedBody *ab, int shape_index)
 
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, double scale, double padding, const World::Object *obj)
 
template<typename BV , typename T >
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, const T *data, int shape_index)
 
template<typename BV , typename T >
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, double scale, double padding, const T *data, int shape_index)
 
std::vector< CollisionSpheredetermineCollisionSpheres (const bodies::Body *body, Eigen::Affine3d &relativeTransform)
 
bool distanceCallback (fcl::CollisionObject *o1, fcl::CollisionObject *o2, void *data, double &min_dist)
 
bool doBoundingSpheresIntersect (const PosedBodySphereDecompositionConstPtr &p1, const PosedBodySphereDecompositionConstPtr &p2)
 
void fcl2contact (const fcl::Contact &fc, Contact &c)
 
void fcl2costsource (const fcl::CostSource &fcs, CostSource &cs)
 
PosedBodyPointDecompositionVectorPtr getAttachedBodyPointDecomposition (const robot_state::AttachedBody *att, double resolution)
 
PosedBodySphereDecompositionVectorPtr getAttachedBodySphereDecomposition (const robot_state::AttachedBody *att, double resolution)
 
BodyDecompositionCachegetBodyDecompositionCache ()
 
BodyDecompositionConstPtr getBodyDecompositionCacheEntry (const shapes::ShapeConstPtr &shape, double resolution)
 
void getBodySphereVisualizationMarkers (GroupStateRepresentationConstPtr &gsr, std::string reference_frame, visualization_msgs::MarkerArray &body_marker_array)
 
void getBodySphereVisualizationMarkers (GroupStateRepresentationPtr &gsr, std::string reference_frame, visualization_msgs::MarkerArray &body_marker_array)
 
void getCollisionMarkers (const std::string &frame_id, const std::string &ns, const ros::Duration &dur, const std::vector< PosedBodySphereDecompositionPtr > &posed_decompositions, const std::vector< PosedBodySphereDecompositionVectorPtr > &posed_vector_decompositions, const std::vector< GradientInfo > &gradients, visualization_msgs::MarkerArray &arr)
 
void getCollisionMarkersFromContacts (visualization_msgs::MarkerArray &arr, const std::string &frame_id, const CollisionResult::ContactMap &con, const std_msgs::ColorRGBA &color, const ros::Duration &lifetime, const double radius=0.035)
 
void getCollisionMarkersFromContacts (visualization_msgs::MarkerArray &arr, const std::string &frame_id, const CollisionResult::ContactMap &con)
 
PosedBodyPointDecompositionVectorPtr getCollisionObjectPointDecomposition (const collision_detection::World::Object &obj, double resolution)
 
bool getCollisionSphereCollision (const distance_field::DistanceField *distance_field, const std::vector< CollisionSphere > &sphere_list, const EigenSTL::vector_Vector3d &sphere_centers, double maximum_value, double tolerance)
 
bool getCollisionSphereCollision (const distance_field::DistanceField *distance_field, const std::vector< CollisionSphere > &sphere_list, const EigenSTL::vector_Vector3d &sphere_centers, double maximum_value, double tolerance, unsigned int num_coll, std::vector< unsigned int > &colls)
 
bool getCollisionSphereGradients (const distance_field::DistanceField *distance_field, const std::vector< CollisionSphere > &sphere_list, const EigenSTL::vector_Vector3d &sphere_centers, GradientInfo &gradient, const CollisionType &type, double tolerance, bool subtract_radii, double maximum_value, bool stop_at_first_collision)
 
void getCollisionSphereMarkers (const std_msgs::ColorRGBA &color, const std::string &frame_id, const std::string &ns, const ros::Duration &dur, const std::vector< PosedBodySphereDecompositionPtr > &posed_decompositions, visualization_msgs::MarkerArray &arr)
 
void getCostMarkers (visualization_msgs::MarkerArray &arr, const std::string &frame_id, std::set< CostSource > &cost_sources)
 
void getCostMarkers (visualization_msgs::MarkerArray &arr, const std::string &frame_id, std::set< CostSource > &cost_sources, const std_msgs::ColorRGBA &color, const ros::Duration &lifetime)
 
void getProximityGradientMarkers (const std::string &frame_id, const std::string &ns, const ros::Duration &dur, const std::vector< PosedBodySphereDecompositionPtr > &posed_decompositions, const std::vector< PosedBodySphereDecompositionVectorPtr > &posed_vector_decompositions, const std::vector< GradientInfo > &gradients, visualization_msgs::MarkerArray &arr)
 
bool getSensorPositioning (geometry_msgs::Point &point, const std::set< CostSource > &cost_sources)
 
template<typename BV , typename T >
FCLShapeCacheGetShapeCache ()
 
double getTotalCost (const std::set< CostSource > &cost_sources)
 
void intersectCostSources (std::set< CostSource > &cost_sources, const std::set< CostSource > &a, const std::set< CostSource > &b)
 
static bool loadLinkBodySphereDecompositions (ros::NodeHandle &nh, const planning_models::RobotModelConstPtr &kmodel, std::map< std::string, std::vector< collision_detection::CollisionSphere > > &link_body_spheres)
 
 MOVEIT_CLASS_FORWARD (CollisionPlugin)
 
 MOVEIT_CLASS_FORWARD (CollisionDetectorAllocator)
 
 MOVEIT_CLASS_FORWARD (WorldDiff)
 
 MOVEIT_CLASS_FORWARD (GroupStateRepresentation)
 
 MOVEIT_CLASS_FORWARD (CollisionRobot)
 
 MOVEIT_CLASS_FORWARD (DistanceFieldCacheEntry)
 
 MOVEIT_CLASS_FORWARD (CollisionWorld)
 
 MOVEIT_CLASS_FORWARD (AllowedCollisionMatrix)
 
 MOVEIT_CLASS_FORWARD (World)
 
 MOVEIT_CLASS_FORWARD (CollisionRobotDistanceField)
 
 MOVEIT_CLASS_FORWARD (BodyDecomposition)
 
 MOVEIT_STRUCT_FORWARD (CollisionGeometryData)
 
 MOVEIT_STRUCT_FORWARD (FCLGeometry)
 
int refineContactNormals (const World::ObjectConstPtr &object, CollisionResult &res, double cell_bbx_search_distance=1.0, double allowed_angle_divergence=0.0, bool estimate_depth=false, double iso_value=0.5, double metaball_radius_multiple=1.5)
 Re-proceses contact normals for an octomap by estimating a metaball iso-surface using the centers of occupied cells in a neighborhood of the contact point. More...
 
void removeCostSources (std::set< CostSource > &cost_sources, const std::set< CostSource > &cost_sources_to_remove, double overlap_fraction)
 
void removeOverlapping (std::set< CostSource > &cost_sources, double overlap_fraction)
 
void transform2fcl (const Eigen::Affine3d &b, fcl::Transform3f &f)
 
fcl::Transform3f transform2fcl (const Eigen::Affine3d &b)
 

Variables

static const double DEFAULT_COLLISION_TOLERANCE = 0.0
 
static const double DEFAULT_MAX_PROPOGATION_DISTANCE = .25
 
static const double DEFAULT_RESOLUTION = .02
 
static const double DEFAULT_SIZE_X = 3.0
 
static const double DEFAULT_SIZE_Y = 3.0
 
static const double DEFAULT_SIZE_Z = 4.0
 
static const bool DEFAULT_USE_SIGNED_DISTANCE_FIELD = false
 
const double EPSILON = 0.001f
 

Detailed Description

Generic interface to collision detection.

Typedef Documentation

The types of bodies that are considered for collision.

Definition at line 71 of file include/moveit/collision_detection/collision_common.h.

Signature of predicate that decides whether a contact is allowed or not (when AllowedCollision::Type is CONDITIONAL)

Definition at line 73 of file collision_matrix.h.

typedef std::map<const std::pair<std::string, std::string>, std::vector<DistanceResultsData> > collision_detection::DistanceMap
typedef std::shared_ptr<const fcl::CollisionObject> collision_detection::FCLCollisionObjectConstPtr
typedef std::shared_ptr<fcl::CollisionObject> collision_detection::FCLCollisionObjectPtr

Enumeration Type Documentation

Enumerator
NONE 
SELF 
INTRA 
ENVIRONMENT 

Definition at line 59 of file collision_distance_field_types.h.

Function Documentation

static bool collision_detection::andDecideContact ( const DecideContactFn f1,
const DecideContactFn f2,
Contact contact 
)
static

Definition at line 259 of file collision_matrix.cpp.

void collision_detection::cleanCollisionGeometryCache ( )

Definition at line 887 of file collision_common.cpp.

bool collision_detection::collisionCallback ( fcl::CollisionObject *  o1,
fcl::CollisionObject *  o2,
void *  data 
)

Definition at line 47 of file collision_common.cpp.

void collision_detection::contactToMsg ( const Contact contact,
moveit_msgs::ContactInformation &  msg 
)

Definition at line 273 of file collision_tools.cpp.

void collision_detection::costSourceToMsg ( const CostSource cost_source,
moveit_msgs::CostSource &  msg 
)

Definition at line 262 of file collision_tools.cpp.

FCLGeometryConstPtr collision_detection::createCollisionGeometry ( const shapes::ShapeConstPtr shape,
const robot_model::LinkModel link,
int  shape_index 
)

Definition at line 837 of file collision_common.cpp.

FCLGeometryConstPtr collision_detection::createCollisionGeometry ( const shapes::ShapeConstPtr shape,
const robot_state::AttachedBody ab,
int  shape_index 
)

Definition at line 843 of file collision_common.cpp.

FCLGeometryConstPtr collision_detection::createCollisionGeometry ( const shapes::ShapeConstPtr shape,
const World::Object obj 
)

Definition at line 849 of file collision_common.cpp.

FCLGeometryConstPtr collision_detection::createCollisionGeometry ( const shapes::ShapeConstPtr shape,
double  scale,
double  padding,
const robot_model::LinkModel link,
int  shape_index 
)

Definition at line 869 of file collision_common.cpp.

FCLGeometryConstPtr collision_detection::createCollisionGeometry ( const shapes::ShapeConstPtr shape,
double  scale,
double  padding,
const robot_state::AttachedBody ab,
int  shape_index 
)

Definition at line 875 of file collision_common.cpp.

FCLGeometryConstPtr collision_detection::createCollisionGeometry ( const shapes::ShapeConstPtr shape,
double  scale,
double  padding,
const World::Object obj 
)

Definition at line 881 of file collision_common.cpp.

template<typename BV , typename T >
FCLGeometryConstPtr collision_detection::createCollisionGeometry ( const shapes::ShapeConstPtr shape,
const T *  data,
int  shape_index 
)

Definition at line 636 of file collision_common.cpp.

template<typename BV , typename T >
FCLGeometryConstPtr collision_detection::createCollisionGeometry ( const shapes::ShapeConstPtr shape,
double  scale,
double  padding,
const T *  data,
int  shape_index 
)

Definition at line 855 of file collision_common.cpp.

std::vector< collision_detection::CollisionSphere > collision_detection::determineCollisionSpheres ( const bodies::Body body,
Eigen::Affine3d &  relativeTransform 
)

Definition at line 48 of file collision_distance_field_types.cpp.

bool collision_detection::distanceCallback ( fcl::CollisionObject *  o1,
fcl::CollisionObject *  o2,
void *  data,
double &  min_dist 
)

Definition at line 390 of file collision_common.cpp.

bool collision_detection::doBoundingSpheresIntersect ( const PosedBodySphereDecompositionConstPtr &  p1,
const PosedBodySphereDecompositionConstPtr &  p2 
)

Definition at line 397 of file collision_distance_field_types.cpp.

void collision_detection::fcl2contact ( const fcl::Contact &  fc,
Contact c 
)
inline
void collision_detection::fcl2costsource ( const fcl::CostSource &  fcs,
CostSource cs 
)
inline
PosedBodyPointDecompositionVectorPtr collision_detection::getAttachedBodyPointDecomposition ( const robot_state::AttachedBody att,
double  resolution 
)

Definition at line 117 of file collision_common_distance_field.cpp.

PosedBodySphereDecompositionVectorPtr collision_detection::getAttachedBodySphereDecomposition ( const robot_state::AttachedBody att,
double  resolution 
)

Definition at line 103 of file collision_common_distance_field.cpp.

BodyDecompositionCache& collision_detection::getBodyDecompositionCache ( )

Definition at line 59 of file collision_common_distance_field.cpp.

BodyDecompositionConstPtr collision_detection::getBodyDecompositionCacheEntry ( const shapes::ShapeConstPtr shape,
double  resolution 
)

Definition at line 65 of file collision_common_distance_field.cpp.

void collision_detection::getBodySphereVisualizationMarkers ( GroupStateRepresentationConstPtr &  gsr,
std::string  reference_frame,
visualization_msgs::MarkerArray &  body_marker_array 
)

Definition at line 131 of file collision_common_distance_field.cpp.

void collision_detection::getBodySphereVisualizationMarkers ( GroupStateRepresentationPtr &  gsr,
std::string  reference_frame,
visualization_msgs::MarkerArray &  body_marker_array 
)
void collision_detection::getCollisionMarkers ( const std::string &  frame_id,
const std::string &  ns,
const ros::Duration dur,
const std::vector< PosedBodySphereDecompositionPtr > &  posed_decompositions,
const std::vector< PosedBodySphereDecompositionVectorPtr > &  posed_vector_decompositions,
const std::vector< GradientInfo > &  gradients,
visualization_msgs::MarkerArray &  arr 
)

Definition at line 546 of file collision_distance_field_types.cpp.

void collision_detection::getCollisionMarkersFromContacts ( visualization_msgs::MarkerArray &  arr,
const std::string &  frame_id,
const CollisionResult::ContactMap con,
const std_msgs::ColorRGBA &  color,
const ros::Duration lifetime,
const double  radius = 0.035 
)

Definition at line 95 of file collision_tools.cpp.

void collision_detection::getCollisionMarkersFromContacts ( visualization_msgs::MarkerArray &  arr,
const std::string &  frame_id,
const CollisionResult::ContactMap con 
)

Definition at line 53 of file collision_tools.cpp.

PosedBodyPointDecompositionVectorPtr collision_detection::getCollisionObjectPointDecomposition ( const collision_detection::World::Object obj,
double  resolution 
)

Definition at line 89 of file collision_common_distance_field.cpp.

bool collision_detection::getCollisionSphereCollision ( const distance_field::DistanceField distance_field,
const std::vector< CollisionSphere > &  sphere_list,
const EigenSTL::vector_Vector3d sphere_centers,
double  maximum_value,
double  tolerance 
)

Definition at line 193 of file collision_distance_field_types.cpp.

bool collision_detection::getCollisionSphereCollision ( const distance_field::DistanceField distance_field,
const std::vector< CollisionSphere > &  sphere_list,
const EigenSTL::vector_Vector3d sphere_centers,
double  maximum_value,
double  tolerance,
unsigned int  num_coll,
std::vector< unsigned int > &  colls 
)

Definition at line 220 of file collision_distance_field_types.cpp.

bool collision_detection::getCollisionSphereGradients ( const distance_field::DistanceField distance_field,
const std::vector< CollisionSphere > &  sphere_list,
const EigenSTL::vector_Vector3d sphere_centers,
GradientInfo gradient,
const CollisionType type,
double  tolerance,
bool  subtract_radii,
double  maximum_value,
bool  stop_at_first_collision 
)

Definition at line 130 of file collision_distance_field_types.cpp.

void collision_detection::getCollisionSphereMarkers ( const std_msgs::ColorRGBA &  color,
const std::string &  frame_id,
const std::string &  ns,
const ros::Duration dur,
const std::vector< PosedBodySphereDecompositionPtr > &  posed_decompositions,
visualization_msgs::MarkerArray &  arr 
)

Definition at line 413 of file collision_distance_field_types.cpp.

void collision_detection::getCostMarkers ( visualization_msgs::MarkerArray &  arr,
const std::string &  frame_id,
std::set< CostSource > &  cost_sources 
)
Todo:
add a class for managing cost sources

Definition at line 42 of file collision_tools.cpp.

void collision_detection::getCostMarkers ( visualization_msgs::MarkerArray &  arr,
const std::string &  frame_id,
std::set< CostSource > &  cost_sources,
const std_msgs::ColorRGBA &  color,
const ros::Duration lifetime 
)

Definition at line 64 of file collision_tools.cpp.

void collision_detection::getProximityGradientMarkers ( const std::string &  frame_id,
const std::string &  ns,
const ros::Duration dur,
const std::vector< PosedBodySphereDecompositionPtr > &  posed_decompositions,
const std::vector< PosedBodySphereDecompositionVectorPtr > &  posed_vector_decompositions,
const std::vector< GradientInfo > &  gradients,
visualization_msgs::MarkerArray &  arr 
)

Definition at line 443 of file collision_distance_field_types.cpp.

bool collision_detection::getSensorPositioning ( geometry_msgs::Point &  point,
const std::set< CostSource > &  cost_sources 
)

Definition at line 134 of file collision_tools.cpp.

template<typename BV , typename T >
FCLShapeCache& collision_detection::GetShapeCache ( )

Definition at line 611 of file collision_common.cpp.

double collision_detection::getTotalCost ( const std::set< CostSource > &  cost_sources)

Definition at line 147 of file collision_tools.cpp.

void collision_detection::intersectCostSources ( std::set< CostSource > &  cost_sources,
const std::set< CostSource > &  a,
const std::set< CostSource > &  b 
)

Definition at line 155 of file collision_tools.cpp.

collision_detection::MOVEIT_CLASS_FORWARD ( CollisionPlugin  )
collision_detection::MOVEIT_CLASS_FORWARD ( CollisionDetectorAllocator  )
collision_detection::MOVEIT_CLASS_FORWARD ( WorldDiff  )
collision_detection::MOVEIT_CLASS_FORWARD ( GroupStateRepresentation  )
collision_detection::MOVEIT_CLASS_FORWARD ( CollisionRobot  )
collision_detection::MOVEIT_CLASS_FORWARD ( DistanceFieldCacheEntry  )
collision_detection::MOVEIT_CLASS_FORWARD ( CollisionWorld  )
collision_detection::MOVEIT_CLASS_FORWARD ( AllowedCollisionMatrix  )
collision_detection::MOVEIT_CLASS_FORWARD ( World  )
collision_detection::MOVEIT_CLASS_FORWARD ( CollisionRobotDistanceField  )
collision_detection::MOVEIT_CLASS_FORWARD ( BodyDecomposition  )
collision_detection::MOVEIT_STRUCT_FORWARD ( CollisionGeometryData  )
collision_detection::MOVEIT_STRUCT_FORWARD ( FCLGeometry  )
int collision_detection::refineContactNormals ( const World::ObjectConstPtr &  object,
CollisionResult res,
double  cell_bbx_search_distance = 1.0,
double  allowed_angle_divergence = 0.0,
bool  estimate_depth = false,
double  iso_value = 0.5,
double  metaball_radius_multiple = 1.5 
)

Re-proceses contact normals for an octomap by estimating a metaball iso-surface using the centers of occupied cells in a neighborhood of the contact point.

This is an implementation of the algorithm described in: A. Leeper, S. Chan, K. Salisbury. Point Clouds Can Be Represented as Implicit Surfaces for Constraint-Based Haptic Rendering. ICRA, May 2012, St Paul, MN. http://adamleeper.com/research/papers/2012_ICRA_leeper-chan-salisbury.pdf

Parameters
Theoctomap originally used for collision detection.
Thecollision result (which will get its normals updated)
Thedistance, as a multiple of the octomap cell size, from which to include neighboring cells.
Theminimum angle change required for a normal to be over-written
Whetherto request a depth estimate from the algorithm (experimental...)
Theiso-surface threshold value (0.5 is a reasonable default).
Themetaball radius, as a multiple of the octomap cell size (1.5 is a reasonable default)

Definition at line 61 of file collision_octomap_filter.cpp.

void collision_detection::removeCostSources ( std::set< CostSource > &  cost_sources,
const std::set< CostSource > &  cost_sources_to_remove,
double  overlap_fraction 
)

Definition at line 209 of file collision_tools.cpp.

void collision_detection::removeOverlapping ( std::set< CostSource > &  cost_sources,
double  overlap_fraction 
)

Definition at line 179 of file collision_tools.cpp.

void collision_detection::transform2fcl ( const Eigen::Affine3d &  b,
fcl::Transform3f &  f 
)
inline
fcl::Transform3f collision_detection::transform2fcl ( const Eigen::Affine3d &  b)
inline

Variable Documentation

const double collision_detection::DEFAULT_COLLISION_TOLERANCE = 0.0
static

Definition at line 54 of file collision_robot_distance_field.h.

const double collision_detection::DEFAULT_MAX_PROPOGATION_DISTANCE = .25
static

Definition at line 55 of file collision_robot_distance_field.h.

const double collision_detection::DEFAULT_RESOLUTION = .02
static

Definition at line 53 of file collision_robot_distance_field.h.

const double collision_detection::DEFAULT_SIZE_X = 3.0
static

Definition at line 49 of file collision_robot_distance_field.h.

const double collision_detection::DEFAULT_SIZE_Y = 3.0
static

Definition at line 50 of file collision_robot_distance_field.h.

const double collision_detection::DEFAULT_SIZE_Z = 4.0
static

Definition at line 51 of file collision_robot_distance_field.h.

const bool collision_detection::DEFAULT_USE_SIGNED_DISTANCE_FIELD = false
static

Definition at line 52 of file collision_robot_distance_field.h.

const double collision_detection::EPSILON = 0.001f

Definition at line 47 of file collision_robot_distance_field.cpp.



moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jul 10 2019 04:03:05