dart
FCLCollisionDetector.hpp
1 /*
2  * Copyright (c) 2011-2021, 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>
37 #include "dart/dynamics/CollisionDetector.hpp"
38 #include "dart/dynamics/fcl/FCLTypes.hpp"
39 
40 namespace dart {
41 namespace collision {
42 
43 class FCLCollisionObject;
44 
46 {
47 public:
49 
50  static std::shared_ptr<FCLCollisionDetector> create();
51 
64  {
65  PRIMITIVE = 0,
66  MESH
67  };
68 
78  {
79  FCL = 0,
80  DART
81  };
82 
84  virtual ~FCLCollisionDetector();
85 
86  // Documentation inherited
87  std::shared_ptr<CollisionDetector> cloneWithoutCollisionObjects()
88  const 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 
137 protected:
140 
141  // Documentation inherited
142  std::unique_ptr<CollisionObject> createCollisionObject(
143  const dynamics::ShapeFrame* shapeFrame) override;
144 
145  void refreshCollisionObject(CollisionObject* object) override;
146 
149  std::shared_ptr<dart::collision::fcl::CollisionGeometry>
150  claimFCLCollisionGeometry(const dynamics::ConstShapePtr& shape);
151 
152 protected:
153  PrimitiveShape mPrimitiveShapeType;
154 
155  ContactPointComputationMethod mContactPointComputationMethod;
156 
157 private:
160  class FCLCollisionGeometryDeleter final
161  {
162  public:
163  FCLCollisionGeometryDeleter(
164  FCLCollisionDetector* cd, const dynamics::ConstShapePtr& shape);
165 
166  void operator()(dart::collision::fcl::CollisionGeometry* geom) const;
167 
168  private:
169  FCLCollisionDetector* mFCLCollisionDetector;
170 
171  dynamics::ConstShapePtr mShape;
172  };
173 
175  struct ShapeInfo final
176  {
178  std::weak_ptr<dart::collision::fcl::CollisionGeometry> mShape;
179 
181  std::size_t mLastKnownVersion;
182  };
183 
186  std::shared_ptr<dart::collision::fcl::CollisionGeometry>
187  createFCLCollisionGeometry(
188  const dynamics::ConstShapePtr& shape,
190  const FCLCollisionGeometryDeleter& deleter);
191 
192 private:
193  using ShapeMap = std::map<dynamics::ConstShapePtr, ShapeInfo>;
194 
195  ShapeMap mShapeMap;
196 
197  static Registrar<FCLCollisionDetector> mRegistrar;
198 };
199 
200 } // namespace collision
201 } // namespace dart
202 
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&#39;s contact point computation.
Definition: FCLCollisionDetector.hpp:77