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

Namespaces

 AllowedCollision
 
 BodyTypes
 
 DistanceRequestTypes
 
 World
 

Classes

class  AllowedCollisionMatrix
 
class  BodyDecomposition
 
struct  BodyDecompositionCache
 
struct  CollisionData
 
class  CollisionDetectorAllocator
 
class  CollisionDetectorAllocatorAllValid
 
class  CollisionDetectorAllocatorDistanceField
 
class  CollisionDetectorAllocatorFCL
 
class  CollisionDetectorAllocatorHybrid
 
class  CollisionDetectorAllocatorTemplate
 
struct  CollisionGeometryData
 
class  CollisionPlugin
 
class  CollisionPluginLoader
 This is used to load the collision plugin. More...
 
struct  CollisionRequest
 
struct  CollisionResult
 
class  CollisionRobot
 
class  CollisionRobotAllValid
 
class  CollisionRobotDistanceField
 
class  CollisionRobotFCL
 
class  CollisionRobotHybrid
 
struct  CollisionSphere
 
class  CollisionWorld
 
class  CollisionWorldAllValid
 
class  CollisionWorldDistanceField
 
class  CollisionWorldFCL
 
class  CollisionWorldHybrid
 
struct  Contact
 
struct  CostSource
 
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
 
class  WorldDiff
 

Typedefs

typedef BodyTypes::Type BodyType
 
typedef boost::function< bool(collision_detection::Contact &)> DecideContactFn
 
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
 

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 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)
 
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, const robot_model::LinkModel *link, int shape_index)
 
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, const T *data, int shape_index)
 
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, double scale, double padding, const T *data, int shape_index)
 
FCLGeometryConstPtr createCollisionGeometry (const shapes::ShapeConstPtr &shape, const robot_state::AttachedBody *ab, 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)
 
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)
 
 MOVEIT_CLASS_FORWARD (CollisionDetectorAllocator)
 
 MOVEIT_CLASS_FORWARD (CollisionRobot)
 
 MOVEIT_CLASS_FORWARD (WorldDiff)
 
 MOVEIT_CLASS_FORWARD (CollisionPlugin)
 
 MOVEIT_CLASS_FORWARD (CollisionWorld)
 
 MOVEIT_CLASS_FORWARD (AllowedCollisionMatrix)
 
 MOVEIT_CLASS_FORWARD (World)
 
 MOVEIT_CLASS_FORWARD (GroupStateRepresentation)
 
 MOVEIT_CLASS_FORWARD (BodyDecomposition)
 
 MOVEIT_CLASS_FORWARD (CollisionRobotDistanceField)
 
 MOVEIT_CLASS_FORWARD (DistanceFieldCacheEntry)
 
 MOVEIT_STRUCT_FORWARD (FCLGeometry)
 
 MOVEIT_STRUCT_FORWARD (CollisionGeometryData)
 
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)
 
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
 
static const double DEFAULT_MAX_PROPOGATION_DISTANCE
 
static const double DEFAULT_RESOLUTION
 
static const double DEFAULT_SIZE_X
 
static const double DEFAULT_SIZE_Y
 
static const double DEFAULT_SIZE_Z
 
static const bool DEFAULT_USE_SIGNED_DISTANCE_FIELD
 
 ENVIRONMENT
 
const double EPSILON
 
 INTRA
 
 NONE
 
 SELF
 


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sun Oct 18 2020 13:17:34