bullet_cast_simple_manager.h
Go to the documentation of this file.
1 
41 #ifndef TESSERACT_COLLISION_BULLET_CAST_SIMPLE_MANAGERS_H
42 #define TESSERACT_COLLISION_BULLET_CAST_SIMPLE_MANAGERS_H
43 
47 
49 {
52 {
53 public:
54  using Ptr = std::shared_ptr<BulletCastSimpleManager>;
55  using ConstPtr = std::shared_ptr<const BulletCastSimpleManager>;
56  using UPtr = std::unique_ptr<BulletCastSimpleManager>;
57  using ConstUPtr = std::unique_ptr<const BulletCastSimpleManager>;
58 
59  BulletCastSimpleManager(std::string name = "BulletCastSimpleManager",
61  ~BulletCastSimpleManager() override = default;
66 
67  std::string getName() const override final;
68 
69  ContinuousContactManager::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  void setCollisionObjectsTransform(const std::string& name,
100  const Eigen::Isometry3d& pose1,
101  const Eigen::Isometry3d& pose2) override final;
102 
103  void setCollisionObjectsTransform(const std::vector<std::string>& names,
104  const tesseract_common::VectorIsometry3d& pose1,
105  const tesseract_common::VectorIsometry3d& pose2) override final;
106 
108  const tesseract_common::TransformMap& pose2) override final;
109 
110  const std::vector<std::string>& getCollisionObjects() const override final;
111 
112  void setActiveCollisionObjects(const std::vector<std::string>& names) override final;
113 
114  const std::vector<std::string>& getActiveCollisionObjects() const override final;
115 
116  void setCollisionMarginData(CollisionMarginData collision_margin_data) override final;
117 
118  const CollisionMarginData& getCollisionMarginData() const override final;
119 
121  const CollisionMarginPairData& pair_margin_data,
122  CollisionMarginPairOverrideType override_type = CollisionMarginPairOverrideType::REPLACE) override final;
123 
124  void setDefaultCollisionMargin(double default_collision_margin) override final;
125 
126  void setCollisionMarginPair(const std::string& name1,
127  const std::string& name2,
128  double collision_margin) override final;
129 
130  void incrementCollisionMargin(double increment) override final;
131 
132  void
133  setContactAllowedValidator(std::shared_ptr<const tesseract_common::ContactAllowedValidator> validator) override final;
134 
135  std::shared_ptr<const tesseract_common::ContactAllowedValidator> getContactAllowedValidator() const override final;
136 
137  void contactTest(ContactResultMap& collisions, const ContactRequest& request) override final;
138 
143  void addCollisionObject(const COW::Ptr& cow);
144 
145 private:
146  std::string name_;
148  std::vector<std::string> active_;
150  std::vector<std::string> collision_objects_;
152  std::unique_ptr<btCollisionDispatcher> dispatcher_;
154  btDispatcherInfo dispatch_info_;
162  std::vector<COW::Ptr> cows_;
165 
171 
174 };
175 
176 } // namespace tesseract_collision::tesseract_collision_bullet
177 
178 #endif // TESSERACT_COLLISION_BULLET_CAST_SIMPLE_MANAGERS_H
VectorIsometry3d
AlignedVector< Eigen::Isometry3d > VectorIsometry3d
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::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_cast_simple_manager.cpp:367
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::dispatch_info_
btDispatcherInfo dispatch_info_
The bullet collision dispatcher configuration information.
Definition: bullet_cast_simple_manager.h:154
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::setActiveCollisionObjects
void setActiveCollisionObjects(const std::vector< std::string > &names) override final
Set which collision objects can move.
Definition: bullet_cast_simple_manager.cpp:307
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::BulletCastSimpleManager::setCollisionMarginPairData
void setCollisionMarginPairData(const CollisionMarginPairData &pair_margin_data, CollisionMarginPairOverrideType override_type=CollisionMarginPairOverrideType::REPLACE) override final
Set the pair contact distance thresholds for which collision should be considered on a per pair basis...
Definition: bullet_cast_simple_manager.cpp:354
tesseract_common
tesseract_collision::tesseract_collision_bullet::TesseractCollisionConfigurationInfo
Definition: tesseract_collision_configuration.h:52
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::cows_
std::vector< COW::Ptr > cows_
A vector of collision objects (active followed by static)
Definition: bullet_cast_simple_manager.h:162
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::clone
ContinuousContactManager::UPtr clone() const override final
Clone the manager.
Definition: bullet_cast_simple_manager.cpp:67
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::getCollisionObjects
const std::vector< std::string > & getCollisionObjects() const override final
Get all collision objects.
Definition: bullet_cast_simple_manager.cpp:305
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::coll_config_
TesseractCollisionConfiguration coll_config_
The bullet collision configuration.
Definition: bullet_cast_simple_manager.h:158
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::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_cast_simple_manager.h:170
tesseract_collision_configuration.h
Modified bullet collision configuration.
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::onCollisionMarginDataChanged
void onCollisionMarginDataChanged()
This function will update internal data when margin data has changed.
Definition: bullet_cast_simple_manager.cpp:478
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::incrementCollisionMargin
void incrementCollisionMargin(double increment) override final
Increment the collision margin data by some value.
Definition: bullet_cast_simple_manager.cpp:375
tesseract_collision::tesseract_collision_bullet::TesseractCollisionConfiguration
This is a modified configuration that included the modified Bullet algorithms.
Definition: tesseract_collision_configuration.h:81
TransformMap
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::operator=
BulletCastSimpleManager & operator=(const BulletCastSimpleManager &)=delete
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::link2castcow_
Link2Cow link2castcow_
A map of cast collision objects being managed.
Definition: bullet_cast_simple_manager.h:164
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::ConstPtr
std::shared_ptr< const BulletCastSimpleManager > ConstPtr
Definition: bullet_cast_simple_manager.h:55
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::config_info_
TesseractCollisionConfigurationInfo config_info_
The bullet collision configuration information.
Definition: bullet_cast_simple_manager.h:156
tesseract_common::CollisionMarginData
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::UPtr
std::unique_ptr< BulletCastSimpleManager > UPtr
Definition: bullet_cast_simple_manager.h:56
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::Ptr
std::shared_ptr< BulletCastSimpleManager > Ptr
Definition: bullet_cast_simple_manager.h:54
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::active_
std::vector< std::string > active_
A list of the active collision objects.
Definition: bullet_cast_simple_manager.h:148
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::link2cow_
Link2Cow link2cow_
A map of collision objects being managed.
Definition: bullet_cast_simple_manager.h:160
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::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 collision object to the checker.
Definition: bullet_cast_simple_manager.cpp:93
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::getCollisionMarginData
const CollisionMarginData & getCollisionMarginData() const override final
Get the contact distance threshold.
Definition: bullet_cast_simple_manager.cpp:349
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::getName
std::string getName() const override final
Get the name of the contact manager.
Definition: bullet_cast_simple_manager.cpp:65
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::hasCollisionObject
bool hasCollisionObject(const std::string &name) const override final
Find if a collision object already exists.
Definition: bullet_cast_simple_manager.cpp:129
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::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_cast_simple_manager.cpp:387
tesseract_collision::tesseract_collision_bullet::Link2Cow
std::map< std::string, COW::Ptr > Link2Cow
Definition: bullet_utils.h:151
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::disableCollisionObject
bool disableCollisionObject(const std::string &name) override final
Disable an object.
Definition: bullet_cast_simple_manager.cpp:162
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::getActiveCollisionObjects
const std::vector< std::string > & getActiveCollisionObjects() const override final
Get which collision objects can move.
Definition: bullet_cast_simple_manager.cpp:341
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::getCollisionObjectGeometriesTransforms
const tesseract_common::VectorIsometry3d & getCollisionObjectGeometriesTransforms(const std::string &name) const override final
Get a collision objects collision geometries transforms.
Definition: bullet_cast_simple_manager.cpp:122
tesseract_collision::ContinuousContactManager
Definition: continuous_contact_manager.h:41
tesseract_collision::ContactResultMap
This structure hold contact results for link pairs.
Definition: types.h:155
tesseract_common::CollisionMarginPairOverrideType
CollisionMarginPairOverrideType
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::BulletCastSimpleManager::setCollisionMarginData
void setCollisionMarginData(CollisionMarginData collision_margin_data) override final
Set the contact distance threshold.
Definition: bullet_cast_simple_manager.cpp:343
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::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_cast_simple_manager.cpp:381
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::setCollisionObjectsTransform
void setCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose) override final
Set a single static collision object's tansforms.
Definition: bullet_cast_simple_manager.cpp:184
tesseract_collision::CollisionShapesConst
std::vector< CollisionShapeConstPtr > CollisionShapesConst
Definition: types.h:51
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::BulletCastSimpleManager
BulletCastSimpleManager(std::string name="BulletCastSimpleManager", TesseractCollisionConfigurationInfo config_info=TesseractCollisionConfigurationInfo())
Definition: bullet_cast_simple_manager.cpp:50
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::removeCollisionObject
bool removeCollisionObject(const std::string &name) override final
Remove an object from the checker.
Definition: bullet_cast_simple_manager.cpp:134
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::ConstUPtr
std::unique_ptr< const BulletCastSimpleManager > ConstUPtr
Definition: bullet_cast_simple_manager.h:57
tesseract_common::CollisionMarginPairData
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::enableCollisionObject
bool enableCollisionObject(const std::string &name) override final
Enable an object.
Definition: bullet_cast_simple_manager.cpp:149
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::setDefaultCollisionMargin
void setDefaultCollisionMargin(double default_collision_margin) override final
Set the default collision margin.
Definition: bullet_cast_simple_manager.cpp:361
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::dispatcher_
std::unique_ptr< btCollisionDispatcher > dispatcher_
The bullet collision dispatcher used for getting object to object collison algorithm.
Definition: bullet_cast_simple_manager.h:152
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::collision_objects_
std::vector< std::string > collision_objects_
A list of the collision objects.
Definition: bullet_cast_simple_manager.h:150
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::name_
std::string name_
Definition: bullet_cast_simple_manager.h:146
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::isCollisionObjectEnabled
bool isCollisionObjectEnabled(const std::string &name) const override final
Check if collision object is enabled.
Definition: bullet_cast_simple_manager.cpp:175
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::~BulletCastSimpleManager
~BulletCastSimpleManager() override=default
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager
A simple implementation of a tesseract manager which does not use BHV.
Definition: bullet_cast_simple_manager.h:51
tesseract_collision::ContactRequest
The ContactRequest struct.
Definition: types.h:300
continuous_contact_manager.h
This is the continuous contact manager base class.
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::contactTest
void contactTest(ContactResultMap &collisions, const ContactRequest &request) override final
Perform a contact test for all objects based.
Definition: bullet_cast_simple_manager.cpp:391
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::getCollisionObjectGeometries
const CollisionShapesConst & getCollisionObjectGeometries(const std::string &name) const override final
Get a collision objects collision geometries.
Definition: bullet_cast_simple_manager.cpp:114


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