33 #ifndef DART_COLLISION_FCL_FCLCOLLISIONDETECTOR_HPP_ 34 #define DART_COLLISION_FCL_FCLCOLLISIONDETECTOR_HPP_ 37 #include "dart/dynamics/CollisionDetector.hpp" 38 #include "dart/dynamics/fcl/FCLTypes.hpp" 43 class FCLCollisionObject;
50 static std::shared_ptr<FCLCollisionDetector> create();
91 const std::string&
getType()
const override;
149 std::shared_ptr<dart::collision::fcl::CollisionGeometry>
160 class FCLCollisionGeometryDeleter final
163 FCLCollisionGeometryDeleter(
166 void operator()(dart::collision::fcl::CollisionGeometry* geom)
const;
171 dynamics::ConstShapePtr mShape;
175 struct ShapeInfo final
178 std::weak_ptr<dart::collision::fcl::CollisionGeometry> mShape;
181 std::size_t mLastKnownVersion;
186 std::shared_ptr<dart::collision::fcl::CollisionGeometry>
187 createFCLCollisionGeometry(
188 const dynamics::ConstShapePtr& shape,
190 const FCLCollisionGeometryDeleter& deleter);
193 using ShapeMap = std::map<dynamics::ConstShapePtr, ShapeInfo>;
203 #endif // DART_COLLISION_FCL_FCLCOLLISIONDETECTOR_HPP_ Helper class to register a object creator function to the Singleton.
Definition: Factory.hpp:124
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:733
PrimitiveShape
Whether to use analytic collision checking for primitive shapes.
Definition: FCLCollisionDetector.hpp:63
std::shared_ptr< dart::collision::fcl::CollisionGeometry > claimFCLCollisionGeometry(const dynamics::ConstShapePtr &shape)
Return fcl::CollisionGeometry associated with give Shape.
Definition: FCLCollisionDetector.cpp:862
std::shared_ptr< CollisionDetector > cloneWithoutCollisionObjects() const override
Create a clone of this CollisionDetector.
Definition: FCLCollisionDetector.cpp:630
Definition: DistanceResult.hpp:46
void setContactPointComputationMethod(ContactPointComputationMethod method)
Set contact point computation method.
Definition: FCLCollisionDetector.cpp:808
void setPrimitiveShapeType(PrimitiveShape type)
Set primitive shape type.
Definition: FCLCollisionDetector.cpp:784
Definition: Aspect.cpp:40
Definition: CollisionOption.hpp:44
Definition: CollisionResult.hpp:51
Definition: DistanceOption.hpp:44
Definition: CollisionObject.hpp:43
Definition: CollisionGroup.hpp:51
const std::string & getType() const override
Return collision detection engine type as a std::string.
Definition: FCLCollisionDetector.cpp:636
std::unique_ptr< CollisionObject > createCollisionObject(const dynamics::ShapeFrame *shapeFrame) override
Create CollisionObject.
Definition: FCLCollisionDetector.cpp:842
static const std::string & getStaticType()
Get collision detector type for this class.
Definition: FCLCollisionDetector.cpp:642
Definition: ShapeFrame.hpp:189
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:670
FCLCollisionDetector()
Constructor.
Definition: FCLCollisionDetector.cpp:833
Definition: CollisionDetector.hpp:56
PrimitiveShape getPrimitiveShapeType() const
Get primitive shape type.
Definition: FCLCollisionDetector.cpp:802
virtual ~FCLCollisionDetector()
Constructor.
Definition: FCLCollisionDetector.cpp:623
ContactPointComputationMethod getContactPointComputationMethod() const
Get contact point computation method.
Definition: FCLCollisionDetector.cpp:827
std::unique_ptr< CollisionGroup > createCollisionGroup() override
Create a collision group.
Definition: FCLCollisionDetector.cpp:649
void refreshCollisionObject(CollisionObject *object) override
Update the collision geometry of a ShapeFrame.
Definition: FCLCollisionDetector.cpp:852
virtual std::unique_ptr< CollisionGroup > createCollisionGroup()=0
Create a collision group.
Definition: FCLCollisionDetector.hpp:45
ContactPointComputationMethod
Whether to use FCL's contact point computation.
Definition: FCLCollisionDetector.hpp:77