dart
CollisionGroup.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_COLLISIONGROUP_HPP_
34 #define DART_COLLISION_COLLISIONGROUP_HPP_
35 
36 #include <unordered_map>
37 #include <unordered_set>
38 #include <vector>
39 #include "dart/common/Observer.hpp"
40 #include "dart/dynamics/CollisionOption.hpp"
41 #include "dart/dynamics/CollisionResult.hpp"
42 #include "dart/dynamics/DistanceOption.hpp"
43 #include "dart/dynamics/DistanceResult.hpp"
44 #include "dart/dynamics/RaycastOption.hpp"
45 #include "dart/dynamics/RaycastResult.hpp"
46 #include "dart/dynamics/SmartPointer.hpp"
47 
48 namespace dart {
49 namespace collision {
50 
52 {
53 public:
55  CollisionGroup(const CollisionDetectorPtr& collisionDetector);
56  // CollisionGroup also can be created from CollisionDetector::create()
57 
59  virtual ~CollisionGroup() = default;
60 
62  CollisionDetectorPtr getCollisionDetector();
63 
66  ConstCollisionDetectorPtr getCollisionDetector() const;
67 
69  void addShapeFrame(const dynamics::ShapeFrame* shapeFrame);
70 
72  void addShapeFrames(
73  const std::vector<const dynamics::ShapeFrame*>& shapeFrames);
74 
83  template <typename... Others>
84  void addShapeFramesOf(
85  const dynamics::ShapeFrame* shapeFrame, const Others*... others);
86 
88  template <typename... Others>
89  void addShapeFramesOf(
90  const std::vector<const dynamics::ShapeFrame*>& shapeFrames,
91  const Others*... others);
92 
95  template <typename... Others>
96  void addShapeFramesOf(
97  const CollisionGroup* otherGroup, const Others*... others);
98 
101  template <typename... Others>
102  void addShapeFramesOf(
103  const dynamics::BodyNode* bodyNode, const Others*... others);
104 
107  template <typename... Others>
108  void addShapeFramesOf(
109  const dynamics::MetaSkeleton* skeleton, const Others*... others);
110 
113  void addShapeFramesOf();
114 
120  template <typename... Others>
121  void subscribeTo(
122  const dynamics::ConstBodyNodePtr& bodyNode, const Others&... others);
123 
129  //
130  // TODO(MXG): Figure out how to determine a version number for MetaSkeletons
131  // so that this function can accept a ConstMetaSkeletonPtr instead of only a
132  // ConstSkeletonPtr.
133  template <typename... Others>
134  void subscribeTo(
135  const dynamics::ConstSkeletonPtr& skeleton, const Others&... others);
136 
139  void subscribeTo();
140 
145  void removeShapeFrame(const dynamics::ShapeFrame* shapeFrame);
146 
148  void removeShapeFrames(
149  const std::vector<const dynamics::ShapeFrame*>& shapeFrames);
150 
159  template <typename... Others>
160  void removeShapeFramesOf(
161  const dynamics::ShapeFrame* shapeFrame, const Others*... others);
162 
164  template <typename... Others>
165  void removeShapeFramesOf(
166  const std::vector<const dynamics::ShapeFrame*>& shapeFrames,
167  const Others*... others);
168 
174  template <typename... Others>
175  void removeShapeFramesOf(
176  const CollisionGroup* otherGroup, const Others*... others);
177 
183  template <typename... Others>
184  void removeShapeFramesOf(
185  const dynamics::BodyNode* bodyNode, const Others*... others);
186 
192  template <typename... Others>
193  void removeShapeFramesOf(
194  const dynamics::MetaSkeleton* skeleton, const Others*... others);
195 
198  void removeShapeFramesOf();
199 
201  void removeAllShapeFrames();
202 
205  template <typename... Others>
206  void unsubscribeFrom(
207  const dynamics::BodyNode* bodyNode, const Others*... others);
208 
211  template <typename... Others>
212  void unsubscribeFrom(
213  const dynamics::Skeleton* skeleton, const Others*... others);
214 
216  bool hasShapeFrame(const dynamics::ShapeFrame* shapeFrame) const;
217 
219  std::size_t getNumShapeFrames() const;
220 
222  const dynamics::ShapeFrame* getShapeFrame(std::size_t index) const;
223 
225  bool collide(
226  const CollisionOption& option = CollisionOption(false, 1u, nullptr),
227  CollisionResult* result = nullptr);
228 
233  bool collide(
234  CollisionGroup* otherGroup,
235  const CollisionOption& option = CollisionOption(false, 1u, nullptr),
236  CollisionResult* result = nullptr);
237 
246  double distance(
247  const DistanceOption& option = DistanceOption(false, 0.0, nullptr),
248  DistanceResult* result = nullptr);
249 
262  double distance(
263  CollisionGroup* otherGroup,
264  const DistanceOption& option = DistanceOption(false, 0.0, nullptr),
265  DistanceResult* result = nullptr);
266 
274  bool raycast(
275  const Eigen::Vector3d& from,
276  const Eigen::Vector3d& to,
277  const RaycastOption& option = RaycastOption(),
278  RaycastResult* result = nullptr);
279 
281  void setAutomaticUpdate(bool automatic = true);
282 
284  bool getAutomaticUpdate() const;
285 
295  void update();
296 
303 
304 protected:
307  void updateEngineData();
308 
312  virtual void initializeEngineData() = 0;
313 
315  virtual void addCollisionObjectToEngine(CollisionObject* object) = 0;
316 
318  virtual void addCollisionObjectsToEngine(
319  const std::vector<CollisionObject*>& collObjects)
320  = 0;
321 
323  virtual void removeCollisionObjectFromEngine(CollisionObject* object) = 0;
324 
326  virtual void removeAllCollisionObjectsFromEngine() = 0;
327 
330  virtual void updateCollisionGroupEngineData() = 0;
331 
332 protected:
334  CollisionDetectorPtr mCollisionDetector;
335  // CollisionGroup shares the ownership of CollisionDetector with other
336  // CollisionGroups created from the same CollisionDetector so that the
337  // CollisionDetector doesn't get destroyed as long as at least one
338  // CollisionGroup is alive.
339 
344  struct ObjectInfo final
345  {
348 
350  CollisionObjectPtr mObject;
351 
353  std::size_t mLastKnownShapeID;
354 
357  std::size_t mLastKnownVersion;
358 
365  std::unordered_set<const void*> mSources;
366  };
367 
368  using ObjectInfoList = std::vector<std::unique_ptr<ObjectInfo>>;
369 
372  ObjectInfoList mObjectInfoList;
373  // CollisionGroup also shares the ownership of CollisionObjects across other
374  // CollisionGroups for the same reason with above.
375  //
376  // Dev note: This was supposed to be std::map rather than std::vector for
377  // better search performance. The reason we use std::vector is to get
378  // deterministic contact results regardless of the order of CollisionObjects
379  // in this container for FCLCollisionDetector.
380  //
381  // fcl's collision result is dependent on the order of objects in the broad
382  // phase classes. If we use std::map, the orders of element between the
383  // original and copy are not guranteed to be the same as we copy std::map
384  // (e.g., by world cloning).
385 
386 private:
397  class ShapeFrameObserver final : public common::Observer
398  {
399  public:
401  void addShapeFrame(const dynamics::ShapeFrame* shapeFrame);
402 
404  void removeShapeFrame(const dynamics::ShapeFrame* shapeFrame);
405 
407  void removeAllShapeFrames();
408 
412  std::unordered_set<const dynamics::ShapeFrame*> mDeletedFrames;
413 
414  protected:
416  void handleDestructionNotification(const common::Subject* subject) override;
417 
418  private:
422  std::unordered_map<const common::Subject*, const dynamics::ShapeFrame*>
423  mMap;
424  };
425 
429  ObjectInfo* addShapeFrameImpl(
430  const dynamics::ShapeFrame* shapeFrame, const void* source);
431 
434  void removeShapeFrameInternal(
435  const dynamics::ShapeFrame* shapeFrame, const void* source);
436 
439  bool mUpdateAutomatically;
440 
444  template <typename Source, typename Child = void>
445  struct CollisionSource
446  {
448  Source mSource;
449 
451  std::size_t mLastKnownVersion;
452 
454  std::unordered_map<const dynamics::ShapeFrame*, ObjectInfo*> mObjects;
455 
458  struct ChildInfo
459  {
461  std::size_t mLastKnownVersion;
462 
464  std::unordered_set<const dynamics::ShapeFrame*> mFrames;
465 
468  explicit ChildInfo(const std::size_t version) : mLastKnownVersion(version)
469  {
470  // Do nothing
471  }
472  };
473 
476  std::unordered_map<const Child*, ChildInfo> mChildren;
477 
479  CollisionSource(const Source& source, std::size_t lastKnownVersion)
480  : mSource(source), mLastKnownVersion(lastKnownVersion)
481  {
482  // Do nothing
483  }
484  };
485 
486  // Convenient typedefs for Skeleton sources
487  using SkeletonSource
488  = CollisionSource<dynamics::WeakConstMetaSkeletonPtr, dynamics::BodyNode>;
489  using SkeletonSources
490  = std::unordered_map<const dynamics::MetaSkeleton*, SkeletonSource>;
491 
492  // Convenient typedefs for BodyNode sources
493  using BodyNodeSource = CollisionSource<dynamics::WeakConstBodyNodePtr>;
494  using BodyNodeSources
495  = std::unordered_map<const dynamics::BodyNode*, BodyNodeSource>;
496 
499  bool updateSkeletonSource(SkeletonSources::value_type& entry);
500 
503  bool updateBodyNodeSource(BodyNodeSources::value_type& entry);
504 
507  bool updateShapeFrame(ObjectInfo* object);
508 
510  SkeletonSources mSkeletonSources;
511 
513  BodyNodeSources mBodyNodeSources;
514 
516  ShapeFrameObserver mObserver;
517 };
518 
519 } // namespace collision
520 } // namespace dart
521 
522 #include "dart/dynamics/detail/CollisionGroup.hpp"
523 
524 #endif // DART_COLLISION_COLLISIONGROUP_HPP_
bool collide(const CollisionOption &option=CollisionOption(false, 1u, nullptr), CollisionResult *result=nullptr)
Perform collision check within this CollisionGroup.
Definition: CollisionGroup.cpp:184
std::size_t mLastKnownVersion
The last known version of the last known shape that was held by the shape frame.
Definition: CollisionGroup.hpp:357
virtual void addCollisionObjectToEngine(CollisionObject *object)=0
Add CollisionObject to the collision detection engine.
The Subject class is a base class for any object that wants to report when it gets destroyed...
Definition: Subject.hpp:57
CollisionGroup(const CollisionDetectorPtr &collisionDetector)
Constructor.
Definition: CollisionGroup.cpp:46
void update()
Check whether this CollisionGroup&#39;s subscriptions or any of its objects need an update, and then update them if they do.
Definition: CollisionGroup.cpp:253
const dynamics::ShapeFrame * mFrame
The ShapeFrame for this object.
Definition: CollisionGroup.hpp:347
void setAutomaticUpdate(bool automatic=true)
Set whether this CollisionGroup will automatically check for updates.
Definition: CollisionGroup.cpp:241
std::unordered_set< const void * > mSources
The set of all sources that indicate that this object should be in this group.
Definition: CollisionGroup.hpp:365
void removeShapeFrame(const dynamics::ShapeFrame *shapeFrame)
Remove a ShapeFrame from this CollisionGroup.
Definition: CollisionGroup.cpp:91
bool getAutomaticUpdate() const
Get whether this CollisionGroup is set to automatically check for updates.
Definition: CollisionGroup.cpp:247
Definition: DistanceResult.hpp:46
Information on a collision object belonging to this group.
Definition: CollisionGroup.hpp:344
double distance(const DistanceOption &option=DistanceOption(false, 0.0, nullptr), DistanceResult *result=nullptr)
Get the minimum signed distance between the Shape pairs in this CollisionGroup.
Definition: CollisionGroup.cpp:206
void removeDeletedShapeFrames()
Remove any ShapeFrames that have been deleted.
Definition: CollisionGroup.cpp:265
Definition: Aspect.cpp:40
void unsubscribeFrom(const dynamics::BodyNode *bodyNode, const Others *... others)
Unsubscribe from bodyNode.
Definition: CollisionGroup.hpp:249
std::unordered_set< const dynamics::ShapeFrame * > mFrames
Last known set of frames attached to this child.
Definition: CollisionGroup.hpp:464
Definition: CollisionOption.hpp:44
std::size_t mLastKnownShapeID
The ID of that last known shape that was held by the shape frame.
Definition: CollisionGroup.hpp:353
const dynamics::ShapeFrame * getShapeFrame(std::size_t index) const
Get the ShapeFrame corresponding to the given index.
Definition: CollisionGroup.cpp:173
Definition: CollisionResult.hpp:51
Definition: DistanceOption.hpp:44
void updateEngineData()
Update engine data.
Definition: CollisionGroup.cpp:308
virtual void updateCollisionGroupEngineData()=0
Update the collision detection engine data such as broadphase algorithm.
virtual void removeAllCollisionObjectsFromEngine()=0
Remove all the CollisionObjects from the collision detection engine.
CollisionObjectPtr mObject
The CollisionObject that was generated by the CollisionDetector.
Definition: CollisionGroup.hpp:350
std::size_t getNumShapeFrames() const
Return number of ShapeFrames added to this CollisionGroup.
Definition: CollisionGroup.cpp:167
void addShapeFramesOf()
Do nothing.
Definition: CollisionGroup.cpp:79
virtual void addCollisionObjectsToEngine(const std::vector< CollisionObject *> &collObjects)=0
Add CollisionObjects to the collision detection engine.
bool raycast(const Eigen::Vector3d &from, const Eigen::Vector3d &to, const RaycastOption &option=RaycastOption(), RaycastResult *result=nullptr)
Performs raycast to this collision group.
Definition: CollisionGroup.cpp:228
Definition: CollisionObject.hpp:43
void removeAllShapeFrames()
Remove all the ShapeFrames in this CollisionGroup.
Definition: CollisionGroup.cpp:146
bool hasShapeFrame(const dynamics::ShapeFrame *shapeFrame) const
Return true if this CollisionGroup contains shapeFrame.
Definition: CollisionGroup.cpp:155
Definition: CollisionGroup.hpp:51
BodyNode class represents a single node of the skeleton.
Definition: BodyNode.hpp:74
MetaSkeleton is a pure abstract base class that provides a common interface for obtaining data (such ...
Definition: MetaSkeleton.hpp:61
Definition: RaycastResult.hpp:62
CollisionDetectorPtr mCollisionDetector
Collision detector.
Definition: CollisionGroup.hpp:334
ChildInfo(const std::size_t version)
A constructor that simply accepts a last known version number.
Definition: CollisionGroup.hpp:468
void subscribeTo()
Do nothing.
Definition: CollisionGroup.cpp:85
virtual ~CollisionGroup()=default
Destructor.
This is information pertaining to a child of the source.
Definition: CollisionGroup.hpp:458
Definition: ShapeFrame.hpp:189
void addShapeFrame(const dynamics::ShapeFrame *shapeFrame)
Add a ShapeFrame to this CollisionGroup.
Definition: CollisionGroup.cpp:65
Definition: RaycastOption.hpp:42
void addShapeFrames(const std::vector< const dynamics::ShapeFrame *> &shapeFrames)
Add ShapeFrames to this CollisionGroup.
Definition: CollisionGroup.cpp:71
virtual void initializeEngineData()=0
Initialize the collision detection engine data such as broadphase algorithm.
void removeShapeFramesOf()
Do nothing.
Definition: CollisionGroup.cpp:140
class Skeleton
Definition: Skeleton.hpp:55
std::size_t mLastKnownVersion
Last known version of this child.
Definition: CollisionGroup.hpp:461
void removeShapeFrames(const std::vector< const dynamics::ShapeFrame *> &shapeFrames)
Remove ShapeFrames from this CollisionGroup.
Definition: CollisionGroup.cpp:132
The Observer class should be inherited by any class that wants to respond in a customized way to the ...
Definition: Observer.hpp:51
ObjectInfoList mObjectInfoList
Information about ShapeFrames and CollisionObjects that have been added to this CollisionGroup.
Definition: CollisionGroup.hpp:372
virtual void removeCollisionObjectFromEngine(CollisionObject *object)=0
Remove CollisionObject from the collision detection engine.
CollisionDetectorPtr getCollisionDetector()
Return collision detection engine associated with this CollisionGroup.
Definition: CollisionGroup.cpp:53