Classes | Namespaces | Typedefs | Functions
fcl/include/moveit/collision_detection_fcl/collision_common.h File Reference
#include <moveit/collision_detection/world.h>
#include <moveit/collision_detection/collision_env.h>
#include <moveit/macros/class_forward.h>
#include <moveit/collision_detection_fcl/fcl_compat.h>
#include <geometric_shapes/check_isometry.h>
#include <fcl/broadphase/broadphase_collision_manager.h>
#include <fcl/narrowphase/collision.h>
#include <fcl/narrowphase/distance.h>
#include <memory>
#include <set>
Include dependency graph for fcl/include/moveit/collision_detection_fcl/collision_common.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  collision_detection::CollisionData
 Data structure which is passed to the collision callback function of the collision manager. More...
 
struct  collision_detection::CollisionGeometryData
 Wrapper around world, link and attached objects' geometry data. More...
 
struct  collision_detection::DistanceData
 Data structure which is passed to the distance callback function of the collision manager. More...
 
struct  collision_detection::FCLGeometry
 Bundles the CollisionGeometryData and FCL collision geometry representation into a single class. More...
 
struct  collision_detection::FCLManager
 Bundles an FCLObject and a broadphase FCL collision manager. More...
 
struct  collision_detection::FCLObject
 A general high-level object which consists of multiple FCLCollisionObjects. It is the top level data structure which is used in the collision checking process. More...
 

Namespaces

 collision_detection
 

Typedefs

typedef std::shared_ptr< const fcl::CollisionObjectdcollision_detection::FCLCollisionObjectConstPtr
 
typedef std::shared_ptr< fcl::CollisionObjectdcollision_detection::FCLCollisionObjectPtr
 

Functions

void collision_detection::cleanCollisionGeometryCache ()
 Increases the counter of the caches which can trigger the cleaning of expired entries from them. More...
 
bool collision_detection::collisionCallback (fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data)
 Callback function used by the FCLManager used for each pair of collision objects to calculate object contact information. More...
 
FCLGeometryConstPtr collision_detection::createCollisionGeometry (const shapes::ShapeConstPtr &shape, const moveit::core::AttachedBody *ab, int shape_index)
 Create new FCLGeometry object out of attached body. More...
 
FCLGeometryConstPtr collision_detection::createCollisionGeometry (const shapes::ShapeConstPtr &shape, const moveit::core::LinkModel *link, int shape_index)
 Create new FCLGeometry object out of robot link model. More...
 
FCLGeometryConstPtr collision_detection::createCollisionGeometry (const shapes::ShapeConstPtr &shape, const World::Object *obj)
 Create new FCLGeometry object out of a world object. More...
 
FCLGeometryConstPtr collision_detection::createCollisionGeometry (const shapes::ShapeConstPtr &shape, double scale, double padding, const moveit::core::AttachedBody *ab, int shape_index)
 Create new scaled and / or padded FCLGeometry object out of an attached body. More...
 
FCLGeometryConstPtr collision_detection::createCollisionGeometry (const shapes::ShapeConstPtr &shape, double scale, double padding, const moveit::core::LinkModel *link, int shape_index)
 Create new scaled and / or padded FCLGeometry object out of robot link model. More...
 
FCLGeometryConstPtr collision_detection::createCollisionGeometry (const shapes::ShapeConstPtr &shape, double scale, double padding, const World::Object *obj)
 Create new scaled and / or padded FCLGeometry object out of an world object. More...
 
bool collision_detection::distanceCallback (fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data, double &min_dist)
 Callback function used by the FCLManager used for each pair of collision objects to calculate collisions and distances. More...
 
void collision_detection::fcl2contact (const fcl::Contactd &fc, Contact &c)
 Transforms an FCL contact into a MoveIt contact point. More...
 
void collision_detection::fcl2costsource (const fcl::CostSourced &fcs, CostSource &cs)
 Transforms the FCL internal representation to the MoveIt CostSource data structure. More...
 
 collision_detection::MOVEIT_STRUCT_FORWARD (CollisionGeometryData)
 
 collision_detection::MOVEIT_STRUCT_FORWARD (FCLGeometry)
 
fcl::Transform3d collision_detection::transform2fcl (const Eigen::Isometry3d &b)
 Transforms an Eigen Isometry3d to FCL coordinate transformation. More...
 
void collision_detection::transform2fcl (const Eigen::Isometry3d &b, fcl::Transform3d &f)
 Transforms an Eigen Isometry3d to FCL coordinate transformation. More...
 


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Apr 18 2024 02:23:41