58 BulletCastBVHManagerPtr
clone()
const;
68 const Eigen::Isometry3d& pose2);
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
#define MOVEIT_CLASS_FORWARD(C)
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.
A bounding volume hierarchy (BVH) implementation of a tesseract contact manager.
void setCastCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose1, const Eigen::Isometry3d &pose2)
Set a single cast (moving) collision object's transforms.
~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.
BulletCastBVHManagerPtr clone() const
Clone the manager.
void addCollisionObject(const CollisionObjectWrapperPtr &cow) override
Add a tesseract collision object to the manager.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW BulletCastBVHManager()=default
Constructor.
Representation of a collision checking request.
Representation of a collision checking result.