collision_scene_fcl.h
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018, University of Edinburgh
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice,
9 // this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without specific
15 // prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 //
29 
30 #ifndef EXOTICA_COLLISION_SCENE_FCL_COLLISION_SCENE_FCL_H_
31 #define EXOTICA_COLLISION_SCENE_FCL_COLLISION_SCENE_FCL_H_
32 
35 
36 #include <fcl/BVH/BVH_model.h>
37 #include <fcl/broadphase/broadphase.h>
38 #include <fcl/collision.h>
39 #include <fcl/distance.h>
40 #include <fcl/narrowphase/narrowphase.h>
41 #include <fcl/octree.h>
42 #include <fcl/shape/geometric_shapes.h>
43 
46 
47 namespace exotica
48 {
50 {
51 public:
53  {
54  CollisionData(CollisionSceneFCL* scene_in) : scene(scene_in) {}
55  fcl::CollisionRequest request;
56  fcl::CollisionResult result;
58  bool self = true;
59  double safe_distance;
60  };
61 
62  void Setup() override;
63 
64  static bool IsAllowedToCollide(fcl::CollisionObject* o1, fcl::CollisionObject* o2, bool self, CollisionSceneFCL* scene);
65  static bool CollisionCallback(fcl::CollisionObject* o1, fcl::CollisionObject* o2, void* data);
66 
70  bool IsStateValid(bool self = true, double safe_distance = 0.0) override;
71  bool IsCollisionFree(const std::string& o1, const std::string& o2, double safe_distance = 0.0) override;
72 
75  std::vector<std::string> GetCollisionWorldLinks() override;
76 
79  std::vector<std::string> GetCollisionRobotLinks() override;
80 
81  Eigen::Vector3d GetTranslation(const std::string& name) override;
82 
85  void UpdateCollisionObjects(const std::map<std::string, std::weak_ptr<KinematicElement>>& objects) override;
86 
88  void UpdateCollisionObjectTransforms() override;
89 
90 private:
91  std::shared_ptr<fcl::CollisionObject> ConstructFclCollisionObject(long i, std::shared_ptr<KinematicElement> element);
92  static void CheckCollision(fcl::CollisionObject* o1, fcl::CollisionObject* o2, CollisionData* data);
93 
94  std::map<std::string, std::shared_ptr<fcl::CollisionObject>> fcl_cache_;
95 
96  std::vector<fcl::CollisionObject*> fcl_objects_;
97  std::vector<std::weak_ptr<KinematicElement>> kinematic_elements_;
98 };
99 }
100 
101 #endif // EXOTICA_COLLISION_SCENE_FCL_COLLISION_SCENE_FCL_H_
void UpdateCollisionObjectTransforms() override
Updates collision object transformations from the kinematic tree.
CollisionData(CollisionSceneFCL *scene_in)
std::shared_ptr< fcl::CollisionObject > ConstructFclCollisionObject(long i, std::shared_ptr< KinematicElement > element)
std::vector< std::weak_ptr< KinematicElement > > kinematic_elements_
std::map< std::string, std::shared_ptr< fcl::CollisionObject > > fcl_cache_
static bool CollisionCallback(fcl::CollisionObject *o1, fcl::CollisionObject *o2, void *data)
std::vector< std::string > GetCollisionRobotLinks() override
Gets the collision robot links.
std::vector< std::string > GetCollisionWorldLinks() override
Gets the collision world links.
void UpdateCollisionObjects(const std::map< std::string, std::weak_ptr< KinematicElement >> &objects) override
Creates the collision scene from kinematic elements.
std::vector< fcl::CollisionObject * > fcl_objects_
Eigen::Vector3d GetTranslation(const std::string &name) override
bool IsCollisionFree(const std::string &o1, const std::string &o2, double safe_distance=0.0) override
bool IsStateValid(bool self=true, double safe_distance=0.0) override
Check if the whole robot is valid (collision only).
static bool IsAllowedToCollide(fcl::CollisionObject *o1, fcl::CollisionObject *o2, bool self, CollisionSceneFCL *scene)
static void CheckCollision(fcl::CollisionObject *o1, fcl::CollisionObject *o2, CollisionData *data)


exotica_collision_scene_fcl
Author(s):
autogenerated on Wed Jul 1 2020 03:33:49