Bullet Collision Detection & Physics Library
Public Member Functions | Private Attributes | List of all members
btBvhTriangleMeshShape Class Reference

The btBvhTriangleMeshShape is a static-triangle mesh shape, it can only be used for fixed/non-moving objects. More...

#include <btBvhTriangleMeshShape.h>

Inheritance diagram for btBvhTriangleMeshShape:
Inheritance graph
[legend]
Collaboration diagram for btBvhTriangleMeshShape:
Collaboration graph
[legend]

Public Member Functions

 BT_DECLARE_ALIGNED_ALLOCATOR ()
 
 btBvhTriangleMeshShape (btStridingMeshInterface *meshInterface, bool useQuantizedAabbCompression, bool buildBvh=true)
 Bvh Concave triangle mesh is a static-triangle mesh shape with Bounding Volume Hierarchy optimization. More...
 
 btBvhTriangleMeshShape (btStridingMeshInterface *meshInterface, bool useQuantizedAabbCompression, const btVector3 &bvhAabbMin, const btVector3 &bvhAabbMax, bool buildBvh=true)
 optionally pass in a larger bvh aabb, used for quantization. This allows for deformations within this aabb More...
 
virtual ~btBvhTriangleMeshShape ()
 
bool getOwnsBvh () const
 
void performRaycast (btTriangleCallback *callback, const btVector3 &raySource, const btVector3 &rayTarget)
 
void performConvexcast (btTriangleCallback *callback, const btVector3 &boxSource, const btVector3 &boxTarget, const btVector3 &boxMin, const btVector3 &boxMax)
 
virtual void processAllTriangles (btTriangleCallback *callback, const btVector3 &aabbMin, const btVector3 &aabbMax) const
 
void refitTree (const btVector3 &aabbMin, const btVector3 &aabbMax)
 
void partialRefitTree (const btVector3 &aabbMin, const btVector3 &aabbMax)
 for a fast incremental refit of parts of the tree. Note: the entire AABB of the tree will become more conservative, it never shrinks More...
 
virtual const char * getName () const
 
virtual void setLocalScaling (const btVector3 &scaling)
 
btOptimizedBvhgetOptimizedBvh ()
 
void setOptimizedBvh (btOptimizedBvh *bvh, const btVector3 &localScaling=btVector3(1, 1, 1))
 
void buildOptimizedBvh ()
 
bool usesQuantizedAabbCompression () const
 
void setTriangleInfoMap (btTriangleInfoMap *triangleInfoMap)
 
const btTriangleInfoMapgetTriangleInfoMap () const
 
btTriangleInfoMapgetTriangleInfoMap ()
 
virtual int calculateSerializeBufferSize () const
 
virtual const char * serialize (void *dataBuffer, btSerializer *serializer) const
 fills the dataBuffer and returns the struct name (and 0 on failure) More...
 
virtual void serializeSingleBvh (btSerializer *serializer) const
 
virtual void serializeSingleTriangleInfoMap (btSerializer *serializer) const
 
- Public Member Functions inherited from btTriangleMeshShape
 BT_DECLARE_ALIGNED_ALLOCATOR ()
 
virtual ~btTriangleMeshShape ()
 
virtual btVector3 localGetSupportingVertex (const btVector3 &vec) const
 
virtual btVector3 localGetSupportingVertexWithoutMargin (const btVector3 &vec) const
 
void recalcLocalAabb ()
 
virtual void getAabb (const btTransform &t, btVector3 &aabbMin, btVector3 &aabbMax) const
 getAabb returns the axis aligned bounding box in the coordinate frame of the given transform t. More...
 
virtual void calculateLocalInertia (btScalar mass, btVector3 &inertia) const
 
virtual const btVector3getLocalScaling () const
 
btStridingMeshInterfacegetMeshInterface ()
 
const btStridingMeshInterfacegetMeshInterface () const
 
const btVector3getLocalAabbMin () const
 
const btVector3getLocalAabbMax () const
 
- Public Member Functions inherited from btConcaveShape
 BT_DECLARE_ALIGNED_ALLOCATOR ()
 
 btConcaveShape ()
 
virtual ~btConcaveShape ()
 
virtual btScalar getMargin () const
 
virtual void setMargin (btScalar collisionMargin)
 
- Public Member Functions inherited from btCollisionShape
 BT_DECLARE_ALIGNED_ALLOCATOR ()
 
 btCollisionShape ()
 
virtual ~btCollisionShape ()
 
virtual void getBoundingSphere (btVector3 &center, btScalar &radius) const
 
virtual btScalar getAngularMotionDisc () const
 getAngularMotionDisc returns the maximum radius needed for Conservative Advancement to handle time-of-impact with rotations. More...
 
