Go to the documentation of this file.
41 #ifndef TESSERACT_COLLISION_BULLET_CAST_SIMPLE_MANAGERS_H
42 #define TESSERACT_COLLISION_BULLET_CAST_SIMPLE_MANAGERS_H
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>;
67 std::string
getName() const override final;
75 bool enabled = true) override final;
100 const Eigen::Isometry3d& pose1,
101 const Eigen::Isometry3d& pose2) override final;
127 const std::
string& name2,
128 double collision_margin) override final;
178 #endif // TESSERACT_COLLISION_BULLET_CAST_SIMPLE_MANAGERS_H
AlignedVector< Eigen::Isometry3d > VectorIsometry3d
void setCollisionMarginPair(const std::string &name1, const std::string &name2, double collision_margin) override final
Set the margin for a given contact pair.
btDispatcherInfo dispatch_info_
The bullet collision dispatcher configuration information.
void setActiveCollisionObjects(const std::vector< std::string > &names) override final
Set which collision objects can move.
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...
std::vector< COW::Ptr > cows_
A vector of collision objects (active followed by static)
ContinuousContactManager::UPtr clone() const override final
Clone the manager.
const std::vector< std::string > & getCollisionObjects() const override final
Get all collision objects.
TesseractCollisionConfiguration coll_config_
The bullet collision configuration.
ContactTestData contact_test_data_
This is used when contactTest is called. It is also added as a user point to the collsion objects so ...
Modified bullet collision configuration.
void onCollisionMarginDataChanged()
This function will update internal data when margin data has changed.
void incrementCollisionMargin(double increment) override final
Increment the collision margin data by some value.
This is a modified configuration that included the modified Bullet algorithms.
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
BulletCastSimpleManager & operator=(const BulletCastSimpleManager &)=delete
Link2Cow link2castcow_
A map of cast collision objects being managed.
std::shared_ptr< const BulletCastSimpleManager > ConstPtr
TesseractCollisionConfigurationInfo config_info_
The bullet collision configuration information.
std::unique_ptr< BulletCastSimpleManager > UPtr
std::shared_ptr< BulletCastSimpleManager > Ptr
std::vector< std::string > active_
A list of the active collision objects.
Link2Cow link2cow_
A map of collision objects being managed.
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.
const CollisionMarginData & getCollisionMarginData() const override final
Get the contact distance threshold.
std::string getName() const override final
Get the name of the contact manager.
bool hasCollisionObject(const std::string &name) const override final
Find if a collision object already exists.
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.
std::map< std::string, COW::Ptr > Link2Cow
bool disableCollisionObject(const std::string &name) override final
Disable an object.
const std::vector< std::string > & getActiveCollisionObjects() const override final
Get which collision objects can move.
const tesseract_common::VectorIsometry3d & getCollisionObjectGeometriesTransforms(const std::string &name) const override final
Get a collision objects collision geometries transforms.
CollisionMarginPairOverrideType
Tesseract ROS Bullet environment utility function.
This is a tesseract bullet collsion object.
void setCollisionMarginData(CollisionMarginData collision_margin_data) override final
Set the contact distance threshold.
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.
void setCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose) override final
Set a single static collision object's tansforms.
std::vector< CollisionShapeConstPtr > CollisionShapesConst
BulletCastSimpleManager(std::string name="BulletCastSimpleManager", TesseractCollisionConfigurationInfo config_info=TesseractCollisionConfigurationInfo())
bool removeCollisionObject(const std::string &name) override final
Remove an object from the checker.
std::unique_ptr< const BulletCastSimpleManager > ConstUPtr
bool enableCollisionObject(const std::string &name) override final
Enable an object.
void setDefaultCollisionMargin(double default_collision_margin) override final
Set the default collision margin.
std::unique_ptr< btCollisionDispatcher > dispatcher_
The bullet collision dispatcher used for getting object to object collison algorithm.
std::vector< std::string > collision_objects_
A list of the collision objects.
bool isCollisionObjectEnabled(const std::string &name) const override final
Check if collision object is enabled.
~BulletCastSimpleManager() override=default
A simple implementation of a tesseract manager which does not use BHV.
void contactTest(ContactResultMap &collisions, const ContactRequest &request) override final
Perform a contact test for all objects based.
const CollisionShapesConst & getCollisionObjectGeometries(const std::string &name) const override final
Get a collision objects collision geometries.