57 BulletBVHManagerPtr
clone()
const;
134 std::map<std::string, CollisionObjectWrapperPtr>
link2cow_;
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
A bounding volume hierarchy (BVH) implementation of a tesseract contact manager.
bool hasCollisionObject(const std::string &name) const
Find if a collision object already exists.
std::vector< std::string > active_
A list of the active collision links.
std::unique_ptr< btBroadphaseInterface > broadphase_
The bullet broadphase interface.
double contact_distance_
The contact distance threshold.
BroadphaseFilterCallback filter_callback_
Callback function for culling objects before a broadphase check.
const std::vector< std::string > & getActiveCollisionObjects() const
Get which collision objects are active.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW BulletBVHManager()
Constructor.
std::map< std::string, CollisionObjectWrapperPtr > link2cow_
A map of collision objects being managed.
btDispatcherInfo dispatch_info_
The bullet collision dispatcher configuration information.
bool removeCollisionObject(const std::string &name)
Remove an object from the checker.
void setCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose)
Set a single static collision object's tansform.
void setContactDistanceThreshold(double contact_distance)
Set the contact distance threshold for which collision should be considered through expanding the AAB...
btDefaultCollisionConfiguration coll_config_
The bullet collision configuration.
std::unique_ptr< btCollisionDispatcher > dispatcher_
The bullet collision dispatcher used for getting object to object collision algorithm.
virtual void addCollisionObject(const CollisionObjectWrapperPtr &cow)=0
Add a collision object to the checker.
bool disableCollisionObject(const std::string &name)
Disable an object.
bool enableCollisionObject(const std::string &name)
Enable an object.
void setActiveCollisionObjects(const std::vector< std::string > &names)
Set which collision objects are active.
double getContactDistanceThreshold() const
Get the contact distance threshold.
BulletBVHManagerPtr clone() const
Clone the manager.
virtual ~BulletBVHManager()
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.
const std::map< std::string, CollisionObjectWrapperPtr > & getCollisionObjects() const
MOVEIT_CLASS_FORWARD(BulletBVHManager)
Representation of a collision checking request.
Representation of a collision checking result.