virtual btScalar getContactBreakingThreshold (btScalar defaultContactThresholdFactor) const
 
void calculateTemporalAabb (const btTransform &curTrans, const btVector3 &linvel, const btVector3 &angvel, btScalar timeStep, btVector3 &temporalAabbMin, btVector3 &temporalAabbMax) const
 calculateTemporalAabb calculates the enclosing aabb for the moving object over interval [0..timeStep) result is conservative More...
 
bool isPolyhedral () const
 
bool isConvex2d () const
 
bool isConvex () const
 
bool isNonMoving () const
 
bool isConcave () const
 
bool isCompound () const
 
bool isSoftBody () const
 
bool isInfinite () const
 isInfinite is used to catch simulation error (aabb check) More...
 
int getShapeType () const
 
virtual btVector3 getAnisotropicRollingFrictionDirection () const
 the getAnisotropicRollingFrictionDirection can be used in combination with setAnisotropicFriction See Bullet/Demos/RollingFrictionDemo for an example More...
 
void setUserPointer (void *userPtr)
 optional user data pointer More...
 
void * getUserPointer () const
 
void setUserIndex (int index)
 
int getUserIndex () const
 
virtual void serializeSingleShape (btSerializer *serializer) const
 

Private Attributes

btOptimizedBvhm_bvh
 
btTriangleInfoMapm_triangleInfoMap
 
bool m_useQuantizedAabbCompression
 
bool m_ownsBvh
 
bool m_pad [11]
 

Additional Inherited Members

- Protected Member Functions inherited from btTriangleMeshShape
 btTriangleMeshShape (btStridingMeshInterface *meshInterface)
 btTriangleMeshShape constructor has been disabled/protected, so that users will not mistakenly use this class. More...
 
- Protected Attributes inherited from btTriangleMeshShape
btVector3 m_localAabbMin
 
btVector3 m_localAabbMax
 
btStridingMeshInterfacem_meshInterface
 
- Protected Attributes inherited from btConcaveShape
btScalar m_collisionMargin
 
- Protected Attributes inherited from btCollisionShape
int m_shapeType
 
void * m_userPointer
 
int m_userIndex
 

Detailed Description

The btBvhTriangleMeshShape is a static-triangle mesh shape, it can only be used for fixed/non-moving objects.

If you required moving concave triangle meshes, it is recommended to perform convex decomposition using HACD, see Bullet/Demos/ConvexDecompositionDemo. Alternatively, you can use btGimpactMeshShape for moving concave triangle meshes. btBvhTriangleMeshShape has several optimizations, such as bounding volume hierarchy and cache friendly traversal for PlayStation 3 Cell SPU. It is recommended to enable useQuantizedAabbCompression for better memory usage. It takes a triangle mesh as input, for example a btTriangleMesh or btTriangleIndexVertexArray. The btBvhTriangleMeshShape class allows for triangle mesh deformations by a refit or partialRefit method. Instead of building the bounding volume hierarchy acceleration structure, it is also possible to serialize (save) and deserialize (load) the structure from disk. See Demos\ConcaveDemo\ConcavePhysicsDemo.cpp for an example.

Definition at line 34 of file btBvhTriangleMeshShape.h.

Constructor & Destructor Documentation

btBvhTriangleMeshShape::btBvhTriangleMeshShape ( btStridingMeshInterface meshInterface,
bool  useQuantizedAabbCompression,
bool  buildBvh = true 
)

Bvh Concave triangle mesh is a static-triangle mesh shape with Bounding Volume Hierarchy optimization.

Uses an interface to access the triangles to allow for sharing graphics/physics triangles.

Definition at line 24 of file btBvhTriangleMeshShape.cpp.

btBvhTriangleMeshShape::btBvhTriangleMeshShape ( btStridingMeshInterface meshInterface,
bool  useQuantizedAabbCompression,
const btVector3 bvhAabbMin,
const btVector3 bvhAabbMax,
bool  buildBvh = true 
)

optionally pass in a larger bvh aabb, used for quantization. This allows for deformations within this aabb

Definition at line 44 of file btBvhTriangleMeshShape.cpp.

btBvhTriangleMeshShape::~btBvhTriangleMeshShape ( )
virtual

Definition at line 84 of file btBvhTriangleMeshShape.cpp.

Member Function Documentation

btBvhTriangleMeshShape::BT_DECLARE_ALIGNED_ALLOCATOR ( )
void btBvhTriangleMeshShape::buildOptimizedBvh ( )

m_localAabbMin/m_localAabbMax is already re-calculated in btTriangleMeshShape. We could just scale aabb, but this needs some more work

Definition at line 341 of file btBvhTriangleMeshShape.cpp.

