Exotica
collision_scene.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_CORE_COLLISION_SCENE_H_
31 #define EXOTICA_CORE_COLLISION_SCENE_H_
32 
33 #include <Eigen/Dense>
34 
35 #include <sstream>
36 #include <string>
37 #include <tuple>
38 #include <unordered_map>
39 #include <unordered_set>
40 
41 #include <exotica_core/factory.h>
43 #include <exotica_core/object.h>
44 
45 #define REGISTER_COLLISION_SCENE_TYPE(TYPE, DERIV) EXOTICA_CORE_REGISTER(exotica::CollisionScene, TYPE, DERIV)
46 namespace exotica
47 {
48 class Scene;
49 
51 {
52 public:
57  {
58  if (this != &other)
59  {
60  entries_ = other.entries_;
61  }
62  return *this;
63  }
64  inline void clear() { entries_.clear(); }
65  inline bool hasEntry(const std::string& name) const { return entries_.find(name) == entries_.end(); }
66  inline void setEntry(const std::string& name1, const std::string& name2) { entries_[name1].insert(name2); }
67  inline void getAllEntryNames(std::vector<std::string>& names) const
68  {
69  names.clear();
70  for (auto& it : entries_)
71  {
72  names.push_back(it.first);
73  }
74  }
75  inline size_t getNumberOfEntries() const { return entries_.size(); }
76  inline bool getAllowedCollision(const std::string& name1, const std::string& name2) const
77  {
78  auto it = entries_.find(name1);
79  if (it == entries_.end()) return true;
80  return it->second.find(name2) == it->second.end();
81  }
82 
83 private:
84  std::unordered_map<std::string, std::unordered_set<std::string>> entries_;
85 };
86 
88 {
89  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
90 
91  ContinuousCollisionProxy() : e1(nullptr), e2(nullptr), in_collision(false), time_of_contact(-1) {}
92  std::shared_ptr<KinematicElement> e1;
93  std::shared_ptr<KinematicElement> e2;
94  KDL::Frame contact_tf1;
95  KDL::Frame contact_tf2;
98 
99  // Contact information, filled in if in continuous contact:
100  double penetration_depth = 0.0;
101  Eigen::Vector3d contact_normal;
102  Eigen::Vector3d contact_pos; // In world frame
103 
104  inline std::string Print() const
105  {
106  std::stringstream ss;
107  if (e1 && e2)
108  {
109  ss << "ContinuousCollisionProxy: '" << e1->segment.getName() << "' - '" << e2->segment.getName() << " in_collision: " << in_collision << " time_of_contact " << time_of_contact << " depth: " << penetration_depth;
110  }
111  else
112  {
113  ss << "ContinuousCollisionProxy (empty)";
114  }
115  return ss.str();
116  }
117 };
118 
120 {
121  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
122 
123  CollisionProxy() : e1(nullptr), e2(nullptr), distance(0) {}
124  std::shared_ptr<KinematicElement> e1;
125  std::shared_ptr<KinematicElement> e2;
126  Eigen::Vector3d contact1;
127  Eigen::Vector3d normal1;
128  Eigen::Vector3d contact2;
129  Eigen::Vector3d normal2;
130  double distance;
131 
132  inline std::string Print() const
133  {
134  std::stringstream ss;
135  if (e1 && e2)
136  {
137  ss << "Proxy: '" << e1->segment.getName() << "' - '" << e2->segment.getName() << "', c1: " << contact1.transpose() << " c2: " << contact2.transpose() << " n1: " << normal1.transpose() << " n2: " << normal2.transpose() << " d: " << distance;
138  }
139  else
140  {
141  ss << "Proxy (empty)";
142  }
143  return ss.str();
144  }
145 };
146 
148 class CollisionScene : public Object, public Uncopyable, public virtual InstantiableBase
149 {
150 public:
152  virtual ~CollisionScene() {}
154  virtual void InstantiateBase(const Initializer& init);
155 
157  virtual void Setup() {}
163  virtual bool IsAllowedToCollide(const std::string& o1, const std::string& o2, const bool& self);
164 
168  virtual bool IsStateValid(bool self = true, double safe_distance = 0.0) = 0;
169 
174  virtual bool IsCollisionFree(const std::string& o1, const std::string& o2, double safe_distance = 0.0) { ThrowPretty("Not implemented!"); }
179  virtual std::vector<CollisionProxy> GetCollisionDistance(bool self) { ThrowPretty("Not implemented!"); }
184  virtual std::vector<CollisionProxy> GetCollisionDistance(const std::string& o1, const std::string& o2) { ThrowPretty("Not implemented!"); }
188  virtual std::vector<CollisionProxy> GetCollisionDistance(const std::string& o1, const bool& self) { ThrowPretty("Not implemented!"); }
193  virtual std::vector<CollisionProxy> GetCollisionDistance(const std::string& o1, const bool& self, const bool& disable_collision_scene_update) { ThrowPretty("Not implemented!"); }
198  virtual std::vector<CollisionProxy> GetCollisionDistance(const std::vector<std::string>& objects, const bool& self) { ThrowPretty("Not implemented!"); }
201  virtual std::vector<CollisionProxy> GetRobotToRobotCollisionDistance(double check_margin) { ThrowPretty("Not implemented!"); }
204  virtual std::vector<CollisionProxy> GetRobotToWorldCollisionDistance(double check_margin) { ThrowPretty("Not implemented!"); }
207  virtual std::vector<std::string> GetCollisionWorldLinks() = 0;
208 
211  virtual std::vector<std::string> GetCollisionRobotLinks() = 0;
212 
221  virtual 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) { ThrowPretty("Not implemented!"); }
225  virtual std::vector<ContinuousCollisionProxy> ContinuousCollisionCast(const std::vector<std::vector<std::tuple<std::string, Eigen::Isometry3d, Eigen::Isometry3d>>>& motion_transforms) { ThrowPretty("Not implemented!"); }
228  virtual Eigen::Vector3d GetTranslation(const std::string& name) = 0;
229 
231  {
232  acm_ = acm;
233  }
234 
237  {
239  }
240 
241  double GetRobotLinkScale() const { return robot_link_scale_; }
242  void SetRobotLinkScale(const double scale)
243  {
244  if (scale < 0.0)
245  ThrowPretty("Link scaling needs to be greater than or equal to 0");
246  robot_link_scale_ = scale;
248  }
249 
250  double GetWorldLinkScale() const { return world_link_scale_; }
251  void SetWorldLinkScale(const double scale)
252  {
253  if (scale < 0.0)
254  ThrowPretty("Link scaling needs to be greater than or equal to 0");
255  world_link_scale_ = scale;
257  }
258 
259  double GetRobotLinkPadding() const { return robot_link_padding_; }
260  void SetRobotLinkPadding(const double padding)
261  {
262  if (padding < 0.0)
263  HIGHLIGHT_NAMED("SetRobotLinkPadding", "Generally, padding should be positive.");
264  robot_link_padding_ = padding;
266  }
267 
268  double GetWorldLinkPadding() const { return world_link_padding_; }
269  void SetWorldLinkPadding(const double padding)
270  {
271  if (padding < 0.0)
272  HIGHLIGHT_NAMED("SetRobotLinkPadding", "Generally, padding should be positive.");
273  world_link_padding_ = padding;
275  }
276 
278  void SetReplacePrimitiveShapesWithMeshes(const bool value)
279  {
282  }
283 
286  virtual void UpdateCollisionObjects(const std::map<std::string, std::weak_ptr<KinematicElement>>& objects) = 0;
287 
289  virtual void UpdateCollisionObjectTransforms() = 0;
290 
292  void set_replace_cylinders_with_capsules(const bool value)
293  {
296  }
297 
298  bool debug_ = false;
299 
301  void AssignScene(std::shared_ptr<Scene> scene)
302  {
303  scene_ = scene;
304  }
305 
306 protected:
309 
311  std::weak_ptr<Scene> scene_;
312 
315 
318 
320  double robot_link_scale_ = 1.0;
321 
323  double world_link_scale_ = 1.0;
324 
326  double robot_link_padding_ = 0.0;
327 
329  double world_link_padding_ = 0.0;
330 
333 
336 
339 };
340 
341 typedef std::shared_ptr<CollisionScene> CollisionScenePtr;
342 } // namespace exotica
343 
344 #endif // EXOTICA_CORE_COLLISION_SCENE_H_
exotica::ContinuousCollisionProxy::contact_tf1
KDL::Frame contact_tf1
Definition: collision_scene.h:94
exotica::ContinuousCollisionProxy::e2
std::shared_ptr< KinematicElement > e2
Definition: collision_scene.h:93
exotica::CollisionScene::SetWorldLinkPadding
void SetWorldLinkPadding(const double padding)
Definition: collision_scene.h:269
exotica::CollisionScene::ContinuousCollisionCast
virtual std::vector< ContinuousCollisionProxy > ContinuousCollisionCast(const std::vector< std::vector< std::tuple< std::string, Eigen::Isometry3d, Eigen::Isometry3d >>> &motion_transforms)
Performs a continuous collision check by casting the active objects passed in against the static envi...
Definition: collision_scene.h:225
exotica::CollisionScene::scene_
std::weak_ptr< Scene > scene_
Stores a pointer to the Scene which owns this CollisionScene.
Definition: collision_scene.h:311
exotica::CollisionScene::world_link_padding_
double world_link_padding_
World link padding.
Definition: collision_scene.h:329
exotica::CollisionScene::SetACM
void SetACM(const AllowedCollisionMatrix &acm)
Definition: collision_scene.h:230
exotica::Uncopyable
Definition: uncopyable.h:35
factory.h
exotica::ContinuousCollisionProxy
Definition: collision_scene.h:87
exotica::AllowedCollisionMatrix::entries_
std::unordered_map< std::string, std::unordered_set< std::string > > entries_
Definition: collision_scene.h:84
exotica::AllowedCollisionMatrix::getAllowedCollision
bool getAllowedCollision(const std::string &name1, const std::string &name2) const
Definition: collision_scene.h:76
exotica::CollisionScene::Setup
virtual void Setup()
Setup additional construction that requires initialiser parameter.
Definition: collision_scene.h:157
exotica::ContinuousCollisionProxy::contact_normal
Eigen::Vector3d contact_normal
Definition: collision_scene.h:101
exotica::AllowedCollisionMatrix::getNumberOfEntries
size_t getNumberOfEntries() const
Definition: collision_scene.h:75
exotica::CollisionScene::SetWorldLinkScale
void SetWorldLinkScale(const double scale)
Definition: collision_scene.h:251
exotica::CollisionScene::SetRobotLinkScale
void SetRobotLinkScale(const double scale)
Definition: collision_scene.h:242
exotica::ContinuousCollisionProxy::in_collision
bool in_collision
Definition: collision_scene.h:96
exotica::CollisionProxy::CollisionProxy
EIGEN_MAKE_ALIGNED_OPERATOR_NEW CollisionProxy()
Definition: collision_scene.h:123
exotica::CollisionScene::IsCollisionFree
virtual bool IsCollisionFree(const std::string &o1, const std::string &o2, double safe_distance=0.0)
Checks if two objects are in collision.
Definition: collision_scene.h:174
exotica::CollisionScene::GetCollisionRobotLinks
virtual std::vector< std::string > GetCollisionRobotLinks()=0
Gets the collision robot links.
exotica::CollisionScene::UpdateCollisionObjectTransforms
virtual void UpdateCollisionObjectTransforms()=0
Updates collision object transformations from the kinematic tree.
exotica::CollisionProxy::e2
std::shared_ptr< KinematicElement > e2
Definition: collision_scene.h:125
exotica::CollisionScene::GetCollisionDistance
virtual std::vector< CollisionProxy > GetCollisionDistance(const std::string &o1, const bool &self)
Gets the closest distance of any collision object which is allowed to collide with any collision obje...
Definition: collision_scene.h:188
exotica::InstantiableBase
Definition: property.h:98
exotica::CollisionScene::GetCollisionDistance
virtual std::vector< CollisionProxy > GetCollisionDistance(bool self)
Computes collision distances.
Definition: collision_scene.h:179
exotica::CollisionScene::GetWorldLinkScale
double GetWorldLinkScale() const
Definition: collision_scene.h:250
exotica
Definition: cartpole_dynamics_solver.h:38
exotica::CollisionScene::UpdateCollisionObjects
virtual void UpdateCollisionObjects(const std::map< std::string, std::weak_ptr< KinematicElement >> &objects)=0
Creates the collision scene from kinematic elements.
exotica::ContinuousCollisionProxy::ContinuousCollisionProxy
EIGEN_MAKE_ALIGNED_OPERATOR_NEW ContinuousCollisionProxy()
Definition: collision_scene.h:91
exotica::ContinuousCollisionProxy::contact_tf2
KDL::Frame contact_tf2
Definition: collision_scene.h:95
exotica::CollisionScene::CollisionScene
CollisionScene()
Definition: collision_scene.h:151
exotica::CollisionScene::GetCollisionDistance
virtual std::vector< CollisionProxy > GetCollisionDistance(const std::vector< std::string > &objects, const bool &self)
Gets the closest distance of any collision object which is allowed to collide with any collision obje...
Definition: collision_scene.h:198
exotica::ContinuousCollisionProxy::Print
std::string Print() const
Definition: collision_scene.h:104
exotica::CollisionScene::robot_link_padding_
double robot_link_padding_
Robot link padding.
Definition: collision_scene.h:326
exotica::CollisionScene::~CollisionScene
virtual ~CollisionScene()
Definition: collision_scene.h:152
HIGHLIGHT_NAMED
#define HIGHLIGHT_NAMED(name, x)
Definition: printable.h:62
exotica::ContinuousCollisionProxy::e1
std::shared_ptr< KinematicElement > e1
Definition: collision_scene.h:92
exotica::CollisionScene::GetRobotToRobotCollisionDistance
virtual std::vector< CollisionProxy > GetRobotToRobotCollisionDistance(double check_margin)
Gets the closest distances between links within the robot that are closer than check_margin.
Definition: collision_scene.h:201
exotica::CollisionScene::GetCollisionDistance
virtual std::vector< CollisionProxy > GetCollisionDistance(const std::string &o1, const std::string &o2)
Computes collision distances between two objects.
Definition: collision_scene.h:184
exotica::CollisionScene::SetAlwaysExternallyUpdatedCollisionScene
void SetAlwaysExternallyUpdatedCollisionScene(const bool value)
Definition: collision_scene.h:236
exotica::CollisionScene::replace_primitive_shapes_with_meshes_
bool replace_primitive_shapes_with_meshes_
Replace primitive shapes with meshes internally (e.g. when primitive shape algorithms are brittle,...
Definition: collision_scene.h:332
exotica::AllowedCollisionMatrix::AllowedCollisionMatrix
AllowedCollisionMatrix()
Definition: collision_scene.h:53
exotica::CollisionScene::GetReplacePrimitiveShapesWithMeshes
bool GetReplacePrimitiveShapesWithMeshes() const
Definition: collision_scene.h:277
exotica::Object
Definition: object.h:44
exotica::AllowedCollisionMatrix::AllowedCollisionMatrix
AllowedCollisionMatrix(const AllowedCollisionMatrix &acm)
Definition: collision_scene.h:55
exotica::CollisionProxy::contact2
Eigen::Vector3d contact2
Definition: collision_scene.h:128
exotica::CollisionScene::GetAlwaysExternallyUpdatedCollisionScene
bool GetAlwaysExternallyUpdatedCollisionScene() const
Definition: collision_scene.h:235
exotica::AllowedCollisionMatrix::operator=
AllowedCollisionMatrix & operator=(const AllowedCollisionMatrix &other)
Definition: collision_scene.h:56
exotica::CollisionScene::acm_
AllowedCollisionMatrix acm_
The allowed collision matrix.
Definition: collision_scene.h:314
exotica::CollisionScene::IsAllowedToCollide
virtual bool IsAllowedToCollide(const std::string &o1, const std::string &o2, const bool &self)
Returns whether two collision objects/shapes are allowed to collide by name.
exotica::Initializer
Definition: property.h:70
exotica::ContinuousCollisionProxy::penetration_depth
double penetration_depth
Definition: collision_scene.h:100
exotica::CollisionScene::robot_link_replacement_config_
std::string robot_link_replacement_config_
Filename for config file (YAML) which contains shape replacements.
Definition: collision_scene.h:338
exotica::CollisionScene::get_replace_cylinders_with_capsules
bool get_replace_cylinders_with_capsules() const
Definition: collision_scene.h:291
exotica::CollisionScene::GetRobotLinkScale
double GetRobotLinkScale() const
Definition: collision_scene.h:241
exotica::AllowedCollisionMatrix::setEntry
void setEntry(const std::string &name1, const std::string &name2)
Definition: collision_scene.h:66
exotica::CollisionScenePtr
std::shared_ptr< CollisionScene > CollisionScenePtr
Definition: collision_scene.h:341
exotica::CollisionScene::always_externally_updated_collision_scene_
bool always_externally_updated_collision_scene_
Whether the collision scene is automatically updated - if not, update on queries.
Definition: collision_scene.h:317
exotica::AllowedCollisionMatrix::~AllowedCollisionMatrix
~AllowedCollisionMatrix()
Definition: collision_scene.h:54
exotica::ContinuousCollisionProxy::contact_pos
Eigen::Vector3d contact_pos
Definition: collision_scene.h:102
exotica::ContinuousCollisionProxy::time_of_contact
double time_of_contact
Definition: collision_scene.h:97
exotica::CollisionScene::robot_link_scale_
double robot_link_scale_
Robot link scaling.
Definition: collision_scene.h:320
exotica::CollisionScene::GetTranslation
virtual Eigen::Vector3d GetTranslation(const std::string &name)=0
Returns the translation of the named collision object.
exotica::CollisionScene::GetRobotLinkPadding
double GetRobotLinkPadding() const
Definition: collision_scene.h:259
exotica::CollisionScene::InstantiateBase
virtual void InstantiateBase(const Initializer &init)
Instantiates the base properties of the CollisionScene.
exotica::AllowedCollisionMatrix::hasEntry
bool hasEntry(const std::string &name) const
Definition: collision_scene.h:65
exotica::CollisionProxy::normal1
Eigen::Vector3d normal1
Definition: collision_scene.h:127
exotica::CollisionScene::GetRobotToWorldCollisionDistance
virtual std::vector< CollisionProxy > GetRobotToWorldCollisionDistance(double check_margin)
Gets the closest distances between links of the robot and the environment that are closer than check_...
Definition: collision_scene.h:204
exotica::CollisionScene
The class of collision scene.
Definition: collision_scene.h:148
exotica::CollisionScene::set_replace_cylinders_with_capsules
void set_replace_cylinders_with_capsules(const bool value)
Definition: collision_scene.h:292
exotica::CollisionScene::debug_
bool debug_
Definition: collision_scene.h:298
exotica::AllowedCollisionMatrix::clear
void clear()
Definition: collision_scene.h:64
ThrowPretty
#define ThrowPretty(m)
Definition: exception.h:36
exotica::CollisionScene::replace_cylinders_with_capsules_
bool replace_cylinders_with_capsules_
Replace cylinders with capsules internally.
Definition: collision_scene.h:335
exotica::CollisionProxy::distance
double distance
Definition: collision_scene.h:130
exotica::CollisionScene::GetWorldLinkPadding
double GetWorldLinkPadding() const
Definition: collision_scene.h:268
exotica::CollisionProxy
Definition: collision_scene.h:119
exotica::CollisionScene::GetCollisionDistance
virtual std::vector< CollisionProxy > GetCollisionDistance(const std::string &o1, const bool &self, const bool &disable_collision_scene_update)
Gets the closest distance of any collision object which is allowed to collide with any collision obje...
Definition: collision_scene.h:193
exotica::CollisionProxy::contact1
Eigen::Vector3d contact1
Definition: collision_scene.h:126
exotica::CollisionProxy::normal2
Eigen::Vector3d normal2
Definition: collision_scene.h:129
exotica::CollisionScene::GetCollisionWorldLinks
virtual std::vector< std::string > GetCollisionWorldLinks()=0
Gets the collision world links.
exotica::CollisionScene::world_link_scale_
double world_link_scale_
World link scaling.
Definition: collision_scene.h:323
exotica::CollisionProxy::Print
std::string Print() const
Definition: collision_scene.h:132
kinematic_element.h
exotica::CollisionScene::IsStateValid
virtual bool IsStateValid(bool self=true, double safe_distance=0.0)=0
Checks if the whole robot is valid (collision only).
exotica::CollisionScene::SetRobotLinkPadding
void SetRobotLinkPadding(const double padding)
Definition: collision_scene.h:260
exotica::CollisionScene::SetReplacePrimitiveShapesWithMeshes
void SetReplacePrimitiveShapesWithMeshes(const bool value)
Definition: collision_scene.h:278
exotica::CollisionScene::AssignScene
void AssignScene(std::shared_ptr< Scene > scene)
Sets a scene pointer to the CollisionScene for access to methods.
Definition: collision_scene.h:301
exotica::AllowedCollisionMatrix
Definition: collision_scene.h:50
exotica::CollisionScene::ContinuousCollisionCheck
virtual 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)
Performs a continuous collision check between two objects with a linear interpolation between two giv...
Definition: collision_scene.h:221
exotica::CollisionProxy::e1
std::shared_ptr< KinematicElement > e1
Definition: collision_scene.h:124
object.h
exotica::CollisionScene::needs_update_of_collision_objects_
bool needs_update_of_collision_objects_
Indicates whether TriggerUpdateCollisionObjects needs to be called.
Definition: collision_scene.h:308
exotica::AllowedCollisionMatrix::getAllEntryNames
void getAllEntryNames(std::vector< std::string > &names) const
Definition: collision_scene.h:67