DART 6.8.5
Loading...
Searching...
No Matches
FCLCollisionDetector.hpp
Go to the documentation of this file.
1/*
2 * Copyright (c) 2011-2019, The DART development contributors
3 * All rights reserved.
4 *
5 * The list of contributors can be found at:
6 * https://github.com/dartsim/dart/blob/master/LICENSE
7 *
8 * This file is provided under the following "BSD-style" License:
9 * Redistribution and use in source and binary forms, with or
10 * without modification, are permitted provided that the following
11 * conditions are met:
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
19 * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
20 * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
21 * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
23 * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
24 * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
25 * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
26 * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30 * POSSIBILITY OF SUCH DAMAGE.
31 */
32
33#ifndef DART_COLLISION_FCL_FCLCOLLISIONDETECTOR_HPP_
34#define DART_COLLISION_FCL_FCLCOLLISIONDETECTOR_HPP_
35
36#include <vector>
39
40namespace dart {
41namespace collision {
42
43class FCLCollisionObject;
44
46{
47public:
49
50 static std::shared_ptr<FCLCollisionDetector> create();
51
64 {
66 MESH
67 };
68
82
84 virtual ~FCLCollisionDetector();
85
86 // Documentation inherited
87 std::shared_ptr<CollisionDetector> cloneWithoutCollisionObjects() const
88 override;
89
90 // Documentation inherited
91 const std::string& getType() const override;
92
94 static const std::string& getStaticType();
95
96 // Documentation inherited
97 std::unique_ptr<CollisionGroup> createCollisionGroup() override;
98
99 // Documentation inherited
100 bool collide(
101 CollisionGroup* group,
102 const CollisionOption& option = CollisionOption(false, 1u, nullptr),
103 CollisionResult* result = nullptr) override;
104
105 // Documentation inherited
106 bool collide(
107 CollisionGroup* group1,
108 CollisionGroup* group2,
109 const CollisionOption& option = CollisionOption(false, 1u, nullptr),
110 CollisionResult* result = nullptr) override;
111
112 // Documentation inherited
113 double distance(
114 CollisionGroup* group,
115 const DistanceOption& option = DistanceOption(false, 0.0, nullptr),
116 DistanceResult* result = nullptr) override;
117
118 // Documentation inherited
119 double distance(
120 CollisionGroup* group1,
121 CollisionGroup* group2,
122 const DistanceOption& option = DistanceOption(false, 0.0, nullptr),
123 DistanceResult* result = nullptr) override;
124
127
130
133
136
137protected:
138
141
142 // Documentation inherited
143 std::unique_ptr<CollisionObject> createCollisionObject(
144 const dynamics::ShapeFrame* shapeFrame) override;
145
146 void refreshCollisionObject(CollisionObject* object) override;
147
151 const dynamics::ConstShapePtr& shape);
152
153protected:
154
156
158
159private:
160
179
189
193 const dynamics::ConstShapePtr& shape,
195 const FCLCollisionGeometryDeleter& deleter);
196
197private:
198
199 using ShapeMap = std::map<dynamics::ConstShapePtr, ShapeInfo>;
200
202
204};
205
206} // namespace collision
207} // namespace dart
208
209#endif // DART_COLLISION_FCL_FCLCOLLISIONDETECTOR_HPP_
boost::weak_ptr< T > fcl_weak_ptr
Definition BackwardCompatibility.hpp:101
boost::shared_ptr< T > fcl_shared_ptr
Definition BackwardCompatibility.hpp:100
const CollisionOption & option
Collision option of DART.
Definition FCLCollisionDetector.cpp:154
CollisionResult * result
Collision result of DART.
Definition FCLCollisionDetector.cpp:157
std::string type
Definition SdfParser.cpp:82
Definition CollisionDetector.hpp:56
virtual std::unique_ptr< CollisionGroup > createCollisionGroup()=0
Create a collision group.
Definition CollisionGroup.hpp:51
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:164
void operator()(dart::collision::fcl::CollisionGeometry *geom) const
Definition FCLCollisionDetector.cpp:1104
dynamics::ConstShapePtr mShape
Definition FCLCollisionDetector.hpp:176
FCLCollisionDetector * mFCLCollisionDetector
Definition FCLCollisionDetector.hpp:174
Definition FCLCollisionDetector.hpp:46
const std::string & getType() const override
Return collision detection engine type as a std::string.
Definition FCLCollisionDetector.cpp:676
ContactPointComputationMethod mContactPointComputationMethod
Definition FCLCollisionDetector.hpp:157
FCLCollisionDetector()
Constructor.
Definition FCLCollisionDetector.cpp:876
void setContactPointComputationMethod(ContactPointComputationMethod method)
Set contact point computation method.
Definition FCLCollisionDetector.cpp:851
ShapeMap mShapeMap
Definition FCLCollisionDetector.hpp:201
void setPrimitiveShapeType(PrimitiveShape type)
Set primitive shape type.
Definition FCLCollisionDetector.cpp:827
virtual ~FCLCollisionDetector()
Constructor.
Definition FCLCollisionDetector.cpp:663
static const std::string & getStaticType()
Get collision detector type for this class.
Definition FCLCollisionDetector.cpp:682
std::unique_ptr< CollisionObject > createCollisionObject(const dynamics::ShapeFrame *shapeFrame) override
Create CollisionObject.
Definition FCLCollisionDetector.cpp:885
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:934
static std::shared_ptr< FCLCollisionDetector > create()
Definition FCLCollisionDetector.cpp:657
std::map< dynamics::ConstShapePtr, ShapeInfo > ShapeMap
Definition FCLCollisionDetector.hpp:199
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:711
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:155
void refreshCollisionObject(CollisionObject *object) override
Update the collision geometry of a ShapeFrame.
Definition FCLCollisionDetector.cpp:895
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:774
static Registrar< FCLCollisionDetector > mRegistrar
Definition FCLCollisionDetector.hpp:203
std::unique_ptr< CollisionGroup > createCollisionGroup() override
Create a collision group.
Definition FCLCollisionDetector.cpp:690
PrimitiveShape getPrimitiveShapeType() const
Get primitive shape type.
Definition FCLCollisionDetector.cpp:845
ContactPointComputationMethod getContactPointComputationMethod() const
Get contact point computation method.
Definition FCLCollisionDetector.cpp:870
std::shared_ptr< CollisionDetector > cloneWithoutCollisionObjects() const override
Create a clone of this CollisionDetector.
Definition FCLCollisionDetector.cpp:670
fcl_shared_ptr< dart::collision::fcl::CollisionGeometry > claimFCLCollisionGeometry(const dynamics::ConstShapePtr &shape)
Return fcl::CollisionGeometry associated with give Shape.
Definition FCLCollisionDetector.cpp:906
Helper class to register a object creator function to the Singleton.
Definition Factory.hpp:121
Definition ShapeFrame.hpp:164
::fcl::CollisionGeometry CollisionGeometry
Definition BackwardCompatibility.hpp:153
std::shared_ptr< const Shape > ConstShapePtr
Definition SmartPointer.hpp:81
Definition BulletCollisionDetector.cpp:63
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:182
fcl_weak_ptr< dart::collision::fcl::CollisionGeometry > mShape
A weak reference to the shape.
Definition FCLCollisionDetector.hpp:184
std::size_t mLastKnownVersion
The last version of the shape, as known by this collision detector.
Definition FCLCollisionDetector.hpp:187