int btBvhTriangleMeshShape::calculateSerializeBufferSize ( ) const
inlinevirtual

Reimplemented from btCollisionShape.

Definition at line 142 of file btBvhTriangleMeshShape.h.

virtual const char* btBvhTriangleMeshShape::getName ( ) const
inlinevirtual

Reimplemented from btTriangleMeshShape.

Reimplemented in btMultimaterialTriangleMeshShape.

Definition at line 78 of file btBvhTriangleMeshShape.h.

btOptimizedBvh* btBvhTriangleMeshShape::getOptimizedBvh ( )
inline

Definition at line 83 of file btBvhTriangleMeshShape.h.

bool btBvhTriangleMeshShape::getOwnsBvh ( ) const
inline

Definition at line 60 of file btBvhTriangleMeshShape.h.

const btTriangleInfoMap* btBvhTriangleMeshShape::getTriangleInfoMap ( ) const
inline

Definition at line 102 of file btBvhTriangleMeshShape.h.

btTriangleInfoMap* btBvhTriangleMeshShape::getTriangleInfoMap ( )
inline

Definition at line 107 of file btBvhTriangleMeshShape.h.

void btBvhTriangleMeshShape::partialRefitTree ( const btVector3 aabbMin,
const btVector3 aabbMax 
)

for a fast incremental refit of parts of the tree. Note: the entire AABB of the tree will become more conservative, it never shrinks

Definition at line 68 of file btBvhTriangleMeshShape.cpp.

void btBvhTriangleMeshShape::performConvexcast ( btTriangleCallback callback,
const btVector3 boxSource,
const btVector3 boxTarget,
const btVector3 boxMin,
const btVector3 boxMax 
)

Definition at line 162 of file btBvhTriangleMeshShape.cpp.

void btBvhTriangleMeshShape::performRaycast ( btTriangleCallback callback,
const btVector3 raySource,
const btVector3 rayTarget 
)

Definition at line 93 of file btBvhTriangleMeshShape.cpp.

void btBvhTriangleMeshShape::processAllTriangles ( btTriangleCallback callback,
const btVector3 aabbMin,
const btVector3 aabbMax 
) const
virtual

Reimplemented from btTriangleMeshShape.

Definition at line 232 of file btBvhTriangleMeshShape.cpp.

void btBvhTriangleMeshShape::refitTree ( const btVector3 aabbMin,
const btVector3 aabbMax 
)

Definition at line 77 of file btBvhTriangleMeshShape.cpp.

const char * btBvhTriangleMeshShape::serialize ( void *  dataBuffer,
btSerializer serializer 
) const
virtual

fills the dataBuffer and returns the struct name (and 0 on failure)

Reimplemented from btCollisionShape.

Definition at line 373 of file btBvhTriangleMeshShape.cpp.

void btBvhTriangleMeshShape::serializeSingleBvh ( btSerializer serializer) const
virtual

Definition at line 446 of file btBvhTriangleMeshShape.cpp.

void btBvhTriangleMeshShape::serializeSingleTriangleInfoMap ( btSerializer serializer) const
virtual

Definition at line 457 of file btBvhTriangleMeshShape.cpp.

void btBvhTriangleMeshShape::setLocalScaling ( const btVector3 scaling)
virtual

Reimplemented from btTriangleMeshShape.

Definition at line 332 of file btBvhTriangleMeshShape.cpp.

void btBvhTriangleMeshShape::setOptimizedBvh ( btOptimizedBvh bvh,
const btVector3 localScaling = btVector3(1,1,1) 
)

Definition at line 356 of file btBvhTriangleMeshShape.cpp.

void btBvhTriangleMeshShape::setTriangleInfoMap ( btTriangleInfoMap triangleInfoMap)
inline

Definition at line 97 of file btBvhTriangleMeshShape.h.

bool btBvhTriangleMeshShape::usesQuantizedAabbCompression ( ) const
inline

Definition at line 92 of file btBvhTriangleMeshShape.h.

Member Data Documentation

btOptimizedBvh* btBvhTriangleMeshShape::m_bvh
private

Definition at line 37 of file btBvhTriangleMeshShape.h.

bool btBvhTriangleMeshShape::m_ownsBvh
private

Definition at line 41 of file btBvhTriangleMeshShape.h.

bool btBvhTriangleMeshShape::m_pad[11]
private

Definition at line 45 of file btBvhTriangleMeshShape.h.

btTriangleInfoMap* btBvhTriangleMeshShape::m_triangleInfoMap
private

Definition at line 38 of file btBvhTriangleMeshShape.h.

bool btBvhTriangleMeshShape::m_useQuantizedAabbCompression
private

Definition at line 40 of file btBvhTriangleMeshShape.h.


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