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 
55 {
56 public:
61  {
62  if (this != &other)
63  {
64  entries_ = other.entries_;
65  }
66  return *this;
67  }
68  inline void clear() { entries_.clear(); }
69  inline bool hasEntry(const std::string& name) const { return entries_.find(name) == entries_.end(); }
70  inline void setEntry(const std::string& name1, const std::string& name2) { entries_[name1].insert(name2); }
71  inline void getAllEntryNames(std::vector<std::string>& names) const
72  {
73  names.clear();
74  for (auto& it : entries_)
75  {
76  names.push_back(it.first);
77  }
78  }
79  inline size_t getNumberOfEntries() const { return entries_.size(); }
80  inline bool getAllowedCollision(const std::string& name1, const std::string& name2) const
81  {
82  auto it = entries_.find(name1);
83  if (it == entries_.end()) return true;
84  return it->second.find(name2) == it->second.end();
85  }
86 
87 private:
88  std::unordered_map<std::string, std::unordered_set<std::string>> entries_;
89 };
90 
92 {
93  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
94 
95  ContinuousCollisionProxy() : e1(nullptr), e2(nullptr), in_collision(false), time_of_contact(-1) {}
96  std::shared_ptr<KinematicElement> e1;
97  std::shared_ptr<KinematicElement> e2;
98  KDL::Frame contact_tf1;
99  KDL::Frame contact_tf2;
102 
103  // Contact information, filled in if in continuous contact:
104  double penetration_depth = 0.0;
105  Eigen::Vector3d contact_normal;
106  Eigen::Vector3d contact_pos; // In world frame
107 
108  inline std::string Print() const
109  {
110  std::stringstream ss;
111  if (e1 && e2)
112  {
113  ss << "ContinuousCollisionProxy: '" << e1->segment.getName() << "' - '" << e2->segment.getName() << " in_collision: " << in_collision << " time_of_contact " << time_of_contact << " depth: " << penetration_depth;
114  }
115  else
116  {
117  ss << "ContinuousCollisionProxy (empty)";
118  }
119  return ss.str();
120  }
121 };
122 
124 {
125  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
126 
127  CollisionProxy() : e1(nullptr), e2(nullptr), distance(0) {}
128  std::shared_ptr<KinematicElement> e1;
129  std::shared_ptr<KinematicElement> e2;
130  Eigen::Vector3d contact1;
131  Eigen::Vector3d normal1;
132  Eigen::Vector3d contact2;
133  Eigen::Vector3d normal2;
134  double distance;
135 
136  inline std::string Print() const
137  {
138  std::stringstream ss;
139  if (e1 && e2)
140  {
141  ss << "Proxy: '" << e1->segment.getName() << "' - '" << e2->segment.getName() << "', c1: " << contact1.transpose() << " c2: " << contact2.transpose() << " n1: " << normal1.transpose() << " n2: " << normal2.transpose() << " d: " << distance;
142  }
143  else
144  {
145  ss << "Proxy (empty)";
146  }
147  return ss.str();
148  }
149 };
150 
152 class CollisionScene : public Object, public Uncopyable, public virtual InstantiableBase
153 {
154 public:
156  virtual ~CollisionScene() {}
158  virtual void InstantiateBase(const Initializer& init);
159 
161  virtual void Setup() {}
167  virtual bool IsAllowedToCollide(const std::string& o1, const std::string& o2, const bool& self);
168 
172  virtual bool IsStateValid(bool self = true, double safe_distance = 0.0) = 0;
173 
178  virtual bool IsCollisionFree(const std::string& /*o1*/, const std::string& /*o2*/, double /*safe_distance*/ = 0.0) { ThrowPretty("Not implemented!"); }
183  virtual std::vector<CollisionProxy> GetCollisionDistance(bool /*self*/) { ThrowPretty("Not implemented!"); }
188  virtual std::vector<CollisionProxy> GetCollisionDistance(const std::string& /*o1*/, const std::string& /*o2*/) { ThrowPretty("Not implemented!"); }
192  virtual std::vector<CollisionProxy> GetCollisionDistance(const std::string& /*o1*/, const bool& /*self*/) { ThrowPretty("Not implemented!"); }
197  virtual std::vector<CollisionProxy> GetCollisionDistance(const std::string& /*o1*/, const bool& /*self*/, const bool& /*disable_collision_scene_update*/) { ThrowPretty("Not implemented!"); }
202  virtual std::vector<CollisionProxy> GetCollisionDistance(const std::vector<std::string>& /*objects*/, const bool& /*self*/) { ThrowPretty("Not implemented!"); }
205  virtual std::vector<CollisionProxy> GetRobotToRobotCollisionDistance(double /*check_margin*/) { ThrowPretty("Not implemented!"); }
208  virtual std::vector<CollisionProxy> GetRobotToWorldCollisionDistance(double /*check_margin*/) { ThrowPretty("Not implemented!"); }
211  virtual std::vector<std::string> GetCollisionWorldLinks() = 0;
212 
215  virtual std::vector<std::string> GetCollisionRobotLinks() = 0;
216 
225  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!"); }
229  virtual std::vector<ContinuousCollisionProxy> ContinuousCollisionCast(const std::vector<std::vector<std::tuple<std::string, Eigen::Isometry3d, Eigen::Isometry3d>>>& /*motion_transforms*/) { ThrowPretty("Not implemented!"); }
232  virtual Eigen::Vector3d GetTranslation(const std::string& name) = 0;
233 
235  {
236  acm_ = acm;
237  }
238 
241  {
243  }
244 
245  double GetRobotLinkScale() const { return robot_link_scale_; }
246  void SetRobotLinkScale(const double scale)
247  {
248  if (scale < 0.0)
249  ThrowPretty("Link scaling needs to be greater than or equal to 0");
250  robot_link_scale_ = scale;
252  }
253 
254  double GetWorldLinkScale() const { return world_link_scale_; }
255  void SetWorldLinkScale(const double scale)
256  {
257  if (scale < 0.0)
258  ThrowPretty("Link scaling needs to be greater than or equal to 0");
259  world_link_scale_ = scale;
261  }
262 
263  double GetRobotLinkPadding() const { return robot_link_padding_; }
264  void SetRobotLinkPadding(const double padding)
265  {
266  if (padding < 0.0)
267  HIGHLIGHT_NAMED("SetRobotLinkPadding", "Generally, padding should be positive.");
268  robot_link_padding_ = padding;
270  }
271 
272  double GetWorldLinkPadding() const { return world_link_padding_; }
273  void SetWorldLinkPadding(const double padding)
274  {
275  if (padding < 0.0)
276  HIGHLIGHT_NAMED("SetRobotLinkPadding", "Generally, padding should be positive.");
277  world_link_padding_ = padding;
279  }
280 
282  void SetReplacePrimitiveShapesWithMeshes(const bool value)
283  {
286  }
287 
290  virtual void UpdateCollisionObjects(const std::map<std::string, std::weak_ptr<KinematicElement>>& objects) = 0;
291 
293  virtual void UpdateCollisionObjectTransforms() = 0;
294 
296  void set_replace_cylinders_with_capsules(const bool value)
297  {
300  }
301 
302  bool debug_ = false;
303 
305  void AssignScene(std::shared_ptr<Scene> scene)
306  {
307  scene_ = scene;
308  }
309 
310 protected:
313 
315  std::weak_ptr<Scene> scene_;
316 
319 
322 
324  double robot_link_scale_ = 1.0;
325 
327  double world_link_scale_ = 1.0;
328 
330  double robot_link_padding_ = 0.0;
331 
333  double world_link_padding_ = 0.0;
334 
337 
340 
343 };
344 
345 typedef std::shared_ptr<CollisionScene> CollisionScenePtr;
346 } // namespace exotica
347 
348 #endif // EXOTICA_CORE_COLLISION_SCENE_H_
exotica::ContinuousCollisionProxy::contact_tf1
KDL::Frame contact_tf1
Definition: collision_scene.h:98
exotica::ContinuousCollisionProxy::e2
std::shared_ptr< KinematicElement > e2
Definition: collision_scene.h:97
exotica::CollisionScene::SetWorldLinkPadding
void SetWorldLinkPadding(const double padding)
Definition: collision_scene.h:273
exotica::CollisionScene::scene_
std::weak_ptr< Scene > scene_
Stores a pointer to the Scene which owns this CollisionScene.
Definition: collision_scene.h:315
exotica::CollisionScene::world_link_padding_
double world_link_padding_
World link padding.
Definition: collision_scene.h:333
exotica::CollisionScene::SetACM
void SetACM(const AllowedCollisionMatrix &acm)
Definition: collision_scene.h:234
exotica::Uncopyable
Definition: uncopyable.h:35
factory.h
exotica::ContinuousCollisionProxy
Definition: collision_scene.h:91
exotica::AllowedCollisionMatrix::entries_
std::unordered_map< std::string, std::unordered_set< std::string > > entries_
Definition: collision_scene.h:88
exotica::CollisionScene::InstantiateBase
virtual void InstantiateBase(const Initializer &init)
Instantiates the base properties of the CollisionScene.
Definition: collision_scene.cpp:42
exotica::CollisionScene::GetRobotToRobotCollisionDistance
virtual std::vector< CollisionProxy > GetRobotToRobotCollisionDistance(double)
Gets the closest distances between links within the robot that are closer than check_margin.
Definition: collision_scene.h:205
exotica::Scene
The class of EXOTica Scene.
Definition: scene.h:69
exotica::AllowedCollisionMatrix::getAllowedCollision
bool getAllowedCollision(const std::string &name1, const std::string &name2) const
Definition: collision_scene.h:80
exotica::CollisionScene::Setup
virtual void Setup()
Setup additional construction that requires initialiser parameter.
Definition: collision_scene.h:161
exotica::ContinuousCollisionProxy::contact_normal
Eigen::Vector3d contact_normal
Definition: collision_scene.h:105
exotica::AllowedCollisionMatrix::getNumberOfEntries
size_t getNumberOfEntries() const
Definition: collision_scene.h:79
exotica::CollisionScene::SetWorldLinkScale
void SetWorldLinkScale(const double scale)
Definition: collision_scene.h:255
exotica::CollisionScene::SetRobotLinkScale
void SetRobotLinkScale(const double scale)
Definition: collision_scene.h:246
exotica::ContinuousCollisionProxy::in_collision
bool in_collision
Definition: collision_scene.h:100
exotica::CollisionProxy::CollisionProxy
EIGEN_MAKE_ALIGNED_OPERATOR_NEW CollisionProxy()
Definition: collision_scene.h:127
exotica::CollisionScene::GetCollisionDistance
virtual std::vector< CollisionProxy > GetCollisionDistance(const std::string &, const bool &, const bool &)
Gets the closest distance of any collision object which is allowed to collide with any collision obje...
Definition: collision_scene.h:197
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:129
exotica::InstantiableBase
Definition: property.h:98
exotica::CollisionScene::GetRobotToWorldCollisionDistance
virtual std::vector< CollisionProxy > GetRobotToWorldCollisionDistance(double)
Gets the closest distances between links of the robot and the environment that are closer than check_...
Definition: collision_scene.h:208
exotica::CollisionScene::GetWorldLinkScale
double GetWorldLinkScale() const
Definition: collision_scene.h:254
exotica
Definition: collision_scene.h:46
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:95
exotica::ContinuousCollisionProxy::contact_tf2
KDL::Frame contact_tf2
Definition: collision_scene.h:99
exotica::CollisionScene::CollisionScene
CollisionScene()
Definition: collision_scene.h:155
exotica::ContinuousCollisionProxy::Print
std::string Print() const
Definition: collision_scene.h:108
exotica::CollisionScene::robot_link_padding_
double robot_link_padding_
Robot link padding.
Definition: collision_scene.h:330
exotica::CollisionScene::~CollisionScene
virtual ~CollisionScene()
Definition: collision_scene.h:156
HIGHLIGHT_NAMED
#define HIGHLIGHT_NAMED(name, x)
Definition: printable.h:62
exotica::ContinuousCollisionProxy::e1
std::shared_ptr< KinematicElement > e1
Definition: collision_scene.h:96
exotica::CollisionScene::ContinuousCollisionCheck
virtual ContinuousCollisionProxy ContinuousCollisionCheck(const std::string &, const KDL::Frame &, const KDL::Frame &, const std::string &, const KDL::Frame &, const KDL::Frame &)
Performs a continuous collision check between two objects with a linear interpolation between two giv...
Definition: collision_scene.h:225
exotica::CollisionScene::SetAlwaysExternallyUpdatedCollisionScene
void SetAlwaysExternallyUpdatedCollisionScene(const bool value)
Definition: collision_scene.h:240
name
std::string name
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:336
exotica::AllowedCollisionMatrix::AllowedCollisionMatrix
AllowedCollisionMatrix()
Definition: collision_scene.h:57
exotica::CollisionScene::GetReplacePrimitiveShapesWithMeshes
bool GetReplacePrimitiveShapesWithMeshes() const
Definition: collision_scene.h:281
exotica::Object
Definition: object.h:44
exotica::AllowedCollisionMatrix::AllowedCollisionMatrix
AllowedCollisionMatrix(const AllowedCollisionMatrix &acm)
Definition: collision_scene.h:59
exotica::CollisionProxy::contact2
Eigen::Vector3d contact2
Definition: collision_scene.h:132
exotica::CollisionScene::GetAlwaysExternallyUpdatedCollisionScene
bool GetAlwaysExternallyUpdatedCollisionScene() const
Definition: collision_scene.h:239
exotica::AllowedCollisionMatrix::operator=
AllowedCollisionMatrix & operator=(const AllowedCollisionMatrix &other)
Definition: collision_scene.h:60
exotica::CollisionScene::acm_
AllowedCollisionMatrix acm_
The allowed collision matrix.
Definition: collision_scene.h:318
exotica::Initializer
Definition: property.h:70
exotica::ContinuousCollisionProxy::penetration_depth
double penetration_depth
Definition: collision_scene.h:104
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:342
exotica::CollisionScene::get_replace_cylinders_with_capsules
bool get_replace_cylinders_with_capsules() const
Definition: collision_scene.h:295
exotica::CollisionScene::GetRobotLinkScale
double GetRobotLinkScale() const
Definition: collision_scene.h:245
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.
Definition: collision_scene.cpp:58
exotica::AllowedCollisionMatrix::setEntry
void setEntry(const std::string &name1, const std::string &name2)
Definition: collision_scene.h:70
exotica::CollisionScenePtr
std::shared_ptr< CollisionScene > CollisionScenePtr
Definition: collision_scene.h:345
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:321
exotica::CollisionScene::ContinuousCollisionCast
virtual std::vector< ContinuousCollisionProxy > ContinuousCollisionCast(const std::vector< std::vector< std::tuple< std::string, Eigen::Isometry3d, Eigen::Isometry3d >>> &)
Performs a continuous collision check by casting the active objects passed in against the static envi...
Definition: collision_scene.h:229
exotica::AllowedCollisionMatrix::~AllowedCollisionMatrix
~AllowedCollisionMatrix()
Definition: collision_scene.h:58
exotica::ContinuousCollisionProxy::contact_pos
Eigen::Vector3d contact_pos
Definition: collision_scene.h:106
exotica::ContinuousCollisionProxy::time_of_contact
double time_of_contact
Definition: collision_scene.h:101
exotica::CollisionScene::robot_link_scale_
double robot_link_scale_
Robot link scaling.
Definition: collision_scene.h:324
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:263
exotica::CollisionScene::GetCollisionDistance
virtual std::vector< CollisionProxy > GetCollisionDistance(const std::string &, const bool &)
Gets the closest distance of any collision object which is allowed to collide with any collision obje...
Definition: collision_scene.h:192
exotica::AllowedCollisionMatrix::hasEntry
bool hasEntry(const std::string &name) const
Definition: collision_scene.h:69
exotica::CollisionProxy::normal1
Eigen::Vector3d normal1
Definition: collision_scene.h:131
exotica::CollisionScene
The class of collision scene.
Definition: collision_scene.h:152
exotica::CollisionScene::set_replace_cylinders_with_capsules
void set_replace_cylinders_with_capsules(const bool value)
Definition: collision_scene.h:296
exotica::CollisionScene::debug_
bool debug_
Definition: collision_scene.h:302
exotica::AllowedCollisionMatrix::clear
void clear()
Definition: collision_scene.h:68
exotica::CollisionScene::IsCollisionFree
virtual bool IsCollisionFree(const std::string &, const std::string &, double=0.0)
Checks if two objects are in collision.
Definition: collision_scene.h:178
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:339
exotica::CollisionProxy::distance
double distance
Definition: collision_scene.h:134
exotica::CollisionScene::GetWorldLinkPadding
double GetWorldLinkPadding() const
Definition: collision_scene.h:272
exotica::CollisionScene::GetCollisionDistance
virtual std::vector< CollisionProxy > GetCollisionDistance(const std::string &, const std::string &)
Computes collision distances between two objects.
Definition: collision_scene.h:188
exotica::CollisionProxy
Definition: collision_scene.h:123
exotica::CollisionScene::GetCollisionDistance
virtual std::vector< CollisionProxy > GetCollisionDistance(bool)
Computes collision distances.
Definition: collision_scene.h:183
exotica::CollisionProxy::contact1
Eigen::Vector3d contact1
Definition: collision_scene.h:130
exotica::CollisionProxy::normal2
Eigen::Vector3d normal2
Definition: collision_scene.h:133
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:327
exotica::CollisionProxy::Print
std::string Print() const
Definition: collision_scene.h:136
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:264
exotica::CollisionScene::SetReplacePrimitiveShapesWithMeshes
void SetReplacePrimitiveShapesWithMeshes(const bool value)
Definition: collision_scene.h:282
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:305
exotica::AllowedCollisionMatrix
The AllowedCollisionMatrix is a data structure containing links for which a detected collision does n...
Definition: collision_scene.h:54
exotica::CollisionProxy::e1
std::shared_ptr< KinematicElement > e1
Definition: collision_scene.h:128
exotica::CollisionScene::GetCollisionDistance
virtual std::vector< CollisionProxy > GetCollisionDistance(const std::vector< std::string > &, const bool &)
Gets the closest distance of any collision object which is allowed to collide with any collision obje...
Definition: collision_scene.h:202
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:312
exotica::AllowedCollisionMatrix::getAllEntryNames
void getAllEntryNames(std::vector< std::string > &names) const
Definition: collision_scene.h:71


exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Fri Aug 2 2024 08:43:02