33 #ifndef DART_COLLISION_FCL_FCLCOLLISIONDETECTOR_HPP_
34 #define DART_COLLISION_FCL_FCLCOLLISIONDETECTOR_HPP_
43 class FCLCollisionObject;
50 static std::shared_ptr<FCLCollisionDetector>
create();
91 const std::string&
getType()
const override;
193 using ShapeMap = std::map<dynamics::ConstShapePtr, ShapeInfo>;
const CollisionOption & option
Collision option of DART.
Definition: FCLCollisionDetector.cpp:157
CollisionResult * result
Collision result of DART.
Definition: FCLCollisionDetector.cpp:160
std::string type
Definition: SdfParser.cpp:82
Definition: CollisionDetector.hpp:58
virtual std::unique_ptr< CollisionGroup > createCollisionGroup()=0
Create a collision group.
Definition: CollisionGroup.hpp:53
Definition: CollisionObject.hpp:45
Definition: CollisionResult.hpp:52
This deleter is responsible for deleting fcl::CollisionGeometry and removing it from mShapeMap when i...
Definition: FCLCollisionDetector.hpp:161
FCLCollisionGeometryDeleter(FCLCollisionDetector *cd, const dynamics::ConstShapePtr &shape)
Definition: FCLCollisionDetector.cpp:1086
void operator()(dart::collision::fcl::CollisionGeometry *geom) const
Definition: FCLCollisionDetector.cpp:1095
dynamics::ConstShapePtr mShape
Definition: FCLCollisionDetector.hpp:171
FCLCollisionDetector * mFCLCollisionDetector
Definition: FCLCollisionDetector.hpp:169
Definition: FCLCollisionDetector.hpp:46
const std::string & getType() const override
Return collision detection engine type as a std::string.
Definition: FCLCollisionDetector.cpp:635
ContactPointComputationMethod mContactPointComputationMethod
Definition: FCLCollisionDetector.hpp:155
FCLCollisionDetector()
Constructor.
Definition: FCLCollisionDetector.cpp:832
void setContactPointComputationMethod(ContactPointComputationMethod method)
Set contact point computation method.
Definition: FCLCollisionDetector.cpp:807
ShapeMap mShapeMap
Definition: FCLCollisionDetector.hpp:195
void setPrimitiveShapeType(PrimitiveShape type)
Set primitive shape type.
Definition: FCLCollisionDetector.cpp:783
virtual ~FCLCollisionDetector()
Constructor.
Definition: FCLCollisionDetector.cpp:622
static const std::string & getStaticType()
Get collision detector type for this class.
Definition: FCLCollisionDetector.cpp:641
std::unique_ptr< CollisionObject > createCollisionObject(const dynamics::ShapeFrame *shapeFrame) override
Create CollisionObject.
Definition: FCLCollisionDetector.cpp:841
fcl_shared_ptr< dart::collision::fcl::CollisionGeometry > createFCLCollisionGeometry(const dynamics::ConstShapePtr &shape, FCLCollisionDetector::PrimitiveShape type, const FCLCollisionGeometryDeleter &deleter)
Create fcl::CollisionGeometry with the custom deleter FCLCollisionGeometryDeleter.
Definition: FCLCollisionDetector.cpp:889
static std::shared_ptr< FCLCollisionDetector > create()
Definition: FCLCollisionDetector.cpp:616
std::map< dynamics::ConstShapePtr, ShapeInfo > ShapeMap
Definition: FCLCollisionDetector.hpp:193
bool collide(CollisionGroup *group, const CollisionOption &option=CollisionOption(false, 1u, nullptr), CollisionResult *result=nullptr) override
Perform collision check for a single group.
Definition: FCLCollisionDetector.cpp:669
PrimitiveShape
Whether to use analytic collision checking for primitive shapes.
Definition: FCLCollisionDetector.hpp:64
@ PRIMITIVE
Definition: FCLCollisionDetector.hpp:65
@ MESH
Definition: FCLCollisionDetector.hpp:66
ContactPointComputationMethod
Whether to use FCL's contact point computation.
Definition: FCLCollisionDetector.hpp:78
@ FCL
Definition: FCLCollisionDetector.hpp:79
@ DART
Definition: FCLCollisionDetector.hpp:80
PrimitiveShape mPrimitiveShapeType
Definition: FCLCollisionDetector.hpp:153
void refreshCollisionObject(CollisionObject *object) override
Update the collision geometry of a ShapeFrame.
Definition: FCLCollisionDetector.cpp:851
double distance(CollisionGroup *group, const DistanceOption &option=DistanceOption(false, 0.0, nullptr), DistanceResult *result=nullptr) override
Get the minimum signed distance between the Shape pairs in the given CollisionGroup.
Definition: FCLCollisionDetector.cpp:732
static Registrar< FCLCollisionDetector > mRegistrar
Definition: FCLCollisionDetector.hpp:197
std::unique_ptr< CollisionGroup > createCollisionGroup() override
Create a collision group.
Definition: FCLCollisionDetector.cpp:648
PrimitiveShape getPrimitiveShapeType() const
Get primitive shape type.
Definition: FCLCollisionDetector.cpp:801
ContactPointComputationMethod getContactPointComputationMethod() const
Get contact point computation method.
Definition: FCLCollisionDetector.cpp:826
std::shared_ptr< CollisionDetector > cloneWithoutCollisionObjects() const override
Create a clone of this CollisionDetector.
Definition: FCLCollisionDetector.cpp:629
fcl_shared_ptr< dart::collision::fcl::CollisionGeometry > claimFCLCollisionGeometry(const dynamics::ConstShapePtr &shape)
Return fcl::CollisionGeometry associated with give Shape.
Definition: FCLCollisionDetector.cpp:861
Helper class to register a object creator function to the Singleton.
Definition: Factory.hpp:125
Definition: ShapeFrame.hpp:192
boost::weak_ptr< T > fcl_weak_ptr
Definition: BackwardCompatibility.hpp:108
boost::shared_ptr< T > fcl_shared_ptr
Definition: BackwardCompatibility.hpp:106
::fcl::CollisionGeometry CollisionGeometry
Definition: BackwardCompatibility.hpp:162
std::shared_ptr< const Shape > ConstShapePtr
Definition: SmartPointer.hpp:81
Definition: BulletCollisionDetector.cpp:65
Definition: CollisionOption.hpp:45
Definition: DistanceOption.hpp:45
Definition: DistanceResult.hpp:47
Information for a shape that was generated by this collision detector.
Definition: FCLCollisionDetector.hpp:176
fcl_weak_ptr< dart::collision::fcl::CollisionGeometry > mShape
A weak reference to the shape.
Definition: FCLCollisionDetector.hpp:178
std::size_t mLastKnownVersion
The last version of the shape, as known by this collision detector.
Definition: FCLCollisionDetector.hpp:181