Go to the documentation of this file.
44 class BulletBVHManager
47 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
57 BulletBVHManagerPtr
clone()
const;
122 std::map<std::string, CollisionObjectWrapperPtr>
link2cow_;
125 std::vector<std::string>
active_;
131 std::unique_ptr<btCollisionDispatcher>
dispatcher_;
140 std::unique_ptr<btBroadphaseInterface>
broadphase_;
void setCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose)
Set a single static collision object's tansform.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW BulletBVHManager()
Constructor.
std::unique_ptr< btCollisionDispatcher > dispatcher_
The bullet collision dispatcher used for getting object to object collison algorithm.
std::unique_ptr< btBroadphaseInterface > broadphase_
The bullet broadphase interface.
virtual ~BulletBVHManager()
std::vector< std::string > active_
A list of the active collision links.
bool disableCollisionObject(const std::string &name)
Disable an object.
bool hasCollisionObject(const std::string &name) const
Find if a collision object already exists.
Representation of a collision checking request.
void setActiveCollisionObjects(const std::vector< std::string > &names)
Set which collision objects are active.
Definition of a structure for the allowed collision matrix.
btDefaultCollisionConfiguration coll_config_
The bullet collision configuration.
Representation of a collision checking result.
std::map< std::string, CollisionObjectWrapperPtr > link2cow_
A map of collision objects being managed.
const std::vector< std::string > & getActiveCollisionObjects() const
Get which collision objects are active.
virtual void addCollisionObject(const CollisionObjectWrapperPtr &cow)=0
Add a collision object to the checker.
double getContactDistanceThreshold() const
Get the contact distance threshold.
BulletBVHManagerPtr clone() const
Clone the manager.
const std::map< std::string, CollisionObjectWrapperPtr > & getCollisionObjects() const
btDispatcherInfo dispatch_info_
The bullet collision dispatcher configuration information.
bool removeCollisionObject(const std::string &name)
Remove an object from the checker.
bool enableCollisionObject(const std::string &name)
Enable an object.
double contact_distance_
The contact distance threshold.
MOVEIT_CLASS_FORWARD(BulletBVHManager)
BroadphaseFilterCallback filter_callback_
Callback function for culling objects before a broadphase check.
virtual void contactTest(collision_detection::CollisionResult &collisions, const collision_detection::CollisionRequest &req, const collision_detection::AllowedCollisionMatrix *acm, bool self)=0
Perform a contact test for all objects.
void setContactDistanceThreshold(double contact_distance)
Set the contact distance threshold for which collision should be considered through expanding the AAB...
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:14