Go to the documentation of this file.
30 #ifndef EXOTICA_CORE_COLLISION_SCENE_H_
31 #define EXOTICA_CORE_COLLISION_SCENE_H_
33 #include <Eigen/Dense>
38 #include <unordered_map>
39 #include <unordered_set>
45 #define REGISTER_COLLISION_SCENE_TYPE(TYPE, DERIV) EXOTICA_CORE_REGISTER(exotica::CollisionScene, TYPE, DERIV)
66 inline void setEntry(
const std::string& name1,
const std::string& name2) {
entries_[name1].insert(name2); }
72 names.push_back(it.first);
79 if (it ==
entries_.end())
return true;
80 return it->second.find(name2) == it->second.end();
84 std::unordered_map<std::string, std::unordered_set<std::string>>
entries_;
89 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
92 std::shared_ptr<KinematicElement>
e1;
93 std::shared_ptr<KinematicElement>
e2;
106 std::stringstream ss;
113 ss <<
"ContinuousCollisionProxy (empty)";
121 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
124 std::shared_ptr<KinematicElement>
e1;
125 std::shared_ptr<KinematicElement>
e2;
134 std::stringstream ss;
137 ss <<
"Proxy: '" <<
e1->segment.getName() <<
"' - '" <<
e2->segment.getName() <<
"', c1: " <<
contact1.transpose() <<
" c2: " <<
contact2.transpose() <<
" n1: " <<
normal1.transpose() <<
" n2: " <<
normal2.transpose() <<
" d: " <<
distance;
141 ss <<
"Proxy (empty)";
163 virtual bool IsAllowedToCollide(
const std::string& o1,
const std::string& o2,
const bool&
self);
168 virtual bool IsStateValid(
bool self =
true,
double safe_distance = 0.0) = 0;
193 virtual std::vector<CollisionProxy>
GetCollisionDistance(
const std::string& o1,
const bool&
self,
const bool& disable_collision_scene_update) {
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;
245 ThrowPretty(
"Link scaling needs to be greater than or equal to 0");
254 ThrowPretty(
"Link scaling needs to be greater than or equal to 0");
263 HIGHLIGHT_NAMED(
"SetRobotLinkPadding",
"Generally, padding should be positive.");
272 HIGHLIGHT_NAMED(
"SetRobotLinkPadding",
"Generally, padding should be positive.");
286 virtual void UpdateCollisionObjects(
const std::map<std::string, std::weak_ptr<KinematicElement>>& objects) = 0;
344 #endif // EXOTICA_CORE_COLLISION_SCENE_H_
KDL::Frame contact_tf1
Definition: collision_scene.h:94
std::shared_ptr< KinematicElement > e2
Definition: collision_scene.h:93
void SetWorldLinkPadding(const double padding)
Definition: collision_scene.h:269
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
std::weak_ptr< Scene > scene_
Stores a pointer to the Scene which owns this CollisionScene.
Definition: collision_scene.h:311
double world_link_padding_
World link padding.
Definition: collision_scene.h:329
void SetACM(const AllowedCollisionMatrix &acm)
Definition: collision_scene.h:230
Definition: uncopyable.h:35
Definition: collision_scene.h:87
std::unordered_map< std::string, std::unordered_set< std::string > > entries_
Definition: collision_scene.h:84
bool getAllowedCollision(const std::string &name1, const std::string &name2) const
Definition: collision_scene.h:76
virtual void Setup()
Setup additional construction that requires initialiser parameter.
Definition: collision_scene.h:157
Eigen::Vector3d contact_normal
Definition: collision_scene.h:101
size_t getNumberOfEntries() const
Definition: collision_scene.h:75
void SetWorldLinkScale(const double scale)
Definition: collision_scene.h:251
void SetRobotLinkScale(const double scale)
Definition: collision_scene.h:242
bool in_collision
Definition: collision_scene.h:96
EIGEN_MAKE_ALIGNED_OPERATOR_NEW CollisionProxy()
Definition: collision_scene.h:123
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
virtual std::vector< std::string > GetCollisionRobotLinks()=0
Gets the collision robot links.
virtual void UpdateCollisionObjectTransforms()=0
Updates collision object transformations from the kinematic tree.
std::shared_ptr< KinematicElement > e2
Definition: collision_scene.h:125
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
Definition: property.h:98
virtual std::vector< CollisionProxy > GetCollisionDistance(bool self)
Computes collision distances.
Definition: collision_scene.h:179
double GetWorldLinkScale() const
Definition: collision_scene.h:250
Definition: cartpole_dynamics_solver.h:38
virtual void UpdateCollisionObjects(const std::map< std::string, std::weak_ptr< KinematicElement >> &objects)=0
Creates the collision scene from kinematic elements.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW ContinuousCollisionProxy()
Definition: collision_scene.h:91
KDL::Frame contact_tf2
Definition: collision_scene.h:95
CollisionScene()
Definition: collision_scene.h:151
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
std::string Print() const
Definition: collision_scene.h:104
double robot_link_padding_
Robot link padding.
Definition: collision_scene.h:326
virtual ~CollisionScene()
Definition: collision_scene.h:152
#define HIGHLIGHT_NAMED(name, x)
Definition: printable.h:62
std::shared_ptr< KinematicElement > e1
Definition: collision_scene.h:92
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
virtual std::vector< CollisionProxy > GetCollisionDistance(const std::string &o1, const std::string &o2)
Computes collision distances between two objects.
Definition: collision_scene.h:184
void SetAlwaysExternallyUpdatedCollisionScene(const bool value)
Definition: collision_scene.h:236
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
AllowedCollisionMatrix()
Definition: collision_scene.h:53
bool GetReplacePrimitiveShapesWithMeshes() const
Definition: collision_scene.h:277
AllowedCollisionMatrix(const AllowedCollisionMatrix &acm)
Definition: collision_scene.h:55
Eigen::Vector3d contact2
Definition: collision_scene.h:128
bool GetAlwaysExternallyUpdatedCollisionScene() const
Definition: collision_scene.h:235
AllowedCollisionMatrix & operator=(const AllowedCollisionMatrix &other)
Definition: collision_scene.h:56
AllowedCollisionMatrix acm_
The allowed collision matrix.
Definition: collision_scene.h:314
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: property.h:70
double penetration_depth
Definition: collision_scene.h:100
std::string robot_link_replacement_config_
Filename for config file (YAML) which contains shape replacements.
Definition: collision_scene.h:338
bool get_replace_cylinders_with_capsules() const
Definition: collision_scene.h:291
double GetRobotLinkScale() const
Definition: collision_scene.h:241
void setEntry(const std::string &name1, const std::string &name2)
Definition: collision_scene.h:66
std::shared_ptr< CollisionScene > CollisionScenePtr
Definition: collision_scene.h:341
bool always_externally_updated_collision_scene_
Whether the collision scene is automatically updated - if not, update on queries.
Definition: collision_scene.h:317
~AllowedCollisionMatrix()
Definition: collision_scene.h:54
Eigen::Vector3d contact_pos
Definition: collision_scene.h:102
double time_of_contact
Definition: collision_scene.h:97
double robot_link_scale_
Robot link scaling.
Definition: collision_scene.h:320
virtual Eigen::Vector3d GetTranslation(const std::string &name)=0
Returns the translation of the named collision object.
double GetRobotLinkPadding() const
Definition: collision_scene.h:259
virtual void InstantiateBase(const Initializer &init)
Instantiates the base properties of the CollisionScene.
bool hasEntry(const std::string &name) const
Definition: collision_scene.h:65
Eigen::Vector3d normal1
Definition: collision_scene.h:127
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
The class of collision scene.
Definition: collision_scene.h:148
void set_replace_cylinders_with_capsules(const bool value)
Definition: collision_scene.h:292
bool debug_
Definition: collision_scene.h:298
void clear()
Definition: collision_scene.h:64
#define ThrowPretty(m)
Definition: exception.h:36
bool replace_cylinders_with_capsules_
Replace cylinders with capsules internally.
Definition: collision_scene.h:335
double distance
Definition: collision_scene.h:130
double GetWorldLinkPadding() const
Definition: collision_scene.h:268
Definition: collision_scene.h:119
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
Eigen::Vector3d contact1
Definition: collision_scene.h:126
Eigen::Vector3d normal2
Definition: collision_scene.h:129
virtual std::vector< std::string > GetCollisionWorldLinks()=0
Gets the collision world links.
double world_link_scale_
World link scaling.
Definition: collision_scene.h:323
std::string Print() const
Definition: collision_scene.h:132
virtual bool IsStateValid(bool self=true, double safe_distance=0.0)=0
Checks if the whole robot is valid (collision only).
void SetRobotLinkPadding(const double padding)
Definition: collision_scene.h:260
void SetReplacePrimitiveShapesWithMeshes(const bool value)
Definition: collision_scene.h:278
void AssignScene(std::shared_ptr< Scene > scene)
Sets a scene pointer to the CollisionScene for access to methods.
Definition: collision_scene.h:301
Definition: collision_scene.h:50
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
std::shared_ptr< KinematicElement > e1
Definition: collision_scene.h:124
bool needs_update_of_collision_objects_
Indicates whether TriggerUpdateCollisionObjects needs to be called.
Definition: collision_scene.h:308
void getAllEntryNames(std::vector< std::string > &names) const
Definition: collision_scene.h:67