Go to the documentation of this file.
45 class BulletCastBVHManager :
public BulletBVHManager
48 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
58 BulletCastBVHManagerPtr
clone()
const;
68 const Eigen::Isometry3d& pose2);
void setCastCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose1, const Eigen::Isometry3d &pose2)
Set a single cast (moving) collision object's tansforms.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW BulletCastBVHManager()=default
Constructor.
BulletCastBVHManagerPtr clone() const
Clone the manager.
Representation of a collision checking request.
Definition of a structure for the allowed collision matrix.
Representation of a collision checking result.
void addCollisionObject(const CollisionObjectWrapperPtr &cow) override
Add a tesseract collision object to the manager.
~BulletCastBVHManager() override=default
void contactTest(collision_detection::CollisionResult &collisions, const collision_detection::CollisionRequest &req, const collision_detection::AllowedCollisionMatrix *acm, bool self) override
Perform a contact test for all objects.
MOVEIT_CLASS_FORWARD(BulletBVHManager)
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:14