moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
A bounding volume hierarchy (BVH) implementation of a tesseract contact manager. More...
#include <bullet_cast_bvh_manager.h>
Public Member Functions | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | BulletCastBVHManager ()=default |
Constructor. | |
~BulletCastBVHManager () override=default | |
BulletCastBVHManagerPtr | clone () const |
Clone the manager. | |
void | setCastCollisionObjectsTransform (const std::string &name, const Eigen::Isometry3d &pose1, const Eigen::Isometry3d &pose2) |
Set a single cast (moving) collision object's transforms. | |
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. | |
void | addCollisionObject (const CollisionObjectWrapperPtr &cow) override |
Add a tesseract collision object to the manager. | |
Public Member Functions inherited from collision_detection_bullet::BulletBVHManager | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | BulletBVHManager () |
Constructor. | |
virtual | ~BulletBVHManager () |
BulletBVHManagerPtr | clone () const |
Clone the manager. | |
bool | hasCollisionObject (const std::string &name) const |
Find if a collision object already exists. | |
bool | removeCollisionObject (const std::string &name) |
Remove an object from the checker. | |
bool | enableCollisionObject (const std::string &name) |
Enable an object. | |
bool | disableCollisionObject (const std::string &name) |
Disable an object. | |
void | setCollisionObjectsTransform (const std::string &name, const Eigen::Isometry3d &pose) |
Set a single static collision object's transform. | |
void | setActiveCollisionObjects (const std::vector< std::string > &names) |
Set which collision objects are active. | |
const std::vector< std::string > & | getActiveCollisionObjects () const |
Get which collision objects are active. | |
void | setContactDistanceThreshold (double contact_distance) |
Set the contact distance threshold for which collision should be considered through expanding the AABB by the contact_distance for all links. | |
double | getContactDistanceThreshold () const |
Get the contact distance threshold. | |
const std::map< std::string, CollisionObjectWrapperPtr > & | getCollisionObjects () const |
Additional Inherited Members | |
Protected Attributes inherited from collision_detection_bullet::BulletBVHManager | |
std::map< std::string, CollisionObjectWrapperPtr > | link2cow_ |
A map of collision objects being managed. | |
std::vector< std::string > | active_ |
A list of the active collision links. | |
double | contact_distance_ |
The contact distance threshold. | |
std::unique_ptr< btCollisionDispatcher > | dispatcher_ |
The bullet collision dispatcher used for getting object to object collision algorithm. | |
btDispatcherInfo | dispatch_info_ |
The bullet collision dispatcher configuration information. | |
btDefaultCollisionConfiguration | coll_config_ |
The bullet collision configuration. | |
std::unique_ptr< btBroadphaseInterface > | broadphase_ |
The bullet broadphase interface. | |
BroadphaseFilterCallback | filter_callback_ |
Callback function for culling objects before a broadphase check. | |
A bounding volume hierarchy (BVH) implementation of a tesseract contact manager.
Definition at line 45 of file bullet_cast_bvh_manager.h.
|
default |
Constructor.
|
overridedefault |
|
overridevirtual |
Add a tesseract collision object to the manager.
cow | The tesseract bullet collision object |
Implements collision_detection_bullet::BulletBVHManager.
Definition at line 151 of file bullet_cast_bvh_manager.cpp.
BulletCastBVHManagerPtr collision_detection_bullet::BulletCastBVHManager::clone | ( | ) | const |
Clone the manager.
This is to be used for multi threaded applications. A user should make a clone for each thread.
Definition at line 44 of file bullet_cast_bvh_manager.cpp.
|
overridevirtual |
Perform a contact test for all objects.
collisions | The Contact results data |
req | The collision request data |
acm | The allowed collision matrix |
Implements collision_detection_bullet::BulletBVHManager.
Definition at line 136 of file bullet_cast_bvh_manager.cpp.
void collision_detection_bullet::BulletCastBVHManager::setCastCollisionObjectsTransform | ( | const std::string & | name, |
const Eigen::Isometry3d & | pose1, | ||
const Eigen::Isometry3d & | pose2 | ||
) |
Set a single cast (moving) collision object's transforms.
This should only be used for moving objects.
name | The name of the object |
pose1 | The start transformation in world |
pose2 | The end transformation in world |
Definition at line 66 of file bullet_cast_bvh_manager.cpp.