DART 6.12.2
Loading...
Searching...
No Matches
FCLCollisionDetector.hpp
Go to the documentation of this file.
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
40
41namespace dart {
42namespace collision {
43
44class FCLCollisionObject;
45
47{
48public:
50
51 static std::shared_ptr<FCLCollisionDetector> create();
52
65 {
67 MESH
68 };
69
83
85 virtual ~FCLCollisionDetector();
86
87 // Documentation inherited
88 std::shared_ptr<CollisionDetector> cloneWithoutCollisionObjects()
89 const override;
90
91 // Documentation inherited
92 const std::string& getType() const override;
93
95 static const std::string& getStaticType();
96
97 // Documentation inherited
98 std::unique_ptr<CollisionGroup> createCollisionGroup() override;
99
100 // Documentation inherited
101 bool collide(
102 CollisionGroup* group,
103 const CollisionOption& option = CollisionOption(false, 1u, nullptr),
104 CollisionResult* result = nullptr) override;
105
106 // Documentation inherited
107 bool collide(
108 CollisionGroup* group1,
109 CollisionGroup* group2,
110 const CollisionOption& option = CollisionOption(false, 1u, nullptr),
111 CollisionResult* result = nullptr) override;
112
113 // Documentation inherited
114 double distance(
115 CollisionGroup* group,
116 const DistanceOption& option = DistanceOption(false, 0.0, nullptr),
117 DistanceResult* result = nullptr) override;
118
119 // Documentation inherited
120 double distance(
121 CollisionGroup* group1,
122 CollisionGroup* group2,
123 const DistanceOption& option = DistanceOption(false, 0.0, nullptr),
124 DistanceResult* result = nullptr) override;
125
128
131
134
137
138protected:
141
142 // Documentation inherited
143 std::unique_ptr<CollisionObject> createCollisionObject(
144 const dynamics::ShapeFrame* shapeFrame) override;
145
146 void refreshCollisionObject(CollisionObject* object) override;
147
152
153protected:
155
157
158private:
174
184
189 const dynamics::ConstShapePtr& shape,
191 const FCLCollisionGeometryDeleter& deleter);
192
193private:
194 using ShapeMap = std::map<dynamics::ConstShapePtr, ShapeInfo>;
195
197
199};
200
201} // namespace collision
202} // namespace dart
203
204#endif // DART_COLLISION_FCL_FCLCOLLISIONDETECTOR_HPP_
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:54
Definition CollisionObject.hpp:45
Definition CollisionResult.hpp:53
This deleter is responsible for deleting fcl::CollisionGeometry and removing it from mShapeMap when i...
Definition FCLCollisionDetector.hpp:162
void operator()(dart::collision::fcl::CollisionGeometry *geom) const
Definition FCLCollisionDetector.cpp:1095
dynamics::ConstShapePtr mShape
Definition FCLCollisionDetector.hpp:172
FCLCollisionDetector * mFCLCollisionDetector
Definition FCLCollisionDetector.hpp:170
Definition FCLCollisionDetector.hpp:47
const std::string & getType() const override
Return collision detection engine type as a std::string.
Definition FCLCollisionDetector.cpp:635
ContactPointComputationMethod mContactPointComputationMethod
Definition FCLCollisionDetector.hpp:156
FCLCollisionDetector()
Constructor.
Definition FCLCollisionDetector.cpp:832
void setContactPointComputationMethod(ContactPointComputationMethod method)
Set contact point computation method.
Definition FCLCollisionDetector.cpp:807
ShapeMap mShapeMap
Definition FCLCollisionDetector.hpp:196
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:194
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:65
@ PRIMITIVE
Definition FCLCollisionDetector.hpp:66
@ MESH
Definition FCLCollisionDetector.hpp:67
ContactPointComputationMethod
Whether to use FCL's contact point computation.
Definition FCLCollisionDetector.hpp:79
@ FCL
Definition FCLCollisionDetector.hpp:80
@ DART
Definition FCLCollisionDetector.hpp:81
PrimitiveShape mPrimitiveShapeType
Definition FCLCollisionDetector.hpp:154
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:198
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:60
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:177
fcl_weak_ptr< dart::collision::fcl::CollisionGeometry > mShape
A weak reference to the shape.
Definition FCLCollisionDetector.hpp:179
std::size_t mLastKnownVersion
The last version of the shape, as known by this collision detector.
Definition FCLCollisionDetector.hpp:182