bullet_discrete_simple_manager.h
Go to the documentation of this file.
1 
41 #ifndef TESSERACT_COLLISION_BULLET_DISCRETE_SIMPLE_MANAGERS_H
42 #define TESSERACT_COLLISION_BULLET_DISCRETE_SIMPLE_MANAGERS_H
43 
47 
49 {
52 {
53 public:
54  using Ptr = std::shared_ptr<BulletDiscreteSimpleManager>;
55  using ConstPtr = std::shared_ptr<const BulletDiscreteSimpleManager>;
56  using UPtr = std::unique_ptr<BulletDiscreteSimpleManager>;
57  using ConstUPtr = std::unique_ptr<const BulletDiscreteSimpleManager>;
58 
59  BulletDiscreteSimpleManager(std::string name = "BulletDiscreteSimpleManager",
61  ~BulletDiscreteSimpleManager() override = default;
66 
67  std::string getName() const override final;
68 
69  DiscreteContactManager::UPtr clone() const override final;
70 
71  bool addCollisionObject(const std::string& name,
72  const int& mask_id,
73  const CollisionShapesConst& shapes,
74  const tesseract_common::VectorIsometry3d& shape_poses,
75  bool enabled = true) override final;
76 
77  const CollisionShapesConst& getCollisionObjectGeometries(const std::string& name) const override final;
78 
80  getCollisionObjectGeometriesTransforms(const std::string& name) const override final;
81 
82  bool hasCollisionObject(const std::string& name) const override final;
83 
84  bool removeCollisionObject(const std::string& name) override final;
85 
86  bool enableCollisionObject(const std::string& name) override final;
87 
88  bool disableCollisionObject(const std::string& name) override final;
89 
90  bool isCollisionObjectEnabled(const std::string& name) const override final;
91 
92  void setCollisionObjectsTransform(const std::string& name, const Eigen::Isometry3d& pose) override final;
93 
94  void setCollisionObjectsTransform(const std::vector<std::string>& names,
95  const tesseract_common::VectorIsometry3d& poses) override final;
96 
97  void setCollisionObjectsTransform(const tesseract_common::TransformMap& transforms) override final;
98 
99  const std::vector<std::string>& getCollisionObjects() const override final;
100 
101  void setActiveCollisionObjects(const std::vector<std::string>& names) override final;
102 
103  const std::vector<std::string>& getActiveCollisionObjects() const override final;
104 
105  void setCollisionMarginData(CollisionMarginData collision_margin_data) override final;
106 
107  const CollisionMarginData& getCollisionMarginData() const override final;
108 
110  const CollisionMarginPairData& pair_margin_data,
111  CollisionMarginPairOverrideType override_type = CollisionMarginPairOverrideType::REPLACE) override final;
112 
113  void setDefaultCollisionMargin(double default_collision_margin) override final;
114 
115  void setCollisionMarginPair(const std::string& name1,
116  const std::string& name2,
117  double collision_margin) override final;
118 
119  void incrementCollisionMargin(double increment) override final;
120 
121  void
122  setContactAllowedValidator(std::shared_ptr<const tesseract_common::ContactAllowedValidator> validator) override final;
123 
124  std::shared_ptr<const tesseract_common::ContactAllowedValidator> getContactAllowedValidator() const override final;
125 
126  void contactTest(ContactResultMap& collisions, const ContactRequest& request) override final;
127 
132  void addCollisionObject(const COW::Ptr& cow);
133 
134 private:
135  std::string name_;
137  std::vector<std::string> active_;
139  std::vector<std::string> collision_objects_;
141  std::unique_ptr<btCollisionDispatcher> dispatcher_;
143  btDispatcherInfo dispatch_info_;
151  std::vector<COW::Ptr> cows_;
152 
158 
161 };
162 
163 } // namespace tesseract_collision::tesseract_collision_bullet
164 #endif // TESSERACT_COLLISION_BULLET_DISCRETE_SIMPLE_MANAGERS_H
VectorIsometry3d
AlignedVector< Eigen::Isometry3d > VectorIsometry3d
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::removeCollisionObject
bool removeCollisionObject(const std::string &name) override final
Remove an object from the checker.
Definition: bullet_discrete_simple_manager.cpp:136
tesseract_collision::tesseract_collision_bullet
Definition: bullet_cast_bvh_manager.h:48
tesseract_collision::ContactTestData
This data is intended only to be used internal to the collision checkers as a container and should no...
Definition: types.h:328
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::getCollisionMarginData
const CollisionMarginData & getCollisionMarginData() const override final
Get the contact distance threshold.
Definition: bullet_discrete_simple_manager.cpp:235
tesseract_common
tesseract_collision::tesseract_collision_bullet::TesseractCollisionConfigurationInfo
Definition: tesseract_collision_configuration.h:52
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::dispatcher_
std::unique_ptr< btCollisionDispatcher > dispatcher_
The bullet collision dispatcher used for getting object to object collison algorithm.
Definition: bullet_discrete_simple_manager.h:141
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::getActiveCollisionObjects
const std::vector< std::string > & getActiveCollisionObjects() const override final
Get which collision objects can move.
Definition: bullet_discrete_simple_manager.cpp:227
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::BulletDiscreteSimpleManager
BulletDiscreteSimpleManager(std::string name="BulletDiscreteSimpleManager", TesseractCollisionConfigurationInfo config_info=TesseractCollisionConfigurationInfo())
Definition: bullet_discrete_simple_manager.cpp:50
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::operator=
BulletDiscreteSimpleManager & operator=(const BulletDiscreteSimpleManager &)=delete
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::ConstUPtr
std::unique_ptr< const BulletDiscreteSimpleManager > ConstUPtr
Definition: bullet_discrete_simple_manager.h:57
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::getCollisionObjectGeometriesTransforms
const tesseract_common::VectorIsometry3d & getCollisionObjectGeometriesTransforms(const std::string &name) const override final
Get a collision objects collision geometries transforms.
Definition: bullet_discrete_simple_manager.cpp:124
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::onCollisionMarginDataChanged
void onCollisionMarginDataChanged()
This function will update internal data when margin data has changed.
Definition: bullet_discrete_simple_manager.cpp:357
tesseract_collision_configuration.h
Modified bullet collision configuration.
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::getCollisionObjects
const std::vector< std::string > & getCollisionObjects() const override final
Get all collision objects.
Definition: bullet_discrete_simple_manager.cpp:204
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::getName
std::string getName() const override final
Get the name of the contact manager.
Definition: bullet_discrete_simple_manager.cpp:67
tesseract_collision::tesseract_collision_bullet::TesseractCollisionConfiguration
This is a modified configuration that included the modified Bullet algorithms.
Definition: tesseract_collision_configuration.h:81
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::collision_objects_
std::vector< std::string > collision_objects_
A list of the collision objects.
Definition: bullet_discrete_simple_manager.h:139
TransformMap
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::incrementCollisionMargin
void incrementCollisionMargin(double increment) override final
Increment the collision margin data by some value.
Definition: bullet_discrete_simple_manager.cpp:261
discrete_contact_manager.h
This is the discrete contact manager base class.
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::setCollisionMarginPairData
void setCollisionMarginPairData(const CollisionMarginPairData &pair_margin_data, CollisionMarginPairOverrideType override_type=CollisionMarginPairOverrideType::REPLACE) override final
Set the contact distance thresholds for which collision should be considered on a per pair basis.
Definition: bullet_discrete_simple_manager.cpp:240
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::setDefaultCollisionMargin
void setDefaultCollisionMargin(double default_collision_margin) override final
Set the default collision margin.
Definition: bullet_discrete_simple_manager.cpp:247
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::contactTest
void contactTest(ContactResultMap &collisions, const ContactRequest &request) override final
Perform a contact test for all objects based.
Definition: bullet_discrete_simple_manager.cpp:277
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::addCollisionObject
bool addCollisionObject(const std::string &name, const int &mask_id, const CollisionShapesConst &shapes, const tesseract_common::VectorIsometry3d &shape_poses, bool enabled=true) override final
Add a object to the checker.
Definition: bullet_discrete_simple_manager.cpp:95
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::setCollisionObjectsTransform
void setCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose) override final
Set a single collision object's transforms.
Definition: bullet_discrete_simple_manager.cpp:181
tesseract_collision::DiscreteContactManager
Definition: discrete_contact_manager.h:41
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::setCollisionMarginData
void setCollisionMarginData(CollisionMarginData collision_margin_data) override final
Set the contact distance threshold.
Definition: bullet_discrete_simple_manager.cpp:229
tesseract_common::CollisionMarginData
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::ConstPtr
std::shared_ptr< const BulletDiscreteSimpleManager > ConstPtr
Definition: bullet_discrete_simple_manager.h:55
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::active_
std::vector< std::string > active_
A list of the active collision objects.
Definition: bullet_discrete_simple_manager.h:137
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::cows_
std::vector< COW::Ptr > cows_
A vector of collision objects (active followed by static)
Definition: bullet_discrete_simple_manager.h:151
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::clone
DiscreteContactManager::UPtr clone() const override final
Clone the manager.
Definition: bullet_discrete_simple_manager.cpp:69
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::disableCollisionObject
bool disableCollisionObject(const std::string &name) override final
Disable an object.
Definition: bullet_discrete_simple_manager.cpp:161
tesseract_collision::tesseract_collision_bullet::Link2Cow
std::map< std::string, COW::Ptr > Link2Cow
Definition: bullet_utils.h:151
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::getCollisionObjectGeometries
const CollisionShapesConst & getCollisionObjectGeometries(const std::string &name) const override final
Get a collision objects collision geometries.
Definition: bullet_discrete_simple_manager.cpp:116
tesseract_collision::ContactResultMap
This structure hold contact results for link pairs.
Definition: types.h:155
tesseract_common::CollisionMarginPairOverrideType
CollisionMarginPairOverrideType
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::UPtr
std::unique_ptr< BulletDiscreteSimpleManager > UPtr
Definition: bullet_discrete_simple_manager.h:56
bullet_utils.h
Tesseract ROS Bullet environment utility function.
tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper
This is a tesseract bullet collsion object.
Definition: bullet_utils.h:89
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::isCollisionObjectEnabled
bool isCollisionObjectEnabled(const std::string &name) const override final
Check if collision object is enabled.
Definition: bullet_discrete_simple_manager.cpp:172
tesseract_collision::CollisionShapesConst
std::vector< CollisionShapeConstPtr > CollisionShapesConst
Definition: types.h:51
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::getContactAllowedValidator
std::shared_ptr< const tesseract_common::ContactAllowedValidator > getContactAllowedValidator() const override final
Get the active function for determining if two links are allowed to be in collision.
Definition: bullet_discrete_simple_manager.cpp:273
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::Ptr
std::shared_ptr< BulletDiscreteSimpleManager > Ptr
Definition: bullet_discrete_simple_manager.h:54
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::link2cow_
Link2Cow link2cow_
A map of all (static and active) collision objects being managed.
Definition: bullet_discrete_simple_manager.h:149
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::setCollisionMarginPair
void setCollisionMarginPair(const std::string &name1, const std::string &name2, double collision_margin) override final
Set the margin for a given contact pair.
Definition: bullet_discrete_simple_manager.cpp:253
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::contact_test_data_
ContactTestData contact_test_data_
This is used when contactTest is called. It is also added as a user point to the collsion objects so ...
Definition: bullet_discrete_simple_manager.h:157
tesseract_common::CollisionMarginPairData
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::~BulletDiscreteSimpleManager
~BulletDiscreteSimpleManager() override=default
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::setActiveCollisionObjects
void setActiveCollisionObjects(const std::vector< std::string > &names) override final
Set which collision objects can move.
Definition: bullet_discrete_simple_manager.cpp:206
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::hasCollisionObject
bool hasCollisionObject(const std::string &name) const override final
Find if a collision object already exists.
Definition: bullet_discrete_simple_manager.cpp:131
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::coll_config_
TesseractCollisionConfiguration coll_config_
The bullet collision configuration.
Definition: bullet_discrete_simple_manager.h:147
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::name_
std::string name_
Definition: bullet_discrete_simple_manager.h:135
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::enableCollisionObject
bool enableCollisionObject(const std::string &name) override final
Enable an object.
Definition: bullet_discrete_simple_manager.cpp:150
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager
A simple implementation of a bullet manager which does not use BHV.
Definition: bullet_discrete_simple_manager.h:51
tesseract_collision::ContactRequest
The ContactRequest struct.
Definition: types.h:300
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::setContactAllowedValidator
void setContactAllowedValidator(std::shared_ptr< const tesseract_common::ContactAllowedValidator > validator) override final
Set the active function for determining if two links are allowed to be in collision.
Definition: bullet_discrete_simple_manager.cpp:267
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::config_info_
TesseractCollisionConfigurationInfo config_info_
The bullet collision configuration information.
Definition: bullet_discrete_simple_manager.h:145
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::dispatch_info_
btDispatcherInfo dispatch_info_
The bullet collision dispatcher configuration information.
Definition: bullet_discrete_simple_manager.h:143


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