Exotica
collision_scene_fcl_latest.h
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018-2020, University of Edinburgh, University of Oxford
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_LATEST_COLLISION_SCENE_FCL_LATEST_H_
31 #define EXOTICA_COLLISION_SCENE_FCL_LATEST_COLLISION_SCENE_FCL_LATEST_H_
32 
33 #include <iostream>
34 
37 
38 #include <exotica_collision_scene_fcl_latest/collision_scene_fcl_latest_initializer.h>
39 
40 #include <fcl/fcl.h> // FCL 0.6 as provided by fcl_catkin
41 
42 namespace exotica
43 {
44 class CollisionSceneFCLLatest : public CollisionScene, public Instantiable<CollisionSceneFCLLatestInitializer>
45 {
46 public:
48  {
49  CollisionData(CollisionSceneFCLLatest* scene_in) : scene(scene_in) {}
50  fcl::CollisionRequestd request;
51  fcl::CollisionResultd result;
53  bool self = true;
54  double safe_distance;
55  };
56 
57  struct DistanceData
58  {
59  DistanceData(CollisionSceneFCLLatest* scene_in) : scene(scene_in) {}
60  fcl::DistanceRequestd request;
61  fcl::DistanceResultd result;
63  std::vector<CollisionProxy> proxies;
64  double Distance = 1e300;
65  bool self = true;
66  };
67 
68  void Setup() override;
69 
70  bool IsAllowedToCollide(const std::string& o1, const std::string& o2, const bool& self) override;
71 
72  static bool IsAllowedToCollide(fcl::CollisionObjectd* o1, fcl::CollisionObjectd* o2, bool self, CollisionSceneFCLLatest* scene);
73  static bool CollisionCallback(fcl::CollisionObjectd* o1, fcl::CollisionObjectd* o2, void* data);
74  static bool CollisionCallbackDistance(fcl::CollisionObjectd* o1, fcl::CollisionObjectd* o2, void* data, double& dist);
75 
79  bool IsStateValid(bool self = true, double safe_distance = 0.0) override;
80  bool IsCollisionFree(const std::string& o1, const std::string& o2, double safe_distance = 0.0) override;
81 
85  std::vector<CollisionProxy> GetCollisionDistance(bool self) override;
86  std::vector<CollisionProxy> GetCollisionDistance(const std::string& o1, const std::string& o2) override;
87  std::vector<CollisionProxy> GetCollisionDistance(const std::string& o1, const bool& self = true) override;
88  std::vector<CollisionProxy> GetCollisionDistance(const std::vector<std::string>& objects, const bool& self = true) override;
89  std::vector<CollisionProxy> GetCollisionDistance(const std::string& o1, const bool& self = true, const bool& disable_collision_scene_update = false) override;
90 
91  std::vector<CollisionProxy> GetRobotToRobotCollisionDistance(double check_margin) override;
92  std::vector<CollisionProxy> GetRobotToWorldCollisionDistance(double check_margin) override;
93 
102  ContinuousCollisionProxy ContinuousCollisionCheck(const std::string& o1, const KDL::Frame& tf1_beg, const KDL::Frame& tf1_end, const std::string& o2, const KDL::Frame& tf2_beg, const KDL::Frame& tf2_end) override;
103 
106  std::vector<std::string> GetCollisionWorldLinks() override;
107 
110  std::vector<std::string> GetCollisionRobotLinks() override;
111 
112  Eigen::Vector3d GetTranslation(const std::string& name) override;
113 
116  void UpdateCollisionObjects(const std::map<std::string, std::weak_ptr<KinematicElement>>& objects) override;
117 
119  void UpdateCollisionObjectTransforms() override;
120 
121 private:
122  std::shared_ptr<fcl::BroadPhaseCollisionManagerd> broad_phase_collision_manager_;
123 
124  std::shared_ptr<fcl::CollisionObjectd> ConstructFclCollisionObject(long i, std::shared_ptr<KinematicElement> element);
125  static void CheckCollision(fcl::CollisionObjectd* o1, fcl::CollisionObjectd* o2, CollisionData* data);
126  static void ComputeDistance(fcl::CollisionObjectd* o1, fcl::CollisionObjectd* o2, DistanceData* data);
127 
128  std::vector<fcl::CollisionObjectd*> fcl_objects_;
129  std::vector<std::shared_ptr<fcl::CollisionObjectd>> fcl_cache_; // to avoid shared_ptr from going stale, to be refactored
130  std::vector<std::weak_ptr<KinematicElement>> kinematic_elements_;
131  std::map<std::string, std::weak_ptr<KinematicElement>> kinematic_elements_map_;
132 
133  // The following maps are stored by the name of the *frame*, e.g., base_link_collision_0
134  std::map<std::string, std::vector<fcl::CollisionObjectd*>> fcl_objects_map_;
135  std::map<std::string, std::vector<fcl::CollisionObjectd*>> fcl_robot_objects_map_;
136  std::map<std::string, std::vector<fcl::CollisionObjectd*>> fcl_world_objects_map_;
137 
138  std::shared_ptr<KinematicElement> GetKinematicElementFromMapByName(const std::string& frame_name)
139  {
140  auto it = kinematic_elements_map_.find(frame_name);
141  if (it == kinematic_elements_map_.end()) ThrowPretty("KinematicElement is not a valid collision link:" << frame_name);
142 
143  return it->second.lock();
144  }
145 
146  std::vector<fcl::CollisionObjectd*> GetRobotCollisionObjectsFromMapByName(const std::string& frame_name)
147  {
148  auto it = fcl_robot_objects_map_.find(frame_name);
149  if (it == fcl_robot_objects_map_.end()) ThrowPretty(frame_name << " is not a robot collision object");
150 
151  return it->second;
152  }
153 
154  std::vector<fcl::CollisionObjectd*> GetWorldCollisionObjectsFromMapByName(const std::string& frame_name)
155  {
156  auto it = fcl_world_objects_map_.find(frame_name);
157  if (it == fcl_world_objects_map_.end()) ThrowPretty(frame_name << " is not a world collision object");
158 
159  return it->second;
160  }
161 
162  std::vector<fcl::CollisionObjectd*> GetCollisionObjectsFromMapByName(const std::string& frame_name)
163  {
164  auto it = fcl_objects_map_.find(frame_name);
165  if (it == fcl_objects_map_.end()) ThrowPretty(frame_name << " is not a collision object");
166 
167  return it->second;
168  }
169 };
170 } // namespace exotica
171 
172 #endif // EXOTICA_COLLISION_SCENE_FCL_LATEST_COLLISION_SCENE_FCL_LATEST_H_
exotica::CollisionSceneFCLLatest::DistanceData
Definition: collision_scene_fcl_latest.h:57
exotica::CollisionSceneFCLLatest::GetKinematicElementFromMapByName
std::shared_ptr< KinematicElement > GetKinematicElementFromMapByName(const std::string &frame_name)
Definition: collision_scene_fcl_latest.h:138
exotica::Distance
Definition: distance.h:39
exotica::CollisionSceneFCLLatest::CollisionData::scene
CollisionSceneFCLLatest * scene
Definition: collision_scene_fcl_latest.h:52
exotica::CollisionSceneFCLLatest::GetCollisionRobotLinks
std::vector< std::string > GetCollisionRobotLinks() override
Gets the collision robot links.
exotica::ContinuousCollisionProxy
Definition: collision_scene.h:87
exotica::CollisionSceneFCLLatest::CollisionData::safe_distance
double safe_distance
Definition: collision_scene_fcl_latest.h:54
exotica::CollisionSceneFCLLatest::ContinuousCollisionCheck
ContinuousCollisionProxy ContinuousCollisionCheck(const std::string &o1, const KDL::Frame &tf1_beg, const KDL::Frame &tf1_end, const std::string &o2, const KDL::Frame &tf2_beg, const KDL::Frame &tf2_end) override
Performs a continuous collision check between two objects with a linear interpolation between two giv...
exotica::CollisionSceneFCLLatest::ComputeDistance
static void ComputeDistance(fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, DistanceData *data)
exotica::CollisionSceneFCLLatest::ConstructFclCollisionObject
std::shared_ptr< fcl::CollisionObjectd > ConstructFclCollisionObject(long i, std::shared_ptr< KinematicElement > element)
exotica::CollisionSceneFCLLatest::DistanceData::proxies
std::vector< CollisionProxy > proxies
Definition: collision_scene_fcl_latest.h:63
exotica::CollisionSceneFCLLatest::broad_phase_collision_manager_
std::shared_ptr< fcl::BroadPhaseCollisionManagerd > broad_phase_collision_manager_
Definition: collision_scene_fcl_latest.h:122
exotica::CollisionSceneFCLLatest::kinematic_elements_map_
std::map< std::string, std::weak_ptr< KinematicElement > > kinematic_elements_map_
Definition: collision_scene_fcl_latest.h:131
exotica::CollisionSceneFCLLatest::UpdateCollisionObjects
void UpdateCollisionObjects(const std::map< std::string, std::weak_ptr< KinematicElement >> &objects) override
Creates the collision scene from kinematic elements.
exotica::CollisionSceneFCLLatest::CollisionData
Definition: collision_scene_fcl_latest.h:47
exotica::CollisionSceneFCLLatest::GetRobotToWorldCollisionDistance
std::vector< CollisionProxy > GetRobotToWorldCollisionDistance(double check_margin) override
Gets the closest distances between links of the robot and the environment that are closer than check_...
exotica::CollisionSceneFCLLatest::DistanceData::DistanceData
DistanceData(CollisionSceneFCLLatest *scene_in)
Definition: collision_scene_fcl_latest.h:59
exotica::Instantiable
Definition: property.h:110
exotica::CollisionSceneFCLLatest::fcl_world_objects_map_
std::map< std::string, std::vector< fcl::CollisionObjectd * > > fcl_world_objects_map_
Definition: collision_scene_fcl_latest.h:136
exotica
Definition: cartpole_dynamics_solver.h:38
exotica::CollisionSceneFCLLatest::DistanceData::scene
CollisionSceneFCLLatest * scene
Definition: collision_scene_fcl_latest.h:62
conversions.h
collision_scene.h
exotica::CollisionSceneFCLLatest::fcl_robot_objects_map_
std::map< std::string, std::vector< fcl::CollisionObjectd * > > fcl_robot_objects_map_
Definition: collision_scene_fcl_latest.h:135
exotica::CollisionSceneFCLLatest::CollisionData::result
fcl::CollisionResultd result
Definition: collision_scene_fcl_latest.h:51
exotica::CollisionSceneFCLLatest::kinematic_elements_
std::vector< std::weak_ptr< KinematicElement > > kinematic_elements_
Definition: collision_scene_fcl_latest.h:130
exotica::CollisionSceneFCLLatest::GetCollisionObjectsFromMapByName
std::vector< fcl::CollisionObjectd * > GetCollisionObjectsFromMapByName(const std::string &frame_name)
Definition: collision_scene_fcl_latest.h:162
exotica::CollisionSceneFCLLatest::IsAllowedToCollide
bool IsAllowedToCollide(const std::string &o1, const std::string &o2, const bool &self) override
Returns whether two collision objects/shapes are allowed to collide by name.
exotica::CollisionSceneFCLLatest::Setup
void Setup() override
Setup additional construction that requires initialiser parameter.
exotica::CollisionSceneFCLLatest
Definition: collision_scene_fcl_latest.h:44
exotica::CollisionSceneFCLLatest::UpdateCollisionObjectTransforms
void UpdateCollisionObjectTransforms() override
Updates collision object transformations from the kinematic tree.
exotica::CollisionSceneFCLLatest::fcl_objects_map_
std::map< std::string, std::vector< fcl::CollisionObjectd * > > fcl_objects_map_
Definition: collision_scene_fcl_latest.h:134
exotica::CollisionSceneFCLLatest::CollisionCallbackDistance
static bool CollisionCallbackDistance(fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data, double &dist)
exotica::CollisionSceneFCLLatest::fcl_cache_
std::vector< std::shared_ptr< fcl::CollisionObjectd > > fcl_cache_
Definition: collision_scene_fcl_latest.h:129
exotica::CollisionSceneFCLLatest::DistanceData::request
fcl::DistanceRequestd request
Definition: collision_scene_fcl_latest.h:60
exotica::CollisionSceneFCLLatest::GetTranslation
Eigen::Vector3d GetTranslation(const std::string &name) override
Returns the translation of the named collision object.
exotica::CollisionSceneFCLLatest::CollisionCallback
static bool CollisionCallback(fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data)
exotica::CollisionSceneFCLLatest::GetRobotCollisionObjectsFromMapByName
std::vector< fcl::CollisionObjectd * > GetRobotCollisionObjectsFromMapByName(const std::string &frame_name)
Definition: collision_scene_fcl_latest.h:146
exotica::CollisionSceneFCLLatest::GetCollisionWorldLinks
std::vector< std::string > GetCollisionWorldLinks() override
Gets the collision world links.
exotica::CollisionScene
The class of collision scene.
Definition: collision_scene.h:148
exotica::CollisionSceneFCLLatest::DistanceData::result
fcl::DistanceResultd result
Definition: collision_scene_fcl_latest.h:61
exotica::CollisionSceneFCLLatest::GetCollisionDistance
std::vector< CollisionProxy > GetCollisionDistance(bool self) override
Computes collision distances.
ThrowPretty
#define ThrowPretty(m)
Definition: exception.h:36
exotica::CollisionSceneFCLLatest::CollisionData::request
fcl::CollisionRequestd request
Definition: collision_scene_fcl_latest.h:50
exotica::CollisionSceneFCLLatest::CollisionData::CollisionData
CollisionData(CollisionSceneFCLLatest *scene_in)
Definition: collision_scene_fcl_latest.h:49
exotica::CollisionSceneFCLLatest::IsCollisionFree
bool IsCollisionFree(const std::string &o1, const std::string &o2, double safe_distance=0.0) override
Checks if two objects are in collision.
exotica::CollisionSceneFCLLatest::CheckCollision
static void CheckCollision(fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, CollisionData *data)
exotica::CollisionSceneFCLLatest::GetWorldCollisionObjectsFromMapByName
std::vector< fcl::CollisionObjectd * > GetWorldCollisionObjectsFromMapByName(const std::string &frame_name)
Definition: collision_scene_fcl_latest.h:154
exotica::CollisionSceneFCLLatest::fcl_objects_
std::vector< fcl::CollisionObjectd * > fcl_objects_
Definition: collision_scene_fcl_latest.h:128
exotica::CollisionSceneFCLLatest::IsStateValid
bool IsStateValid(bool self=true, double safe_distance=0.0) override
Check if the whole robot is valid (collision only).
exotica::CollisionSceneFCLLatest::GetRobotToRobotCollisionDistance
std::vector< CollisionProxy > GetRobotToRobotCollisionDistance(double check_margin) override
Gets the closest distances between links within the robot that are closer than check_margin.