discrete_contact_manager.h
Go to the documentation of this file.
1 
28 #ifndef TESSERACT_COLLISION_DISCRETE_CONTACT_MANAGER_H
29 #define TESSERACT_COLLISION_DISCRETE_CONTACT_MANAGER_H
30 
33 #include <memory>
35 
37 #include <tesseract_common/fwd.h>
38 
39 namespace tesseract_collision
40 {
42 {
43 public:
44  // LCOV_EXCL_START
45  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
46  // LCOV_EXCL_STOP
47 
48  using Ptr = std::shared_ptr<DiscreteContactManager>;
49  using ConstPtr = std::shared_ptr<const DiscreteContactManager>;
50  using UPtr = std::unique_ptr<DiscreteContactManager>;
51  using ConstUPtr = std::unique_ptr<const DiscreteContactManager>;
52 
53  DiscreteContactManager() = default;
54  virtual ~DiscreteContactManager() = default;
59 
64  virtual std::string getName() const = 0;
65 
72  virtual DiscreteContactManager::UPtr clone() const = 0;
73 
82  virtual bool addCollisionObject(const std::string& name,
83  const int& mask_id,
84  const CollisionShapesConst& shapes,
85  const tesseract_common::VectorIsometry3d& shape_poses,
86  bool enabled = true) = 0;
87 
93  virtual const CollisionShapesConst& getCollisionObjectGeometries(const std::string& name) const = 0;
94 
101  getCollisionObjectGeometriesTransforms(const std::string& name) const = 0;
102 
108  virtual bool hasCollisionObject(const std::string& name) const = 0;
109 
115  virtual bool removeCollisionObject(const std::string& name) = 0;
116 
121  virtual bool enableCollisionObject(const std::string& name) = 0;
122 
127  virtual bool disableCollisionObject(const std::string& name) = 0;
128 
134  virtual bool isCollisionObjectEnabled(const std::string& name) const = 0;
135 
141  virtual void setCollisionObjectsTransform(const std::string& name, const Eigen::Isometry3d& pose) = 0;
142 
148  virtual void setCollisionObjectsTransform(const std::vector<std::string>& names,
149  const tesseract_common::VectorIsometry3d& poses) = 0;
150 
155  virtual void setCollisionObjectsTransform(const tesseract_common::TransformMap& transforms) = 0;
156 
161  virtual const std::vector<std::string>& getCollisionObjects() const = 0;
162 
167  virtual void setActiveCollisionObjects(const std::vector<std::string>& names) = 0;
168 
173  virtual const std::vector<std::string>& getActiveCollisionObjects() const = 0;
174 
179  virtual void setCollisionMarginData(CollisionMarginData collision_margin_data) = 0;
180 
185  virtual const CollisionMarginData& getCollisionMarginData() const = 0;
186 
192  virtual void setCollisionMarginPairData(
193  const CollisionMarginPairData& pair_margin_data,
194  CollisionMarginPairOverrideType override_type = CollisionMarginPairOverrideType::REPLACE) = 0;
195 
200  virtual void setDefaultCollisionMargin(double default_collision_margin) = 0;
201 
212  virtual void setCollisionMarginPair(const std::string& name1, const std::string& name2, double collision_margin) = 0;
213 
218  virtual void incrementCollisionMargin(double increment) = 0;
219 
221  virtual void
222  setContactAllowedValidator(std::shared_ptr<const tesseract_common::ContactAllowedValidator> validator) = 0;
223 
225  virtual std::shared_ptr<const tesseract_common::ContactAllowedValidator> getContactAllowedValidator() const = 0;
226 
232  virtual void contactTest(ContactResultMap& collisions, const ContactRequest& request) = 0;
233 
238  virtual void applyContactManagerConfig(const ContactManagerConfig& config);
239 };
240 
241 } // namespace tesseract_collision
242 #endif // TESSERACT_COLLISION_DISCRETE_CONTACT_MANAGER_H
tesseract_collision::DiscreteContactManager::isCollisionObjectEnabled
virtual bool isCollisionObjectEnabled(const std::string &name) const =0
Check if collision object is enabled.
tesseract_common::VectorIsometry3d
AlignedVector< Eigen::Isometry3d > VectorIsometry3d
tesseract_collision::DiscreteContactManager::setCollisionMarginPair
virtual void setCollisionMarginPair(const std::string &name1, const std::string &name2, double collision_margin)=0
Set the margin for a given contact pair.
tesseract_collision::DiscreteContactManager::operator=
DiscreteContactManager & operator=(const DiscreteContactManager &)=delete
tesseract_collision::DiscreteContactManager::ConstUPtr
std::unique_ptr< const DiscreteContactManager > ConstUPtr
Definition: discrete_contact_manager.h:51
tesseract_collision::ContactManagerConfig
Contains parameters used to configure a contact manager before a series of contact checks.
Definition: types.h:420
types.h
Tesseracts Collision Forward Declarations.
tesseract_collision::DiscreteContactManager::getActiveCollisionObjects
virtual const std::vector< std::string > & getActiveCollisionObjects() const =0
Get which collision objects can move.
tesseract_collision::DiscreteContactManager::setCollisionMarginData
virtual void setCollisionMarginData(CollisionMarginData collision_margin_data)=0
Set the contact distance threshold.
tesseract_collision::DiscreteContactManager::setDefaultCollisionMargin
virtual void setDefaultCollisionMargin(double default_collision_margin)=0
Set the default collision margin.
tesseract_collision::DiscreteContactManager::setContactAllowedValidator
virtual void setContactAllowedValidator(std::shared_ptr< const tesseract_common::ContactAllowedValidator > validator)=0
Set the active function for determining if two links are allowed to be in collision.
tesseract_common::TransformMap
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
tesseract_collision::DiscreteContactManager::ConstPtr
std::shared_ptr< const DiscreteContactManager > ConstPtr
Definition: discrete_contact_manager.h:49
tesseract_collision::DiscreteContactManager::removeCollisionObject
virtual bool removeCollisionObject(const std::string &name)=0
Remove an object from the checker.
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_collision::DiscreteContactManager::getContactAllowedValidator
virtual std::shared_ptr< const tesseract_common::ContactAllowedValidator > getContactAllowedValidator() const =0
Get the active function for determining if two links are allowed to be in collision.
tesseract_collision::DiscreteContactManager
Definition: discrete_contact_manager.h:41
tesseract_common::CollisionMarginData
tesseract_collision::DiscreteContactManager::disableCollisionObject
virtual bool disableCollisionObject(const std::string &name)=0
Disable an object.
tesseract_collision::DiscreteContactManager::clone
virtual DiscreteContactManager::UPtr clone() const =0
Clone the manager.
tesseract_collision::ContactResultMap
This structure hold contact results for link pairs.
Definition: types.h:155
tesseract_common::CollisionMarginPairOverrideType
CollisionMarginPairOverrideType
tesseract_collision::DiscreteContactManager::contactTest
virtual void contactTest(ContactResultMap &collisions, const ContactRequest &request)=0
Perform a contact test for all objects based.
tesseract_collision::DiscreteContactManager::addCollisionObject
virtual bool addCollisionObject(const std::string &name, const int &mask_id, const CollisionShapesConst &shapes, const tesseract_common::VectorIsometry3d &shape_poses, bool enabled=true)=0
Add a object to the checker.
tesseract_collision::DiscreteContactManager::incrementCollisionMargin
virtual void incrementCollisionMargin(double increment)=0
Increment the collision margin data by some value.
tesseract_collision::DiscreteContactManager::setCollisionObjectsTransform
virtual void setCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose)=0
Set a single collision object's transforms.
tesseract_collision::DiscreteContactManager::DiscreteContactManager
DiscreteContactManager()=default
tesseract_collision::DiscreteContactManager::hasCollisionObject
virtual bool hasCollisionObject(const std::string &name) const =0
Find if a collision object already exists.
tesseract_collision::DiscreteContactManager::getName
virtual std::string getName() const =0
Get the name of the contact manager.
tesseract_collision::CollisionShapesConst
std::vector< CollisionShapeConstPtr > CollisionShapesConst
Definition: types.h:51
tesseract_collision::DiscreteContactManager::~DiscreteContactManager
virtual ~DiscreteContactManager()=default
TESSERACT_COMMON_IGNORE_WARNINGS_POP
Definition: create_convex_hull.cpp:37
tesseract_collision::DiscreteContactManager::enableCollisionObject
virtual bool enableCollisionObject(const std::string &name)=0
Enable an object.
fwd.h
tesseract_collision::DiscreteContactManager::applyContactManagerConfig
virtual void applyContactManagerConfig(const ContactManagerConfig &config)
Applies settings in the config.
Definition: discrete_contact_manager.cpp:32
tesseract_collision::DiscreteContactManager::setCollisionMarginPairData
virtual void setCollisionMarginPairData(const CollisionMarginPairData &pair_margin_data, CollisionMarginPairOverrideType override_type=CollisionMarginPairOverrideType::REPLACE)=0
Set the contact distance thresholds for which collision should be considered on a per pair basis.
tesseract_collision::DiscreteContactManager::getCollisionObjects
virtual const std::vector< std::string > & getCollisionObjects() const =0
Get all collision objects.
tesseract_common::CollisionMarginPairData
tesseract_collision::DiscreteContactManager::getCollisionObjectGeometriesTransforms
virtual const tesseract_common::VectorIsometry3d & getCollisionObjectGeometriesTransforms(const std::string &name) const =0
Get a collision objects collision geometries transforms.
tesseract_collision::DiscreteContactManager::setActiveCollisionObjects
virtual void setActiveCollisionObjects(const std::vector< std::string > &names)=0
Set which collision objects can move.
tesseract_collision::DiscreteContactManager::getCollisionObjectGeometries
virtual const CollisionShapesConst & getCollisionObjectGeometries(const std::string &name) const =0
Get a collision objects collision geometries.
tesseract_collision::DiscreteContactManager::UPtr
std::unique_ptr< DiscreteContactManager > UPtr
Definition: discrete_contact_manager.h:50
tesseract_collision
Definition: bullet_cast_bvh_manager.h:48
tesseract_collision::DiscreteContactManager::getCollisionMarginData
virtual const CollisionMarginData & getCollisionMarginData() const =0
Get the contact distance threshold.
macros.h
tesseract_collision::DiscreteContactManager::Ptr
std::shared_ptr< DiscreteContactManager > Ptr
Definition: discrete_contact_manager.h:48
tesseract_collision::ContactRequest
The ContactRequest struct.
Definition: types.h:300


tesseract_collision
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:52