Public Types | Public Member Functions | Public Attributes | Protected Attributes | List of all members
tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper Class Reference

This is a tesseract bullet collsion object. More...

#include <bullet_utils.h>

Inheritance diagram for tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper:
Inheritance graph
[legend]

Public Types

using ConstPtr = std::shared_ptr< const CollisionObjectWrapper >
 
using Ptr = std::shared_ptr< CollisionObjectWrapper >
 

Public Member Functions

std::shared_ptr< CollisionObjectWrapperclone ()
 This clones the collision objects but not the collision shape wich is const. More...
 
 CollisionObjectWrapper ()=default
 
 CollisionObjectWrapper (std::string name, const int &type_id, CollisionShapesConst shapes, tesseract_common::VectorIsometry3d shape_poses)
 
void getAABB (btVector3 &aabb_min, btVector3 &aabb_max) const
 Get the collision objects axis aligned bounding box. More...
 
const CollisionShapesConstgetCollisionGeometries () const
 
const tesseract_common::VectorIsometry3dgetCollisionGeometriesTransforms () const
 
const std::string & getName () const
 Get the collision object name. More...
 
const int & getTypeID () const
 Get a user defined type. More...
 
void manage (const std::shared_ptr< BulletCollisionShape > &t)
 
void manageReserve (std::size_t s)
 
bool sameObject (const CollisionObjectWrapper &other) const
 Check if two CollisionObjectWrapper objects point to the same source object. More...
 

Public Attributes

short int m_collisionFilterGroup { btBroadphaseProxy::KinematicFilter }
 
short int m_collisionFilterMask { btBroadphaseProxy::StaticFilter | btBroadphaseProxy::KinematicFilter }
 
bool m_enabled { true }
 

Protected Attributes

std::vector< std::shared_ptr< BulletCollisionShape > > m_data
 This manages the collision shape pointer so they get destroyed. More...
 
std::string m_name
 The name of the collision object. More...
 
tesseract_common::VectorIsometry3d m_shape_poses
 
CollisionShapesConst m_shapes
 The shapes poses information. More...
 
int m_type_id { -1 }
 A user defined type id. More...
 

Detailed Description

This is a tesseract bullet collsion object.

It is a wrapper around bullet's collision object which contains specific information related to tesseract

Definition at line 89 of file bullet_utils.h.

Member Typedef Documentation

◆ ConstPtr

Definition at line 97 of file bullet_utils.h.

◆ Ptr

Definition at line 96 of file bullet_utils.h.

Constructor & Destructor Documentation

◆ CollisionObjectWrapper() [1/2]

tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper::CollisionObjectWrapper ( )
default

◆ CollisionObjectWrapper() [2/2]

tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper::CollisionObjectWrapper ( std::string  name,
const int &  type_id,
CollisionShapesConst  shapes,
tesseract_common::VectorIsometry3d  shape_poses 
)

Definition at line 461 of file bullet_utils.cpp.

Member Function Documentation

◆ clone()

std::shared_ptr< CollisionObjectWrapper > tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper::clone ( )

This clones the collision objects but not the collision shape wich is const.

Returns
Shared Pointer to the cloned collision object

Definition at line 539 of file bullet_utils.cpp.

◆ getAABB()

void tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper::getAABB ( btVector3 &  aabb_min,
btVector3 &  aabb_max 
) const

Get the collision objects axis aligned bounding box.

Parameters
aabb_minThe minimum point
aabb_maxThe maximum point

Definition at line 530 of file bullet_utils.cpp.

◆ getCollisionGeometries()

const CollisionShapesConst & tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper::getCollisionGeometries ( ) const

Definition at line 523 of file bullet_utils.cpp.

◆ getCollisionGeometriesTransforms()

const tesseract_common::VectorIsometry3d & tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper::getCollisionGeometriesTransforms ( ) const

Definition at line 525 of file bullet_utils.cpp.

◆ getName()

const std::string & tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper::getName ( ) const

Get the collision object name.

Definition at line 508 of file bullet_utils.cpp.

◆ getTypeID()

const int & tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper::getTypeID ( ) const

Get a user defined type.

Definition at line 510 of file bullet_utils.cpp.

◆ manage()

void tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper::manage ( const std::shared_ptr< BulletCollisionShape > &  t)

Definition at line 556 of file bullet_utils.cpp.

◆ manageReserve()

void tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper::manageReserve ( std::size_t  s)

Definition at line 558 of file bullet_utils.cpp.

◆ sameObject()

bool tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper::sameObject ( const CollisionObjectWrapper other) const

Check if two CollisionObjectWrapper objects point to the same source object.

Definition at line 512 of file bullet_utils.cpp.

Member Data Documentation

◆ m_collisionFilterGroup

short int tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper::m_collisionFilterGroup { btBroadphaseProxy::KinematicFilter }

Definition at line 105 of file bullet_utils.h.

◆ m_collisionFilterMask

short int tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper::m_collisionFilterMask { btBroadphaseProxy::StaticFilter | btBroadphaseProxy::KinematicFilter }

Definition at line 106 of file bullet_utils.h.

◆ m_data

std::vector<std::shared_ptr<BulletCollisionShape> > tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper::m_data
protected

This manages the collision shape pointer so they get destroyed.

Definition at line 147 of file bullet_utils.h.

◆ m_enabled

bool tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper::m_enabled { true }

Definition at line 107 of file bullet_utils.h.

◆ m_name

std::string tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper::m_name
protected

The name of the collision object.

Definition at line 139 of file bullet_utils.h.

◆ m_shape_poses

tesseract_common::VectorIsometry3d tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper::m_shape_poses
protected

Definition at line 145 of file bullet_utils.h.

◆ m_shapes

CollisionShapesConst tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper::m_shapes
protected

The shapes poses information.

Definition at line 143 of file bullet_utils.h.

◆ m_type_id

int tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper::m_type_id { -1 }
protected

A user defined type id.

Definition at line 141 of file bullet_utils.h.


The documentation for this class was generated from the following files:


tesseract_collision
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:53