23 : m_dynamicsWorld(world),
187 shape = gimpactShape;
191 printf(
"unsupported gimpact sub type\n");
221 printf(
"error: wrong up axis for btCapsuleShape\n");
263 btVector3 halfExtents = implicitShapeDimensions + margin;
283 printf(
"unknown Cylinder up axis\n");
292 btVector3 halfExtents = implicitShapeDimensions;
312 printf(
"unknown Cone up axis\n");
326 tmpPos.
resize(numSpheres);
328 for (i = 0; i < numSpheres; i++)
345 tmpPoints.
resize(numPoints);
347 for (i = 0; i < numPoints; i++)
349#ifdef BT_USE_DOUBLE_PRECISION
362 for (i = 0; i < numPoints; i++)
373 printf(
"error: cannot create shape type (%d)\n", shapeData->
m_shapeType);
406 if (bvhPtr && *bvhPtr)
419 if (bvhPtr && *bvhPtr)
433 shape = trimeshShape;
441#ifdef USE_INTERNAL_EDGE_UTILITY
469 printf(
"error: couldn't create childShape for compoundShape\n");
473 shape = compoundShape;
484 printf(
"unsupported shape type (%d)\n", shapeData->
m_shapeType);
496 int l = (int)strlen(name);
497 char* newName =
new char[l + 1];
498 memcpy(newName, name, l);
580 constraint = coneTwist;
599 printf(
"Error in btWorldImporter::createGeneric6DofSpringConstraint: requires rbA && rbB\n");
604 btVector3 angLowerLimit, angUpperLimit, linLowerLimit, linUpperlimit;
610 angLowerLimit.
setW(0.f);
617 if (fileVersion > 280)
619 for (i = 0; i < 6; i++)
654 printf(
"Error in btWorldImporter::createGeneric6DofConstraint: missing rbB\n");
660 btVector3 angLowerLimit, angUpperLimit, linLowerLimit, linUpperlimit;
703 printf(
"unknown constraint type\n");
711 if (fileVersion >= 280)
718 if (constraintData->
m_name)
801 constraint = coneTwist;
820 printf(
"Error in btWorldImporter::createGeneric6DofSpringConstraint: requires rbA && rbB\n");
825 btVector3 angLowerLimit, angUpperLimit, linLowerLimit, linUpperlimit;
831 angLowerLimit.
setW(0.f);
838 if (fileVersion > 280)
840 for (i = 0; i < 6; i++)
875 printf(
"Error in btWorldImporter::createGeneric6DofConstraint: missing rbB\n");
881 btVector3 angLowerLimit, angUpperLimit, linLowerLimit, linUpperlimit;
956 printf(
"Error in btWorldImporter::createGeneric6DofSpring2Constraint: requires rbA && rbB\n");
961 btVector3 angLowerLimit, angUpperLimit, linLowerLimit, linUpperlimit;
967 angLowerLimit.
setW(0.f);
974 if (fileVersion > 280)
977 for (i = 0; i < 3; i++)
984 for (i = 0; i < 3; i++)
1020 printf(
"Error in btWorldImporter::createGeneric6DofSpring2Constraint: requires rbA && rbB\n");
1028 printf(
"unknown constraint type\n");
1036 if (fileVersion >= 280)
1043 if (constraintData->
m_name)
1128 constraint = coneTwist;
1147 printf(
"Error in btWorldImporter::createGeneric6DofSpringConstraint: requires rbA && rbB\n");
1152 btVector3 angLowerLimit, angUpperLimit, linLowerLimit, linUpperlimit;
1158 angLowerLimit.
setW(0.f);
1165 if (fileVersion > 280)
1167 for (i = 0; i < 6; i++)
1202 printf(
"Error in btWorldImporter::createGeneric6DofConstraint: missing rbB\n");
1208 btVector3 angLowerLimit, angUpperLimit, linLowerLimit, linUpperlimit;
1245 constraint = slider;
1284 printf(
"Error in btWorldImporter::createGeneric6DofSpring2Constraint: requires rbA && rbB\n");
1289 btVector3 angLowerLimit, angUpperLimit, linLowerLimit, linUpperlimit;
1295 angLowerLimit.
setW(0.f);
1302 if (fileVersion > 280)
1305 for (i = 0; i < 3; i++)
1312 for (i = 0; i < 3; i++)
1348 printf(
"Error in btWorldImporter::createGeneric6DofSpring2Constraint: requires rbA && rbB\n");
1357 printf(
"unknown constraint type\n");
1365 if (fileVersion >= 280)
1372 if (constraintData->
m_name)
1471 meshPart.
m_vertexBase = (
const unsigned char*)vertices;
1488 meshPart.
m_vertexBase = (
const unsigned char*)vertices;
1497 return meshInterface;
1536 bool uninitialized3indices8Workaround =
false;
1540 uninitialized3indices8Workaround =
true;
1549 uninitialized3indices8Workaround =
true;
1558 uninitialized3indices8Workaround =
true;
1565 if (!uninitialized3indices8Workaround && curPart->
m_3indices8)
1579#ifdef USE_INTERNAL_EDGE_UTILITY
1789 const void* heightfieldData,
btScalar heightScale,
1791 int upAxis,
int heightDataType,
1796 heightfieldData, heightScale, minHeight, maxHeight, upAxis,
PHY_ScalarType(heightDataType), flipQuadEdges);
1913 if (shapePtr && *shapePtr)
1923 if (bodyPtr && *bodyPtr)
1933 if (constraintPtr && *constraintPtr)
1935 return *constraintPtr;
1943 if (namePtr && *namePtr)
1992 if (shapePtr && *shapePtr)
2008 bool isDynamic = mass != 0.f;
2018#ifdef USE_INTERNAL_EDGE_UTILITY
2032 printf(
"error: no shape found\n");
2042 if (shapePtr && *shapePtr)
2058 bool isDynamic = mass != 0.f;
2068#ifdef USE_INTERNAL_EDGE_UTILITY
2082 printf(
"error: no shape found\n");
#define btAlignedFree(ptr)
#define btAlignedAlloc(size, alignment)
@ COMPOUND_SHAPE_PROXYTYPE
@ GIMPACT_SHAPE_PROXYTYPE
Used for GIMPACT Trimesh integration.
@ SOFTBODY_SHAPE_PROXYTYPE
@ SCALED_TRIANGLE_MESH_SHAPE_PROXYTYPE
@ TRIANGLE_MESH_SHAPE_PROXYTYPE
@ MULTI_SPHERE_SHAPE_PROXYTYPE
@ CYLINDER_SHAPE_PROXYTYPE
@ CAPSULE_SHAPE_PROXYTYPE
@ CONVEX_HULL_SHAPE_PROXYTYPE
PHY_ScalarType
PHY_ScalarType enumerates possible scalar types.
@ CONST_GIMPACT_TRIMESH_SHAPE
void btAdjustInternalEdgeContacts(btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, const btCollisionObjectWrapper *colObj1Wrap, int partId0, int index0, int normalAdjustFlags)
Changes a btManifoldPoint collision normal to the normal from the mesh.
ContactAddedCallback gContactAddedCallback
This is to allow MaterialCombiner/Custom Friction/Restitution values.
bool(* ContactAddedCallback)(btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, int partId0, int index0, const btCollisionObjectWrapper *colObj1Wrap, int partId1, int index1)
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
@ CONETWIST_CONSTRAINT_TYPE
@ POINT2POINT_CONSTRAINT_TYPE
@ D6_SPRING_2_CONSTRAINT_TYPE
@ D6_SPRING_CONSTRAINT_TYPE
int size() const
return the number of elements in the array
void resize(int newsize, const T &fillData=T())
void clear()
clear the array, deallocated memory. Generally it is better to use array.resize(0),...
void push_back(const T &_Val)
The btBoxShape is a box primitive around the origin, its sides axis aligned with length specified by ...
The btBvhTriangleMeshShape is a static-triangle mesh shape, it can only be used for fixed/non-moving ...
void setOptimizedBvh(btOptimizedBvh *bvh, const btVector3 &localScaling=btVector3(1, 1, 1))
const btTriangleInfoMap * getTriangleInfoMap() const
void setTriangleInfoMap(btTriangleInfoMap *triangleInfoMap)
btCapsuleShapeX represents a capsule around the Z axis the total height is height+2*radius,...
btCapsuleShapeZ represents a capsule around the Z axis the total height is height+2*radius,...
The btCapsuleShape represents a capsule around the Y axis, there is also the btCapsuleShapeX aligned ...
void deSerializeFloat(struct btCapsuleShapeData *dataBuffer)
btCollisionObject can be used to manage collision detection objects.
@ CF_CUSTOM_MATERIAL_CALLBACK
void setRestitution(btScalar rest)
void setCollisionFlags(int flags)
btTransform & getWorldTransform()
void setWorldTransform(const btTransform &worldTrans)
void setFriction(btScalar frict)
int getCollisionFlags() const
The btCollisionShape class provides an interface for collision shapes that can be shared among btColl...
virtual void setMargin(btScalar margin)=0
virtual void calculateLocalInertia(btScalar mass, btVector3 &inertia) const =0
virtual void setLocalScaling(const btVector3 &scaling)=0
The btCompoundShape allows to store multiple other btCollisionShapes This allows for moving concave c...
void addChildShape(const btTransform &localTransform, btCollisionShape *shape)
virtual void setMargin(btScalar collisionMargin)
btConeShape implements a Cone shape, around the X axis
btConeShapeZ implements a Cone shape, around the Z axis
The btConeShape implements a cone shape primitive, centered around the origin and aligned with the Y ...
btConeTwistConstraint can be used to simulate ragdoll joints (upper arm, leg etc)
void setLimit(int limitIndex, btScalar limitValue)
void setDamping(btScalar damping)
The btConvexHullShape implements an implicit convex hull of an array of vertices.
void addPoint(const btVector3 &point, bool recalculateLocalAabb=true)
virtual void setMargin(btScalar margin)
The btCylinderShape class implements a cylinder shape primitive, centered around the origin....
The btDynamicsWorld is the interface class for several dynamics implementation, basic,...
virtual void removeRigidBody(btRigidBody *body)=0
btContactSolverInfo & getSolverInfo()
virtual void removeConstraint(btTypedConstraint *constraint)
virtual void addRigidBody(btRigidBody *body)=0
virtual void addConstraint(btTypedConstraint *constraint, bool disableCollisionsBetweenLinkedBodies=false)
virtual void setGravity(const btVector3 &gravity)=0
This class manages a mesh supplied by the btStridingMeshInterface interface.
virtual void setMargin(btScalar margin)
virtual void setLocalScaling(const btVector3 &scaling)
void updateBound()
performs refit operation
The btGeatConstraint will couple the angular velocity for two bodies around given local axis and rati...
btGeneric6DofConstraint between two rigidbodies each with a pivotpoint that descibes the axis locatio...
void setLinearLowerLimit(const btVector3 &linearLower)
void setAngularLowerLimit(const btVector3 &angularLower)
void setAngularUpperLimit(const btVector3 &angularUpper)
void setLinearUpperLimit(const btVector3 &linearUpper)
void setStiffness(int index, btScalar stiffness, bool limitIfNeeded=true)
void setDamping(int index, btScalar damping, bool limitIfNeeded=true)
void setLinearUpperLimit(const btVector3 &linearUpper)
void enableSpring(int index, bool onOff)
void setAngularUpperLimit(const btVector3 &angularUpper)
void setAngularLowerLimit(const btVector3 &angularLower)
void setLinearLowerLimit(const btVector3 &linearLower)
void setEquilibriumPoint()
Generic 6 DOF constraint that allows to set spring motors to any translational and rotational DOF.
void setDamping(int index, btScalar damping)
void enableSpring(int index, bool onOff)
void setStiffness(int index, btScalar stiffness)
void setEquilibriumPoint()
void insert(const Key &key, const Value &value)
const Value * find(const Key &key) const
btHeightfieldTerrainShape simulates a 2D heightfield terrain
btHeightfieldTerrainShape(int heightStickWidth, int heightStickLength, const float *heightfieldData, btScalar minHeight, btScalar maxHeight, int upAxis, bool flipQuadEdges)
preferred constructors
hinge constraint between two rigidbodies each with a pivotpoint that descibes the axis location in lo...
void setAngularOnly(bool angularOnly)
void setLimit(btScalar low, btScalar high, btScalar _softness=0.9f, btScalar _biasFactor=0.3f, btScalar _relaxationFactor=1.0f)
void enableAngularMotor(bool enableMotor, btScalar targetVelocity, btScalar maxMotorImpulse)
ManifoldContactPoint collects and maintains persistent contactpoints.
The btMultiSphereShape represents the convex hull of a collection of spheres.
The btOptimizedBvh extends the btQuantizedBvh to create AABB tree for triangle meshes,...
point to point constraint between two rigidbodies each with a pivotpoint that descibes the 'ballsocke...
virtual void deSerializeFloat(struct btQuantizedBvhFloatData &quantizedBvhFloatData)
virtual void deSerializeDouble(struct btQuantizedBvhDoubleData &quantizedBvhDoubleData)
The btRigidBody is the main class for rigid body objects.
void setLinearFactor(const btVector3 &linearFactor)
void setMassProps(btScalar mass, const btVector3 &inertia)
void setAngularFactor(const btVector3 &angFac)
static const btRigidBody * upcast(const btCollisionObject *colObj)
to keep collision detection and dynamics separate we don't store a rigidbody pointer but a rigidbody ...
The btScaledBvhTriangleMeshShape allows to instance a scaled version of an existing btBvhTriangleMesh...
void setUseFrameOffset(bool frameOffsetOnOff)
void setLowerLinLimit(btScalar lowerLimit)
void setUpperLinLimit(btScalar upperLimit)
void setUpperAngLimit(btScalar upperLimit)
void setLowerAngLimit(btScalar lowerLimit)
The btSphereShape implements an implicit sphere, centered around a local origin with radius.
The btStaticPlaneShape simulates an infinite non-moving (static) collision plane.
The btStridingMeshInterface is the interface class for high performance generic access to triangle me...
void setScaling(const btVector3 &scaling)
The btTriangleIndexVertexArray allows to access multiple triangle meshes, by indexing into existing t...
void addIndexedMesh(const btIndexedMesh &mesh, PHY_ScalarType indexType=PHY_INTEGER)
virtual int getNumSubParts() const
getNumSubParts returns the number of separate subparts each subpart has a continuous array of vertice...
TypedConstraint is the baseclass for Bullet constraints and vehicles.
void setDbgDrawSize(btScalar dbgDrawSize)
void setEnabled(bool enabled)
void setOverrideNumSolverIterations(int overideNumIterations)
override the number of constraint solver iterations used to solve this constraint -1 will use the def...
void setBreakingImpulseThreshold(btScalar threshold)
btVector3 can be used to represent 3D points and vectors.
const btScalar & getZ() const
Return the z value.
void deSerializeFloat(const struct btVector3FloatData &dataIn)
void deSerializeDouble(const struct btVector3DoubleData &dataIn)
void setW(btScalar _w)
Set the w value.
const btScalar & getY() const
Return the y value.
const btScalar & getX() const
Return the x value.
char * duplicateName(const char *name)
btAlignedObjectArray< btTriangleIndexVertexArray * > m_allocatedTriangleIndexArrays
btAlignedObjectArray< char * > m_allocatedNames
virtual btCollisionObject * createCollisionObject(const btTransform &startTransform, btCollisionShape *shape, const char *bodyName)
btTypedConstraint * getConstraintByName(const char *name)
static btRigidBody & getFixedBody()
virtual btCollisionShape * createConeShapeY(btScalar radius, btScalar height)
btAlignedObjectArray< btCollisionObject * > m_allocatedRigidBodies
virtual btCollisionShape * createCapsuleShapeY(btScalar radius, btScalar height)
btTypedConstraint * getConstraintByIndex(int index) const
virtual btOptimizedBvh * createOptimizedBvh()
acceleration and connectivity structures
virtual class btScaledBvhTriangleMeshShape * createScaledTrangleMeshShape(btBvhTriangleMeshShape *meshShape, const btVector3 &localScalingbtBvhTriangleMeshShape)
virtual btRigidBody * createRigidBody(bool isDynamic, btScalar mass, const btTransform &startTransform, btCollisionShape *shape, const char *bodyName)
void convertConstraintBackwardsCompatible281(btTypedConstraintData *constraintData, btRigidBody *rbA, btRigidBody *rbB, int fileVersion)
btRigidBody * getRigidBodyByName(const char *name)
virtual class btConvexHullShape * createConvexHullShape()
virtual btCollisionShape * createConvexTriangleMeshShape(btStridingMeshInterface *trimesh)
const char * getNameForPointer(const void *ptr) const
virtual btCollisionShape * createCapsuleShapeX(btScalar radius, btScalar height)
virtual btCollisionShape * createPlaneShape(const btVector3 &planeNormal, btScalar planeConstant)
shapes
btAlignedObjectArray< btOptimizedBvh * > m_allocatedBvhs
btHashMap< btHashPtr, btOptimizedBvh * > m_bvhMap
btCollisionObject * getRigidBodyByIndex(int index) const
btCollisionShape * getCollisionShapeByIndex(int index)
btHashMap< btHashString, btTypedConstraint * > m_nameConstraintMap
virtual btConeTwistConstraint * createConeTwistConstraint(btRigidBody &rbA, btRigidBody &rbB, const btTransform &rbAFrame, const btTransform &rbBFrame)
virtual class btMultiSphereShape * createMultiSphereShape(const btVector3 *positions, const btScalar *radi, int numSpheres)
virtual ~btWorldImporter()
virtual btStridingMeshInterfaceData * createStridingMeshInterfaceData(btStridingMeshInterfaceData *interfaceData)
btAlignedObjectArray< btTypedConstraint * > m_allocatedConstraints
void convertConstraintDouble(btTypedConstraintDoubleData *constraintData, btRigidBody *rbA, btRigidBody *rbB, int fileVersion)
virtual btGeneric6DofSpring2Constraint * createGeneric6DofSpring2Constraint(btRigidBody &rbA, btRigidBody &rbB, const btTransform &frameInA, const btTransform &frameInB, int rotateOrder)
btAlignedObjectArray< unsigned char * > m_charIndexArrays
virtual btCollisionShape * createBoxShape(const btVector3 &halfExtents)
virtual void setDynamicsWorldInfo(const btVector3 &gravity, const btContactSolverInfo &solverInfo)
those virtuals are called by load and can be overridden by the user
int getNumRigidBodies() const
int getNumTriangleInfoMaps() const
virtual btTriangleIndexVertexArray * createMeshInterface(btStridingMeshInterfaceData &meshData)
btAlignedObjectArray< int * > m_indexArrays
virtual btGeneric6DofConstraint * createGeneric6DofConstraint(btRigidBody &rbA, btRigidBody &rbB, const btTransform &frameInA, const btTransform &frameInB, bool useLinearReferenceFrameA)
int getNumCollisionShapes() const
btAlignedObjectArray< btTriangleInfoMap * > m_allocatedTriangleInfoMaps
virtual btCollisionShape * createCylinderShapeY(btScalar radius, btScalar height)
virtual void deleteAllData()
delete all memory collision shapes, rigid bodies, constraints etc.
virtual btGeneric6DofSpringConstraint * createGeneric6DofSpringConstraint(btRigidBody &rbA, btRigidBody &rbB, const btTransform &frameInA, const btTransform &frameInB, bool useLinearReferenceFrameA)
virtual btCollisionShape * createConeShapeX(btScalar radius, btScalar height)
btDynamicsWorld * m_dynamicsWorld
virtual btCollisionShape * createCylinderShapeX(btScalar radius, btScalar height)
void convertConstraintFloat(btTypedConstraintFloatData *constraintData, btRigidBody *rbA, btRigidBody *rbB, int fileVersion)
virtual class btCompoundShape * createCompoundShape()
btWorldImporter(btDynamicsWorld *world)
btTriangleInfoMap * getTriangleInfoMapByIndex(int index) const
btAlignedObjectArray< btCollisionShape * > m_allocatedCollisionShapes
virtual btGearConstraint * createGearConstraint(btRigidBody &rbA, btRigidBody &rbB, const btVector3 &axisInA, const btVector3 &axisInB, btScalar ratio)
btHashMap< btHashString, btCollisionShape * > m_nameShapeMap
int getNumConstraints() const
btHashMap< btHashPtr, btCollisionShape * > m_shapeMap
virtual btCollisionShape * createConeShapeZ(btScalar radius, btScalar height)
virtual btHingeConstraint * createHingeConstraint(btRigidBody &rbA, btRigidBody &rbB, const btTransform &rbAFrame, const btTransform &rbBFrame, bool useReferenceFrameA=false)
btAlignedObjectArray< btVector3DoubleData * > m_doubleVertexArrays
btHashMap< btHashString, btRigidBody * > m_nameBodyMap
btCollisionShape * convertCollisionShape(btCollisionShapeData *shapeData)
virtual btCollisionShape * createSphereShape(btScalar radius)
btCollisionShape * getCollisionShapeByName(const char *name)
void convertRigidBodyDouble(btRigidBodyDoubleData *colObjData)
btAlignedObjectArray< btVector3FloatData * > m_floatVertexArrays
virtual class btTriangleIndexVertexArray * createTriangleMeshContainer()
virtual btBvhTriangleMeshShape * createBvhTriangleMeshShape(btStridingMeshInterface *trimesh, btOptimizedBvh *bvh)
btAlignedObjectArray< btStridingMeshInterfaceData * > m_allocatedbtStridingMeshInterfaceDatas
virtual btGImpactMeshShape * createGimpactShape(btStridingMeshInterface *trimesh)
btOptimizedBvh * getBvhByIndex(int index) const
void convertRigidBodyFloat(btRigidBodyFloatData *colObjData)
btHashMap< btHashPtr, btCollisionObject * > m_bodyMap
virtual btPoint2PointConstraint * createPoint2PointConstraint(btRigidBody &rbA, btRigidBody &rbB, const btVector3 &pivotInA, const btVector3 &pivotInB)
constraints
virtual btCollisionShape * createCylinderShapeZ(btScalar radius, btScalar height)
virtual btTriangleInfoMap * createTriangleInfoMap()
virtual class btHeightfieldTerrainShape * createHeightfieldShape(int heightStickWidth, int heightStickLength, const void *heightfieldData, btScalar heightScale, btScalar minHeight, btScalar maxHeight, int upAxis, int heightDataType, bool flipQuadEdges)
virtual btCollisionShape * createCapsuleShapeZ(btScalar radius, btScalar height)
virtual btSliderConstraint * createSliderConstraint(btRigidBody &rbA, btRigidBody &rbB, const btTransform &frameInA, const btTransform &frameInB, bool useLinearReferenceFrameA)
btAlignedObjectArray< short int * > m_shortIndexArrays
btHashMap< btHashPtr, const char * > m_objectNameMap
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
unsigned char m_values[3]
btTransformDoubleData m_worldTransform
btTransformFloatData m_worldTransform
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
btTransformFloatData m_transform
btCollisionShapeData * m_childShape
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
btCompoundShapeChildData * m_childShapePtr
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
this structure is not used, except for loading pre-2.82 .bullet files
btTransformFloatData m_rbBFrame
btTransformFloatData m_rbAFrame
btTransformDoubleData m_rbBFrame
double m_relaxationFactor
btTransformDoubleData m_rbAFrame
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
btVector3DoubleData * m_unscaledPointsDoublePtr
btVector3FloatData * m_unscaledPointsFloatPtr
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
btVector3FloatData m_implicitShapeDimensions
btVector3FloatData m_localScaling
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
btStridingMeshInterfaceData m_meshInterface
btVector3FloatData m_localScaling
btVector3DoubleData m_axisInA
btVector3DoubleData m_axisInB
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
btVector3FloatData m_axisInB
btVector3FloatData m_axisInA
btTransformFloatData m_rbBFrame
int m_useLinearReferenceFrameA
btVector3FloatData m_linearUpperLimit
btVector3FloatData m_linearLowerLimit
btVector3FloatData m_angularLowerLimit
btVector3FloatData m_angularUpperLimit
btTransformFloatData m_rbAFrame
btVector3DoubleData m_linearUpperLimit
btVector3DoubleData m_angularLowerLimit
btTransformDoubleData m_rbAFrame
btVector3DoubleData m_linearLowerLimit
btVector3DoubleData m_angularUpperLimit
btTransformDoubleData m_rbBFrame
int m_useLinearReferenceFrameA
btTransformFloatData m_rbAFrame
btTransformFloatData m_rbBFrame
btVector3FloatData m_linearSpringDamping
btVector3FloatData m_linearEquilibriumPoint
char m_linearSpringDampingLimited[4]
btVector3FloatData m_angularSpringDamping
char m_linearEnableSpring[4]
btVector3FloatData m_angularSpringStiffness
btVector3FloatData m_linearSpringStiffness
char m_linearSpringStiffnessLimited[4]
btVector3FloatData m_angularUpperLimit
char m_angularSpringDampingLimited[4]
char m_angularEnableSpring[4]
char m_angularSpringStiffnessLimited[4]
btVector3FloatData m_linearUpperLimit
btVector3FloatData m_angularLowerLimit
btVector3FloatData m_angularEquilibriumPoint
btVector3FloatData m_linearLowerLimit
btVector3DoubleData m_angularSpringStiffness
btVector3DoubleData m_linearSpringDamping
char m_angularSpringStiffnessLimited[4]
btVector3DoubleData m_angularLowerLimit
btVector3DoubleData m_linearSpringStiffness
char m_angularEnableSpring[4]
char m_angularSpringDampingLimited[4]
btTransformDoubleData m_rbBFrame
btVector3DoubleData m_linearUpperLimit
btVector3DoubleData m_linearLowerLimit
char m_linearSpringStiffnessLimited[4]
char m_linearSpringDampingLimited[4]
btVector3DoubleData m_linearEquilibriumPoint
btTransformDoubleData m_rbAFrame
btVector3DoubleData m_angularEquilibriumPoint
btVector3DoubleData m_angularSpringDamping
btVector3DoubleData m_angularUpperLimit
char m_linearEnableSpring[4]
btGeneric6DofConstraintData m_6dofData
float m_springStiffness[6]
float m_equilibriumPoint[6]
double m_equilibriumPoint[6]
double m_springDamping[6]
double m_springStiffness[6]
btGeneric6DofConstraintDoubleData2 m_6dofData
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
double m_motorTargetVelocity
double m_relaxationFactor
btTransformDoubleData m_rbBFrame
btTransformDoubleData m_rbAFrame
this structure is not used, except for loading pre-2.82 .bullet files
float m_motorTargetVelocity
btTransformDoubleData m_rbAFrame
btTransformDoubleData m_rbBFrame
float m_motorTargetVelocity
btTransformFloatData m_rbAFrame
btTransformFloatData m_rbBFrame
The btIndexedMesh indexes a single vertex and index array.
PHY_ScalarType m_indexType
int m_triangleIndexStride
const unsigned char * m_vertexBase
const unsigned char * m_triangleIndexBase
PHY_ScalarType m_vertexType
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
btShortIntIndexData * m_indices16
btCharIndexTripletData * m_3indices8
btVector3FloatData * m_vertices3f
btShortIntIndexTripletData * m_3indices16
btIntIndexData * m_indices32
btVector3DoubleData * m_vertices3d
int m_localPositionArraySize
btPositionAndRadius * m_localPositionArrayPtr
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
btVector3DoubleData m_pivotInB
btVector3DoubleData m_pivotInA
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64 th...
btVector3DoubleData m_pivotInA
btVector3DoubleData m_pivotInB
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
btVector3FloatData m_pivotInB
btVector3FloatData m_pivotInA
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
btCollisionObjectDoubleData m_collisionObjectData
btVector3DoubleData m_linearFactor
btVector3DoubleData m_angularFactor
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
btVector3FloatData m_linearFactor
btVector3FloatData m_angularFactor
btCollisionObjectFloatData m_collisionObjectData
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
btTriangleMeshShapeData m_trimeshShapeData
btVector3FloatData m_localScaling
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
float m_angularUpperLimit
int m_useLinearReferenceFrameA
btTransformFloatData m_rbBFrame
float m_angularLowerLimit
btTransformFloatData m_rbAFrame
int m_useOffsetForConstraintFrame
int m_useLinearReferenceFrameA
double m_linearUpperLimit
btTransformDoubleData m_rbAFrame
double m_angularUpperLimit
double m_linearLowerLimit
btTransformDoubleData m_rbBFrame
int m_useOffsetForConstraintFrame
double m_angularLowerLimit
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
btVector3FloatData m_localScaling
btVector3FloatData m_planeNormal
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
btMeshPartData * m_meshPartsPtr
btVector3FloatData m_scaling
The btTriangleInfoMap stores edge angle information for some triangles. You can compute this informat...
void deSerialize(struct btTriangleInfoMapData &data)
fills the dataBuffer and returns the struct name (and 0 on failure)
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
btStridingMeshInterfaceData m_meshInterface
btQuantizedBvhDoubleData * m_quantizedDoubleBvh
btQuantizedBvhFloatData * m_quantizedFloatBvh
btTriangleInfoMapData * m_triangleInfoMap
this structure is not used, except for loading pre-2.82 .bullet files
int m_disableCollisionsBetweenLinkedBodies
float m_breakingImpulseThreshold
int m_overrideNumSolverIterations
int m_disableCollisionsBetweenLinkedBodies
double m_breakingImpulseThreshold
int m_overrideNumSolverIterations
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
int m_disableCollisionsBetweenLinkedBodies
float m_breakingImpulseThreshold
int m_overrideNumSolverIterations