Generate a single bullet.h headerfile for serialization, to make it easier to load .bullet files with no dependencies on the Bullet SDK (except Bullet/LinearMath and Bullet/Extras/Serialize/BulletFileLoader)

Added a work-in-progress example how to load a .bullet file using this bullet.h file (and not using the Bullet SDK)
This commit is contained in:
erwin.coumans 2011-02-21 22:32:12 +00:00
parent f19995aeab
commit ecaf8d2594
54 changed files with 1419 additions and 2321 deletions

View File

@ -1,4 +1,4 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
/* Copyright (C) 2011 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
@ -16,54 +16,930 @@
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
// Auto generated from Bullet/Extras/HeaderGenerator/bulletGenerate.py
#ifndef __BULLET_H__
#define __BULLET_H__
#include "bullet_PointerArray.h"
#include "bullet_btPhysicsSystem.h"
#include "bullet_ListBase.h"
#include "bullet_btVector3FloatData.h"
#include "bullet_btVector3DoubleData.h"
#include "bullet_btMatrix3x3FloatData.h"
#include "bullet_btMatrix3x3DoubleData.h"
#include "bullet_btTransformFloatData.h"
#include "bullet_btTransformDoubleData.h"
#include "bullet_btBvhSubtreeInfoData.h"
#include "bullet_btOptimizedBvhNodeFloatData.h"
#include "bullet_btOptimizedBvhNodeDoubleData.h"
#include "bullet_btQuantizedBvhNodeData.h"
#include "bullet_btQuantizedBvhFloatData.h"
#include "bullet_btQuantizedBvhDoubleData.h"
#include "bullet_btCollisionShapeData.h"
#include "bullet_btStaticPlaneShapeData.h"
#include "bullet_btConvexInternalShapeData.h"
#include "bullet_btPositionAndRadius.h"
#include "bullet_btMultiSphereShapeData.h"
#include "bullet_btIntIndexData.h"
#include "bullet_btShortIntIndexData.h"
#include "bullet_btShortIntIndexTripletData.h"
#include "bullet_btMeshPartData.h"
#include "bullet_btStridingMeshInterfaceData.h"
#include "bullet_btTriangleMeshShapeData.h"
#include "bullet_btCompoundShapeChildData.h"
#include "bullet_btCompoundShapeData.h"
#include "bullet_btCylinderShapeData.h"
#include "bullet_btCapsuleShapeData.h"
#include "bullet_btTriangleInfoData.h"
#include "bullet_btTriangleInfoMapData.h"
#include "bullet_btGImpactMeshShapeData.h"
#include "bullet_btConvexHullShapeData.h"
#include "bullet_btCollisionObjectDoubleData.h"
#include "bullet_btCollisionObjectFloatData.h"
#include "bullet_btRigidBodyFloatData.h"
#include "bullet_btRigidBodyDoubleData.h"
#include "bullet_btConstraintInfo1.h"
#include "bullet_btTypedConstraintData.h"
#include "bullet_btPoint2PointConstraintFloatData.h"
#include "bullet_btPoint2PointConstraintDoubleData.h"
#include "bullet_btHingeConstraintDoubleData.h"
#include "bullet_btHingeConstraintFloatData.h"
#include "bullet_btConeTwistConstraintData.h"
#include "bullet_btGeneric6DofConstraintData.h"
#include "bullet_btSliderConstraintData.h"
namespace Bullet {
// put an empty struct in the case
typedef struct bInvalidHandle {
int unused;
}bInvalidHandle;
class PointerArray;
class btPhysicsSystem;
class ListBase;
class btVector3FloatData;
class btVector3DoubleData;
class btMatrix3x3FloatData;
class btMatrix3x3DoubleData;
class btTransformFloatData;
class btTransformDoubleData;
class btBvhSubtreeInfoData;
class btOptimizedBvhNodeFloatData;
class btOptimizedBvhNodeDoubleData;
class btQuantizedBvhNodeData;
class btQuantizedBvhFloatData;
class btQuantizedBvhDoubleData;
class btCollisionShapeData;
class btStaticPlaneShapeData;
class btConvexInternalShapeData;
class btPositionAndRadius;
class btMultiSphereShapeData;
class btIntIndexData;
class btShortIntIndexData;
class btShortIntIndexTripletData;
class btMeshPartData;
class btStridingMeshInterfaceData;
class btTriangleMeshShapeData;
class btCompoundShapeChildData;
class btCompoundShapeData;
class btCylinderShapeData;
class btCapsuleShapeData;
class btTriangleInfoData;
class btTriangleInfoMapData;
class btGImpactMeshShapeData;
class btConvexHullShapeData;
class btCollisionObjectDoubleData;
class btCollisionObjectFloatData;
class btRigidBodyFloatData;
class btRigidBodyDoubleData;
class btConstraintInfo1;
class btTypedConstraintData;
class btPoint2PointConstraintFloatData;
class btPoint2PointConstraintDoubleData;
class btHingeConstraintDoubleData;
class btHingeConstraintFloatData;
class btConeTwistConstraintData;
class btGeneric6DofConstraintData;
class btGeneric6DofSpringConstraintData;
class btSliderConstraintData;
class SoftBodyMaterialData;
class SoftBodyNodeData;
class SoftBodyLinkData;
class SoftBodyFaceData;
class SoftBodyTetraData;
class SoftRigidAnchorData;
class SoftBodyConfigData;
class SoftBodyPoseData;
class SoftBodyClusterData;
class btSoftBodyJointData;
class btSoftBodyFloatData;
// -------------------------------------------------- //
class PointerArray
{
public:
int m_size;
int m_capacity;
void *m_data;
};
// -------------------------------------------------- //
class btPhysicsSystem
{
public:
PointerArray m_collisionShapes;
PointerArray m_collisionObjects;
PointerArray m_constraints;
};
// -------------------------------------------------- //
class ListBase
{
public:
void *first;
void *last;
};
// -------------------------------------------------- //
class btVector3FloatData
{
public:
float m_floats[4];
};
// -------------------------------------------------- //
class btVector3DoubleData
{
public:
double m_floats[4];
};
// -------------------------------------------------- //
class btMatrix3x3FloatData
{
public:
btVector3FloatData m_el[3];
};
// -------------------------------------------------- //
class btMatrix3x3DoubleData
{
public:
btVector3DoubleData m_el[3];
};
// -------------------------------------------------- //
class btTransformFloatData
{
public:
btMatrix3x3FloatData m_basis;
btVector3FloatData m_origin;
};
// -------------------------------------------------- //
class btTransformDoubleData
{
public:
btMatrix3x3DoubleData m_basis;
btVector3DoubleData m_origin;
};
// -------------------------------------------------- //
class btBvhSubtreeInfoData
{
public:
int m_rootNodeIndex;
int m_subtreeSize;
short m_quantizedAabbMin[3];
short m_quantizedAabbMax[3];
};
// -------------------------------------------------- //
class btOptimizedBvhNodeFloatData
{
public:
btVector3FloatData m_aabbMinOrg;
btVector3FloatData m_aabbMaxOrg;
int m_escapeIndex;
int m_subPart;
int m_triangleIndex;
char m_pad[4];
};
// -------------------------------------------------- //
class btOptimizedBvhNodeDoubleData
{
public:
btVector3DoubleData m_aabbMinOrg;
btVector3DoubleData m_aabbMaxOrg;
int m_escapeIndex;
int m_subPart;
int m_triangleIndex;
char m_pad[4];
};
// -------------------------------------------------- //
class btQuantizedBvhNodeData
{
public:
short m_quantizedAabbMin[3];
short m_quantizedAabbMax[3];
int m_escapeIndexOrTriangleIndex;
};
// -------------------------------------------------- //
class btQuantizedBvhFloatData
{
public:
btVector3FloatData m_bvhAabbMin;
btVector3FloatData m_bvhAabbMax;
btVector3FloatData m_bvhQuantization;
int m_curNodeIndex;
int m_useQuantization;
int m_numContiguousLeafNodes;
int m_numQuantizedContiguousNodes;
btOptimizedBvhNodeFloatData *m_contiguousNodesPtr;
btQuantizedBvhNodeData *m_quantizedContiguousNodesPtr;
btBvhSubtreeInfoData *m_subTreeInfoPtr;
int m_traversalMode;
int m_numSubtreeHeaders;
};
// -------------------------------------------------- //
class btQuantizedBvhDoubleData
{
public:
btVector3DoubleData m_bvhAabbMin;
btVector3DoubleData m_bvhAabbMax;
btVector3DoubleData m_bvhQuantization;
int m_curNodeIndex;
int m_useQuantization;
int m_numContiguousLeafNodes;
int m_numQuantizedContiguousNodes;
btOptimizedBvhNodeDoubleData *m_contiguousNodesPtr;
btQuantizedBvhNodeData *m_quantizedContiguousNodesPtr;
int m_traversalMode;
int m_numSubtreeHeaders;
btBvhSubtreeInfoData *m_subTreeInfoPtr;
};
// -------------------------------------------------- //
class btCollisionShapeData
{
public:
char *m_name;
int m_shapeType;
char m_padding[4];
};
// -------------------------------------------------- //
class btStaticPlaneShapeData
{
public:
btCollisionShapeData m_collisionShapeData;
btVector3FloatData m_localScaling;
btVector3FloatData m_planeNormal;
float m_planeConstant;
char m_pad[4];
};
// -------------------------------------------------- //
class btConvexInternalShapeData
{
public:
btCollisionShapeData m_collisionShapeData;
btVector3FloatData m_localScaling;
btVector3FloatData m_implicitShapeDimensions;
float m_collisionMargin;
int m_padding;
};
// -------------------------------------------------- //
class btPositionAndRadius
{
public:
btVector3FloatData m_pos;
float m_radius;
};
// -------------------------------------------------- //
class btMultiSphereShapeData
{
public:
btConvexInternalShapeData m_convexInternalShapeData;
btPositionAndRadius *m_localPositionArrayPtr;
int m_localPositionArraySize;
char m_padding[4];
};
// -------------------------------------------------- //
class btIntIndexData
{
public:
int m_value;
};
// -------------------------------------------------- //
class btShortIntIndexData
{
public:
short m_value;
char m_pad[2];
};
// -------------------------------------------------- //
class btShortIntIndexTripletData
{
public:
short m_values[3];
char m_pad[2];
};
// -------------------------------------------------- //
class btMeshPartData
{
public:
btVector3FloatData *m_vertices3f;
btVector3DoubleData *m_vertices3d;
btIntIndexData *m_indices32;
btShortIntIndexTripletData *m_3indices16;
btShortIntIndexData *m_indices16;
int m_numTriangles;
int m_numVertices;
};
// -------------------------------------------------- //
class btStridingMeshInterfaceData
{
public:
btMeshPartData *m_meshPartsPtr;
btVector3FloatData m_scaling;
int m_numMeshParts;
char m_padding[4];
};
// -------------------------------------------------- //
class btTriangleMeshShapeData
{
public:
btCollisionShapeData m_collisionShapeData;
btStridingMeshInterfaceData m_meshInterface;
btQuantizedBvhFloatData *m_quantizedFloatBvh;
btQuantizedBvhDoubleData *m_quantizedDoubleBvh;
btTriangleInfoMapData *m_triangleInfoMap;
float m_collisionMargin;
char m_pad3[4];
};
// -------------------------------------------------- //
class btCompoundShapeChildData
{
public:
btTransformFloatData m_transform;
btCollisionShapeData *m_childShape;
int m_childShapeType;
float m_childMargin;
};
// -------------------------------------------------- //
class btCompoundShapeData
{
public:
btCollisionShapeData m_collisionShapeData;
btCompoundShapeChildData *m_childShapePtr;
int m_numChildShapes;
float m_collisionMargin;
};
// -------------------------------------------------- //
class btCylinderShapeData
{
public:
btConvexInternalShapeData m_convexInternalShapeData;
int m_upAxis;
char m_padding[4];
};
// -------------------------------------------------- //
class btCapsuleShapeData
{
public:
btConvexInternalShapeData m_convexInternalShapeData;
int m_upAxis;
char m_padding[4];
};
// -------------------------------------------------- //
class btTriangleInfoData
{
public:
int m_flags;
float m_edgeV0V1Angle;
float m_edgeV1V2Angle;
float m_edgeV2V0Angle;
};
// -------------------------------------------------- //
class btTriangleInfoMapData
{
public:
int *m_hashTablePtr;
int *m_nextPtr;
btTriangleInfoData *m_valueArrayPtr;
int *m_keyArrayPtr;
float m_convexEpsilon;
float m_planarEpsilon;
float m_equalVertexThreshold;
float m_edgeDistanceThreshold;
float m_zeroAreaThreshold;
int m_nextSize;
int m_hashTableSize;
int m_numValues;
int m_numKeys;
char m_padding[4];
};
// -------------------------------------------------- //
class btGImpactMeshShapeData
{
public:
btCollisionShapeData m_collisionShapeData;
btStridingMeshInterfaceData m_meshInterface;
btVector3FloatData m_localScaling;
float m_collisionMargin;
int m_gimpactSubType;
};
// -------------------------------------------------- //
class btConvexHullShapeData
{
public:
btConvexInternalShapeData m_convexInternalShapeData;
btVector3FloatData *m_unscaledPointsFloatPtr;
btVector3DoubleData *m_unscaledPointsDoublePtr;
int m_numUnscaledPoints;
char m_padding3[4];
};
// -------------------------------------------------- //
class btCollisionObjectDoubleData
{
public:
void *m_broadphaseHandle;
void *m_collisionShape;
btCollisionShapeData *m_rootCollisionShape;
char *m_name;
btTransformDoubleData m_worldTransform;
btTransformDoubleData m_interpolationWorldTransform;
btVector3DoubleData m_interpolationLinearVelocity;
btVector3DoubleData m_interpolationAngularVelocity;
btVector3DoubleData m_anisotropicFriction;
double m_contactProcessingThreshold;
double m_deactivationTime;
double m_friction;
double m_restitution;
double m_hitFraction;
double m_ccdSweptSphereRadius;
double m_ccdMotionThreshold;
int m_hasAnisotropicFriction;
int m_collisionFlags;
int m_islandTag1;
int m_companionId;
int m_activationState1;
int m_internalType;
int m_checkCollideWith;
char m_padding[4];
};
// -------------------------------------------------- //
class btCollisionObjectFloatData
{
public:
void *m_broadphaseHandle;
void *m_collisionShape;
btCollisionShapeData *m_rootCollisionShape;
char *m_name;
btTransformFloatData m_worldTransform;
btTransformFloatData m_interpolationWorldTransform;
btVector3FloatData m_interpolationLinearVelocity;
btVector3FloatData m_interpolationAngularVelocity;
btVector3FloatData m_anisotropicFriction;
float m_contactProcessingThreshold;
float m_deactivationTime;
float m_friction;
float m_restitution;
float m_hitFraction;
float m_ccdSweptSphereRadius;
float m_ccdMotionThreshold;
int m_hasAnisotropicFriction;
int m_collisionFlags;
int m_islandTag1;
int m_companionId;
int m_activationState1;
int m_internalType;
int m_checkCollideWith;
};
// -------------------------------------------------- //
class btRigidBodyFloatData
{
public:
btCollisionObjectFloatData m_collisionObjectData;
btMatrix3x3FloatData m_invInertiaTensorWorld;
btVector3FloatData m_linearVelocity;
btVector3FloatData m_angularVelocity;
btVector3FloatData m_angularFactor;
btVector3FloatData m_linearFactor;
btVector3FloatData m_gravity;
btVector3FloatData m_gravity_acceleration;
btVector3FloatData m_invInertiaLocal;
btVector3FloatData m_totalForce;
btVector3FloatData m_totalTorque;
float m_inverseMass;
float m_linearDamping;
float m_angularDamping;
float m_additionalDampingFactor;
float m_additionalLinearDampingThresholdSqr;
float m_additionalAngularDampingThresholdSqr;
float m_additionalAngularDampingFactor;
float m_linearSleepingThreshold;
float m_angularSleepingThreshold;
int m_additionalDamping;
};
// -------------------------------------------------- //
class btRigidBodyDoubleData
{
public:
btCollisionObjectDoubleData m_collisionObjectData;
btMatrix3x3DoubleData m_invInertiaTensorWorld;
btVector3DoubleData m_linearVelocity;
btVector3DoubleData m_angularVelocity;
btVector3DoubleData m_angularFactor;
btVector3DoubleData m_linearFactor;
btVector3DoubleData m_gravity;
btVector3DoubleData m_gravity_acceleration;
btVector3DoubleData m_invInertiaLocal;
btVector3DoubleData m_totalForce;
btVector3DoubleData m_totalTorque;
double m_inverseMass;
double m_linearDamping;
double m_angularDamping;
double m_additionalDampingFactor;
double m_additionalLinearDampingThresholdSqr;
double m_additionalAngularDampingThresholdSqr;
double m_additionalAngularDampingFactor;
double m_linearSleepingThreshold;
double m_angularSleepingThreshold;
int m_additionalDamping;
char m_padding[4];
};
// -------------------------------------------------- //
class btConstraintInfo1
{
public:
int m_numConstraintRows;
int nub;
};
// -------------------------------------------------- //
class btTypedConstraintData
{
public:
bInvalidHandle *m_rbA;
bInvalidHandle *m_rbB;
char *m_name;
int m_objectType;
int m_userConstraintType;
int m_userConstraintId;
int m_needsFeedback;
float m_appliedImpulse;
float m_dbgDrawSize;
int m_disableCollisionsBetweenLinkedBodies;
char m_pad4[4];
};
// -------------------------------------------------- //
class btPoint2PointConstraintFloatData
{
public:
btTypedConstraintData m_typeConstraintData;
btVector3FloatData m_pivotInA;
btVector3FloatData m_pivotInB;
};
// -------------------------------------------------- //
class btPoint2PointConstraintDoubleData
{
public:
btTypedConstraintData m_typeConstraintData;
btVector3DoubleData m_pivotInA;
btVector3DoubleData m_pivotInB;
};
// -------------------------------------------------- //
class btHingeConstraintDoubleData
{
public:
btTypedConstraintData m_typeConstraintData;
btTransformDoubleData m_rbAFrame;
btTransformDoubleData m_rbBFrame;
int m_useReferenceFrameA;
int m_angularOnly;
int m_enableAngularMotor;
float m_motorTargetVelocity;
float m_maxMotorImpulse;
float m_lowerLimit;
float m_upperLimit;
float m_limitSoftness;
float m_biasFactor;
float m_relaxationFactor;
};
// -------------------------------------------------- //
class btHingeConstraintFloatData
{
public:
btTypedConstraintData m_typeConstraintData;
btTransformFloatData m_rbAFrame;
btTransformFloatData m_rbBFrame;
int m_useReferenceFrameA;
int m_angularOnly;
int m_enableAngularMotor;
float m_motorTargetVelocity;
float m_maxMotorImpulse;
float m_lowerLimit;
float m_upperLimit;
float m_limitSoftness;
float m_biasFactor;
float m_relaxationFactor;
};
// -------------------------------------------------- //
class btConeTwistConstraintData
{
public:
btTypedConstraintData m_typeConstraintData;
btTransformFloatData m_rbAFrame;
btTransformFloatData m_rbBFrame;
float m_swingSpan1;
float m_swingSpan2;
float m_twistSpan;
float m_limitSoftness;
float m_biasFactor;
float m_relaxationFactor;
float m_damping;
char m_pad[4];
};
// -------------------------------------------------- //
class btGeneric6DofConstraintData
{
public:
btTypedConstraintData m_typeConstraintData;
btTransformFloatData m_rbAFrame;
btTransformFloatData m_rbBFrame;
btVector3FloatData m_linearUpperLimit;
btVector3FloatData m_linearLowerLimit;
btVector3FloatData m_angularUpperLimit;
btVector3FloatData m_angularLowerLimit;
int m_useLinearReferenceFrameA;
int m_useOffsetForConstraintFrame;
};
// -------------------------------------------------- //
class btGeneric6DofSpringConstraintData
{
public:
btGeneric6DofConstraintData m_6dofData;
int m_springEnabled[6];
float m_equilibriumPoint[6];
float m_springStiffness[6];
float m_springDamping[6];
};
// -------------------------------------------------- //
class btSliderConstraintData
{
public:
btTypedConstraintData m_typeConstraintData;
btTransformFloatData m_rbAFrame;
btTransformFloatData m_rbBFrame;
float m_linearUpperLimit;
float m_linearLowerLimit;
float m_angularUpperLimit;
float m_angularLowerLimit;
int m_useLinearReferenceFrameA;
int m_useOffsetForConstraintFrame;
};
// -------------------------------------------------- //
class SoftBodyMaterialData
{
public:
float m_linearStiffness;
float m_angularStiffness;
float m_volumeStiffness;
int m_flags;
};
// -------------------------------------------------- //
class SoftBodyNodeData
{
public:
SoftBodyMaterialData *m_material;
btVector3FloatData m_position;
btVector3FloatData m_previousPosition;
btVector3FloatData m_velocity;
btVector3FloatData m_accumulatedForce;
btVector3FloatData m_normal;
float m_inverseMass;
float m_area;
int m_attach;
int m_pad;
};
// -------------------------------------------------- //
class SoftBodyLinkData
{
public:
SoftBodyMaterialData *m_material;
int m_nodeIndices[2];
float m_restLength;
int m_bbending;
};
// -------------------------------------------------- //
class SoftBodyFaceData
{
public:
btVector3FloatData m_normal;
SoftBodyMaterialData *m_material;
int m_nodeIndices[3];
float m_restArea;
};
// -------------------------------------------------- //
class SoftBodyTetraData
{
public:
btVector3FloatData m_c0[4];
SoftBodyMaterialData *m_material;
int m_nodeIndices[4];
float m_restVolume;
float m_c1;
float m_c2;
int m_pad;
};
// -------------------------------------------------- //
class SoftRigidAnchorData
{
public:
btMatrix3x3FloatData m_c0;
btVector3FloatData m_c1;
btVector3FloatData m_localFrame;
bInvalidHandle *m_rigidBody;
int m_nodeIndex;
float m_c2;
};
// -------------------------------------------------- //
class SoftBodyConfigData
{
public:
int m_aeroModel;
float m_baumgarte;
float m_damping;
float m_drag;
float m_lift;
float m_pressure;
float m_volume;
float m_dynamicFriction;
float m_poseMatch;
float m_rigidContactHardness;
float m_kineticContactHardness;
float m_softContactHardness;
float m_anchorHardness;
float m_softRigidClusterHardness;
float m_softKineticClusterHardness;
float m_softSoftClusterHardness;
float m_softRigidClusterImpulseSplit;
float m_softKineticClusterImpulseSplit;
float m_softSoftClusterImpulseSplit;
float m_maxVolume;
float m_timeScale;
int m_velocityIterations;
int m_positionIterations;
int m_driftIterations;
int m_clusterIterations;
int m_collisionFlags;
};
// -------------------------------------------------- //
class SoftBodyPoseData
{
public:
btMatrix3x3FloatData m_rot;
btMatrix3x3FloatData m_scale;
btMatrix3x3FloatData m_aqq;
btVector3FloatData m_com;
btVector3FloatData *m_positions;
float *m_weights;
int m_numPositions;
int m_numWeigts;
int m_bvolume;
int m_bframe;
float m_restVolume;
int m_pad;
};
// -------------------------------------------------- //
class SoftBodyClusterData
{
public:
btTransformFloatData m_framexform;
btMatrix3x3FloatData m_locii;
btMatrix3x3FloatData m_invwi;
btVector3FloatData m_com;
btVector3FloatData m_vimpulses[2];
btVector3FloatData m_dimpulses[2];
btVector3FloatData m_lv;
btVector3FloatData m_av;
btVector3FloatData *m_framerefs;
int *m_nodeIndices;
float *m_masses;
int m_numFrameRefs;
int m_numNodes;
int m_numMasses;
float m_idmass;
float m_imass;
int m_nvimpulses;
int m_ndimpulses;
float m_ndamping;
float m_ldamping;
float m_adamping;
float m_matching;
float m_maxSelfCollisionImpulse;
float m_selfCollisionImpulseFactor;
int m_containsAnchor;
int m_collide;
int m_clusterIndex;
};
// -------------------------------------------------- //
class btSoftBodyJointData
{
public:
void *m_bodyA;
void *m_bodyB;
btVector3FloatData m_refs[2];
float m_cfm;
float m_erp;
float m_split;
int m_delete;
btVector3FloatData m_relPosition[2];
int m_bodyAtype;
int m_bodyBtype;
int m_jointType;
int m_pad;
};
// -------------------------------------------------- //
class btSoftBodyFloatData
{
public:
btCollisionObjectFloatData m_collisionObjectData;
SoftBodyPoseData *m_pose;
SoftBodyMaterialData **m_materials;
SoftBodyNodeData *m_nodes;
SoftBodyLinkData *m_links;
SoftBodyFaceData *m_faces;
SoftBodyTetraData *m_tetrahedra;
SoftRigidAnchorData *m_anchors;
SoftBodyClusterData *m_clusters;
btSoftBodyJointData *m_joints;
int m_numMaterials;
int m_numNodes;
int m_numLinks;
int m_numFaces;
int m_numTetrahedra;
int m_numAnchors;
int m_numClusters;
int m_numJoints;
SoftBodyConfigData m_config;
};
}
#endif//__BULLET_H__

View File

@ -1,77 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLETCOMMON_H__
#define __BULLETCOMMON_H__
// put an empty struct in the case
typedef struct bInvalidHandle {
int unused;
}bInvalidHandle;
namespace Bullet {
class PointerArray;
class btPhysicsSystem;
class ListBase;
class btVector3FloatData;
class btVector3DoubleData;
class btMatrix3x3FloatData;
class btMatrix3x3DoubleData;
class btTransformFloatData;
class btTransformDoubleData;
class btBvhSubtreeInfoData;
class btOptimizedBvhNodeFloatData;
class btOptimizedBvhNodeDoubleData;
class btQuantizedBvhNodeData;
class btQuantizedBvhFloatData;
class btQuantizedBvhDoubleData;
class btCollisionShapeData;
class btStaticPlaneShapeData;
class btConvexInternalShapeData;
class btPositionAndRadius;
class btMultiSphereShapeData;
class btIntIndexData;
class btShortIntIndexData;
class btShortIntIndexTripletData;
class btMeshPartData;
class btStridingMeshInterfaceData;
class btTriangleMeshShapeData;
class btCompoundShapeChildData;
class btCompoundShapeData;
class btCylinderShapeData;
class btCapsuleShapeData;
class btTriangleInfoData;
class btTriangleInfoMapData;
class btGImpactMeshShapeData;
class btConvexHullShapeData;
class btCollisionObjectDoubleData;
class btCollisionObjectFloatData;
class btRigidBodyFloatData;
class btRigidBodyDoubleData;
class btConstraintInfo1;
class btTypedConstraintData;
class btPoint2PointConstraintFloatData;
class btPoint2PointConstraintDoubleData;
class btHingeConstraintDoubleData;
class btHingeConstraintFloatData;
class btConeTwistConstraintData;
class btGeneric6DofConstraintData;
class btSliderConstraintData;
}
#endif//__BULLETCOMMON_H__

View File

@ -1,40 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_LISTBASE__H__
#define __BULLET_LISTBASE__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
namespace Bullet {
// ---------------------------------------------- //
class ListBase
{
public:
void *first;
void *last;
};
}
#endif//__BULLET_LISTBASE__H__

View File

@ -1,41 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_POINTERARRAY__H__
#define __BULLET_POINTERARRAY__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
namespace Bullet {
// ---------------------------------------------- //
class PointerArray
{
public:
int m_size;
int m_capacity;
void *m_data;
};
}
#endif//__BULLET_POINTERARRAY__H__

View File

@ -1,42 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTBVHSUBTREEINFODATA__H__
#define __BULLET_BTBVHSUBTREEINFODATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
namespace Bullet {
// ---------------------------------------------- //
class btBvhSubtreeInfoData
{
public:
int m_rootNodeIndex;
int m_subtreeSize;
short m_quantizedAabbMin[3];
short m_quantizedAabbMax[3];
};
}
#endif//__BULLET_BTBVHSUBTREEINFODATA__H__

View File

@ -1,42 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTCAPSULESHAPEDATA__H__
#define __BULLET_BTCAPSULESHAPEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btConvexInternalShapeData.h"
namespace Bullet {
// ---------------------------------------------- //
class btCapsuleShapeData
{
public:
btConvexInternalShapeData m_convexInternalShapeData;
int m_upAxis;
char m_padding[4];
};
}
#endif//__BULLET_BTCAPSULESHAPEDATA__H__

View File

@ -1,64 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTCOLLISIONOBJECTDOUBLEDATA__H__
#define __BULLET_BTCOLLISIONOBJECTDOUBLEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btTransformDoubleData.h"
#include "bullet_btVector3DoubleData.h"
namespace Bullet {
// ---------------------------------------------- //
class btCollisionObjectDoubleData
{
public:
void *m_broadphaseHandle;
void *m_collisionShape;
btCollisionShapeData *m_rootCollisionShape;
char *m_name;
btTransformDoubleData m_worldTransform;
btTransformDoubleData m_interpolationWorldTransform;
btVector3DoubleData m_interpolationLinearVelocity;
btVector3DoubleData m_interpolationAngularVelocity;
btVector3DoubleData m_anisotropicFriction;
double m_contactProcessingThreshold;
double m_deactivationTime;
double m_friction;
double m_restitution;
double m_hitFraction;
double m_ccdSweptSphereRadius;
double m_ccdMotionThreshold;
int m_hasAnisotropicFriction;
int m_collisionFlags;
int m_islandTag1;
int m_companionId;
int m_activationState1;
int m_internalType;
int m_checkCollideWith;
char m_padding[4];
};
}
#endif//__BULLET_BTCOLLISIONOBJECTDOUBLEDATA__H__

View File

@ -1,63 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTCOLLISIONOBJECTFLOATDATA__H__
#define __BULLET_BTCOLLISIONOBJECTFLOATDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btTransformFloatData.h"
#include "bullet_btVector3FloatData.h"
namespace Bullet {
// ---------------------------------------------- //
class btCollisionObjectFloatData
{
public:
void *m_broadphaseHandle;
void *m_collisionShape;
btCollisionShapeData *m_rootCollisionShape;
char *m_name;
btTransformFloatData m_worldTransform;
btTransformFloatData m_interpolationWorldTransform;
btVector3FloatData m_interpolationLinearVelocity;
btVector3FloatData m_interpolationAngularVelocity;
btVector3FloatData m_anisotropicFriction;
float m_contactProcessingThreshold;
float m_deactivationTime;
float m_friction;
float m_restitution;
float m_hitFraction;
float m_ccdSweptSphereRadius;
float m_ccdMotionThreshold;
int m_hasAnisotropicFriction;
int m_collisionFlags;
int m_islandTag1;
int m_companionId;
int m_activationState1;
int m_internalType;
int m_checkCollideWith;
};
}
#endif//__BULLET_BTCOLLISIONOBJECTFLOATDATA__H__

View File

@ -1,41 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTCOLLISIONSHAPEDATA__H__
#define __BULLET_BTCOLLISIONSHAPEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
namespace Bullet {
// ---------------------------------------------- //
class btCollisionShapeData
{
public:
char *m_name;
int m_shapeType;
char m_padding[4];
};
}
#endif//__BULLET_BTCOLLISIONSHAPEDATA__H__

View File

@ -1,43 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTCOMPOUNDSHAPECHILDDATA__H__
#define __BULLET_BTCOMPOUNDSHAPECHILDDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btTransformFloatData.h"
namespace Bullet {
// ---------------------------------------------- //
class btCompoundShapeChildData
{
public:
btTransformFloatData m_transform;
btCollisionShapeData *m_childShape;
int m_childShapeType;
float m_childMargin;
};
}
#endif//__BULLET_BTCOMPOUNDSHAPECHILDDATA__H__

View File

@ -1,43 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTCOMPOUNDSHAPEDATA__H__
#define __BULLET_BTCOMPOUNDSHAPEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btCollisionShapeData.h"
namespace Bullet {
// ---------------------------------------------- //
class btCompoundShapeData
{
public:
btCollisionShapeData m_collisionShapeData;
btCompoundShapeChildData *m_childShapePtr;
int m_numChildShapes;
float m_collisionMargin;
};
}
#endif//__BULLET_BTCOMPOUNDSHAPEDATA__H__

View File

@ -1,51 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTCONETWISTCONSTRAINTDATA__H__
#define __BULLET_BTCONETWISTCONSTRAINTDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btTransformFloatData.h"
#include "bullet_btTypedConstraintData.h"
namespace Bullet {
// ---------------------------------------------- //
class btConeTwistConstraintData
{
public:
btTypedConstraintData m_typeConstraintData;
btTransformFloatData m_rbAFrame;
btTransformFloatData m_rbBFrame;
float m_swingSpan1;
float m_swingSpan2;
float m_twistSpan;
float m_limitSoftness;
float m_biasFactor;
float m_relaxationFactor;
float m_damping;
char m_pad[4];
};
}
#endif//__BULLET_BTCONETWISTCONSTRAINTDATA__H__

View File

@ -1,40 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTCONSTRAINTINFO1__H__
#define __BULLET_BTCONSTRAINTINFO1__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
namespace Bullet {
// ---------------------------------------------- //
class btConstraintInfo1
{
public:
int m_numConstraintRows;
int nub;
};
}
#endif//__BULLET_BTCONSTRAINTINFO1__H__

View File

@ -1,44 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTCONVEXHULLSHAPEDATA__H__
#define __BULLET_BTCONVEXHULLSHAPEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btConvexInternalShapeData.h"
namespace Bullet {
// ---------------------------------------------- //
class btConvexHullShapeData
{
public:
btConvexInternalShapeData m_convexInternalShapeData;
btVector3FloatData *m_unscaledPointsFloatPtr;
btVector3DoubleData *m_unscaledPointsDoublePtr;
int m_numUnscaledPoints;
char m_padding3[4];
};
}
#endif//__BULLET_BTCONVEXHULLSHAPEDATA__H__

View File

@ -1,45 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTCONVEXINTERNALSHAPEDATA__H__
#define __BULLET_BTCONVEXINTERNALSHAPEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btCollisionShapeData.h"
#include "bullet_btVector3FloatData.h"
namespace Bullet {
// ---------------------------------------------- //
class btConvexInternalShapeData
{
public:
btCollisionShapeData m_collisionShapeData;
btVector3FloatData m_localScaling;
btVector3FloatData m_implicitShapeDimensions;
float m_collisionMargin;
int m_padding;
};
}
#endif//__BULLET_BTCONVEXINTERNALSHAPEDATA__H__

View File

@ -1,42 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTCYLINDERSHAPEDATA__H__
#define __BULLET_BTCYLINDERSHAPEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btConvexInternalShapeData.h"
namespace Bullet {
// ---------------------------------------------- //
class btCylinderShapeData
{
public:
btConvexInternalShapeData m_convexInternalShapeData;
int m_upAxis;
char m_padding[4];
};
}
#endif//__BULLET_BTCYLINDERSHAPEDATA__H__

View File

@ -1,46 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTGIMPACTMESHSHAPEDATA__H__
#define __BULLET_BTGIMPACTMESHSHAPEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btCollisionShapeData.h"
#include "bullet_btStridingMeshInterfaceData.h"
#include "bullet_btVector3FloatData.h"
namespace Bullet {
// ---------------------------------------------- //
class btGImpactMeshShapeData
{
public:
btCollisionShapeData m_collisionShapeData;
btStridingMeshInterfaceData m_meshInterface;
btVector3FloatData m_localScaling;
float m_collisionMargin;
int m_gimpactSubType;
};
}
#endif//__BULLET_BTGIMPACTMESHSHAPEDATA__H__

View File

@ -1,50 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTGENERIC6DOFCONSTRAINTDATA__H__
#define __BULLET_BTGENERIC6DOFCONSTRAINTDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btTransformFloatData.h"
#include "bullet_btTypedConstraintData.h"
#include "bullet_btVector3FloatData.h"
namespace Bullet {
// ---------------------------------------------- //
class btGeneric6DofConstraintData
{
public:
btTypedConstraintData m_typeConstraintData;
btTransformFloatData m_rbAFrame;
btTransformFloatData m_rbBFrame;
btVector3FloatData m_linearUpperLimit;
btVector3FloatData m_linearLowerLimit;
btVector3FloatData m_angularUpperLimit;
btVector3FloatData m_angularLowerLimit;
int m_useLinearReferenceFrameA;
int m_useOffsetForConstraintFrame;
};
}
#endif//__BULLET_BTGENERIC6DOFCONSTRAINTDATA__H__

View File

@ -1,53 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTHINGECONSTRAINTDOUBLEDATA__H__
#define __BULLET_BTHINGECONSTRAINTDOUBLEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btTransformDoubleData.h"
#include "bullet_btTypedConstraintData.h"
namespace Bullet {
// ---------------------------------------------- //
class btHingeConstraintDoubleData
{
public:
btTypedConstraintData m_typeConstraintData;
btTransformDoubleData m_rbAFrame;
btTransformDoubleData m_rbBFrame;
int m_useReferenceFrameA;
int m_angularOnly;
int m_enableAngularMotor;
float m_motorTargetVelocity;
float m_maxMotorImpulse;
float m_lowerLimit;
float m_upperLimit;
float m_limitSoftness;
float m_biasFactor;
float m_relaxationFactor;
};
}
#endif//__BULLET_BTHINGECONSTRAINTDOUBLEDATA__H__

View File

@ -1,53 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTHINGECONSTRAINTFLOATDATA__H__
#define __BULLET_BTHINGECONSTRAINTFLOATDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btTransformFloatData.h"
#include "bullet_btTypedConstraintData.h"
namespace Bullet {
// ---------------------------------------------- //
class btHingeConstraintFloatData
{
public:
btTypedConstraintData m_typeConstraintData;
btTransformFloatData m_rbAFrame;
btTransformFloatData m_rbBFrame;
int m_useReferenceFrameA;
int m_angularOnly;
int m_enableAngularMotor;
float m_motorTargetVelocity;
float m_maxMotorImpulse;
float m_lowerLimit;
float m_upperLimit;
float m_limitSoftness;
float m_biasFactor;
float m_relaxationFactor;
};
}
#endif//__BULLET_BTHINGECONSTRAINTFLOATDATA__H__

View File

@ -1,39 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTINTINDEXDATA__H__
#define __BULLET_BTINTINDEXDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
namespace Bullet {
// ---------------------------------------------- //
class btIntIndexData
{
public:
int m_value;
};
}
#endif//__BULLET_BTINTINDEXDATA__H__

View File

@ -1,40 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTMATRIX3X3DOUBLEDATA__H__
#define __BULLET_BTMATRIX3X3DOUBLEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btVector3DoubleData.h"
namespace Bullet {
// ---------------------------------------------- //
class btMatrix3x3DoubleData
{
public:
btVector3DoubleData m_el[3];
};
}
#endif//__BULLET_BTMATRIX3X3DOUBLEDATA__H__

View File

@ -1,40 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTMATRIX3X3FLOATDATA__H__
#define __BULLET_BTMATRIX3X3FLOATDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btVector3FloatData.h"
namespace Bullet {
// ---------------------------------------------- //
class btMatrix3x3FloatData
{
public:
btVector3FloatData m_el[3];
};
}
#endif//__BULLET_BTMATRIX3X3FLOATDATA__H__

View File

@ -1,45 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTMESHPARTDATA__H__
#define __BULLET_BTMESHPARTDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
namespace Bullet {
// ---------------------------------------------- //
class btMeshPartData
{
public:
btVector3FloatData *m_vertices3f;
btVector3DoubleData *m_vertices3d;
btIntIndexData *m_indices32;
btShortIntIndexTripletData *m_3indices16;
btShortIntIndexData *m_indices16;
int m_numTriangles;
int m_numVertices;
};
}
#endif//__BULLET_BTMESHPARTDATA__H__

View File

@ -1,43 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTMULTISPHERESHAPEDATA__H__
#define __BULLET_BTMULTISPHERESHAPEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btConvexInternalShapeData.h"
namespace Bullet {
// ---------------------------------------------- //
class btMultiSphereShapeData
{
public:
btConvexInternalShapeData m_convexInternalShapeData;
btPositionAndRadius *m_localPositionArrayPtr;
int m_localPositionArraySize;
char m_padding[4];
};
}
#endif//__BULLET_BTMULTISPHERESHAPEDATA__H__

View File

@ -1,45 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTOPTIMIZEDBVHNODEDOUBLEDATA__H__
#define __BULLET_BTOPTIMIZEDBVHNODEDOUBLEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btVector3DoubleData.h"
namespace Bullet {
// ---------------------------------------------- //
class btOptimizedBvhNodeDoubleData
{
public:
btVector3DoubleData m_aabbMinOrg;
btVector3DoubleData m_aabbMaxOrg;
int m_escapeIndex;
int m_subPart;
int m_triangleIndex;
char m_pad[4];
};
}
#endif//__BULLET_BTOPTIMIZEDBVHNODEDOUBLEDATA__H__

View File

@ -1,45 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTOPTIMIZEDBVHNODEFLOATDATA__H__
#define __BULLET_BTOPTIMIZEDBVHNODEFLOATDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btVector3FloatData.h"
namespace Bullet {
// ---------------------------------------------- //
class btOptimizedBvhNodeFloatData
{
public:
btVector3FloatData m_aabbMinOrg;
btVector3FloatData m_aabbMaxOrg;
int m_escapeIndex;
int m_subPart;
int m_triangleIndex;
char m_pad[4];
};
}
#endif//__BULLET_BTOPTIMIZEDBVHNODEFLOATDATA__H__

View File

@ -1,42 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTPHYSICSSYSTEM__H__
#define __BULLET_BTPHYSICSSYSTEM__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_PointerArray.h"
namespace Bullet {
// ---------------------------------------------- //
class btPhysicsSystem
{
public:
PointerArray m_collisionShapes;
PointerArray m_collisionObjects;
PointerArray m_constraints;
};
}
#endif//__BULLET_BTPHYSICSSYSTEM__H__

View File

@ -1,43 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTPOINT2POINTCONSTRAINTDOUBLEDATA__H__
#define __BULLET_BTPOINT2POINTCONSTRAINTDOUBLEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btTypedConstraintData.h"
#include "bullet_btVector3DoubleData.h"
namespace Bullet {
// ---------------------------------------------- //
class btPoint2PointConstraintDoubleData
{
public:
btTypedConstraintData m_typeConstraintData;
btVector3DoubleData m_pivotInA;
btVector3DoubleData m_pivotInB;
};
}
#endif//__BULLET_BTPOINT2POINTCONSTRAINTDOUBLEDATA__H__

View File

@ -1,43 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTPOINT2POINTCONSTRAINTFLOATDATA__H__
#define __BULLET_BTPOINT2POINTCONSTRAINTFLOATDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btTypedConstraintData.h"
#include "bullet_btVector3FloatData.h"
namespace Bullet {
// ---------------------------------------------- //
class btPoint2PointConstraintFloatData
{
public:
btTypedConstraintData m_typeConstraintData;
btVector3FloatData m_pivotInA;
btVector3FloatData m_pivotInB;
};
}
#endif//__BULLET_BTPOINT2POINTCONSTRAINTFLOATDATA__H__

View File

@ -1,41 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTPOSITIONANDRADIUS__H__
#define __BULLET_BTPOSITIONANDRADIUS__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btVector3FloatData.h"
namespace Bullet {
// ---------------------------------------------- //
class btPositionAndRadius
{
public:
btVector3FloatData m_pos;
float m_radius;
};
}
#endif//__BULLET_BTPOSITIONANDRADIUS__H__

View File

@ -1,51 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTQUANTIZEDBVHDOUBLEDATA__H__
#define __BULLET_BTQUANTIZEDBVHDOUBLEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btVector3DoubleData.h"
namespace Bullet {
// ---------------------------------------------- //
class btQuantizedBvhDoubleData
{
public:
btVector3DoubleData m_bvhAabbMin;
btVector3DoubleData m_bvhAabbMax;
btVector3DoubleData m_bvhQuantization;
int m_curNodeIndex;
int m_useQuantization;
int m_numContiguousLeafNodes;
int m_numQuantizedContiguousNodes;
btOptimizedBvhNodeDoubleData *m_contiguousNodesPtr;
btQuantizedBvhNodeData *m_quantizedContiguousNodesPtr;
int m_traversalMode;
int m_numSubtreeHeaders;
btBvhSubtreeInfoData *m_subTreeInfoPtr;
};
}
#endif//__BULLET_BTQUANTIZEDBVHDOUBLEDATA__H__

View File

@ -1,51 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTQUANTIZEDBVHFLOATDATA__H__
#define __BULLET_BTQUANTIZEDBVHFLOATDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btVector3FloatData.h"
namespace Bullet {
// ---------------------------------------------- //
class btQuantizedBvhFloatData
{
public:
btVector3FloatData m_bvhAabbMin;
btVector3FloatData m_bvhAabbMax;
btVector3FloatData m_bvhQuantization;
int m_curNodeIndex;
int m_useQuantization;
int m_numContiguousLeafNodes;
int m_numQuantizedContiguousNodes;
btOptimizedBvhNodeFloatData *m_contiguousNodesPtr;
btQuantizedBvhNodeData *m_quantizedContiguousNodesPtr;
btBvhSubtreeInfoData *m_subTreeInfoPtr;
int m_traversalMode;
int m_numSubtreeHeaders;
};
}
#endif//__BULLET_BTQUANTIZEDBVHFLOATDATA__H__

View File

@ -1,41 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTQUANTIZEDBVHNODEDATA__H__
#define __BULLET_BTQUANTIZEDBVHNODEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
namespace Bullet {
// ---------------------------------------------- //
class btQuantizedBvhNodeData
{
public:
short m_quantizedAabbMin[3];
short m_quantizedAabbMax[3];
int m_escapeIndexOrTriangleIndex;
};
}
#endif//__BULLET_BTQUANTIZEDBVHNODEDATA__H__

View File

@ -1,63 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTRIGIDBODYDOUBLEDATA__H__
#define __BULLET_BTRIGIDBODYDOUBLEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btCollisionObjectDoubleData.h"
#include "bullet_btMatrix3x3DoubleData.h"
#include "bullet_btVector3DoubleData.h"
namespace Bullet {
// ---------------------------------------------- //
class btRigidBodyDoubleData
{
public:
btCollisionObjectDoubleData m_collisionObjectData;
btMatrix3x3DoubleData m_invInertiaTensorWorld;
btVector3DoubleData m_linearVelocity;
btVector3DoubleData m_angularVelocity;
btVector3DoubleData m_angularFactor;
btVector3DoubleData m_linearFactor;
btVector3DoubleData m_gravity;
btVector3DoubleData m_gravity_acceleration;
btVector3DoubleData m_invInertiaLocal;
btVector3DoubleData m_totalForce;
btVector3DoubleData m_totalTorque;
double m_inverseMass;
double m_linearDamping;
double m_angularDamping;
double m_additionalDampingFactor;
double m_additionalLinearDampingThresholdSqr;
double m_additionalAngularDampingThresholdSqr;
double m_additionalAngularDampingFactor;
double m_linearSleepingThreshold;
double m_angularSleepingThreshold;
int m_additionalDamping;
char m_padding[4];
};
}
#endif//__BULLET_BTRIGIDBODYDOUBLEDATA__H__

View File

@ -1,62 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTRIGIDBODYFLOATDATA__H__
#define __BULLET_BTRIGIDBODYFLOATDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btCollisionObjectFloatData.h"
#include "bullet_btMatrix3x3FloatData.h"
#include "bullet_btVector3FloatData.h"
namespace Bullet {
// ---------------------------------------------- //
class btRigidBodyFloatData
{
public:
btCollisionObjectFloatData m_collisionObjectData;
btMatrix3x3FloatData m_invInertiaTensorWorld;
btVector3FloatData m_linearVelocity;
btVector3FloatData m_angularVelocity;
btVector3FloatData m_angularFactor;
btVector3FloatData m_linearFactor;
btVector3FloatData m_gravity;
btVector3FloatData m_gravity_acceleration;
btVector3FloatData m_invInertiaLocal;
btVector3FloatData m_totalForce;
btVector3FloatData m_totalTorque;
float m_inverseMass;
float m_linearDamping;
float m_angularDamping;
float m_additionalDampingFactor;
float m_additionalLinearDampingThresholdSqr;
float m_additionalAngularDampingThresholdSqr;
float m_additionalAngularDampingFactor;
float m_linearSleepingThreshold;
float m_angularSleepingThreshold;
int m_additionalDamping;
};
}
#endif//__BULLET_BTRIGIDBODYFLOATDATA__H__

View File

@ -1,40 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTSHORTINTINDEXDATA__H__
#define __BULLET_BTSHORTINTINDEXDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
namespace Bullet {
// ---------------------------------------------- //
class btShortIntIndexData
{
public:
short m_value;
char m_pad[2];
};
}
#endif//__BULLET_BTSHORTINTINDEXDATA__H__

View File

@ -1,40 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTSHORTINTINDEXTRIPLETDATA__H__
#define __BULLET_BTSHORTINTINDEXTRIPLETDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
namespace Bullet {
// ---------------------------------------------- //
class btShortIntIndexTripletData
{
public:
short m_values[3];
char m_pad[2];
};
}
#endif//__BULLET_BTSHORTINTINDEXTRIPLETDATA__H__

View File

@ -1,49 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTSLIDERCONSTRAINTDATA__H__
#define __BULLET_BTSLIDERCONSTRAINTDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btTransformFloatData.h"
#include "bullet_btTypedConstraintData.h"
namespace Bullet {
// ---------------------------------------------- //
class btSliderConstraintData
{
public:
btTypedConstraintData m_typeConstraintData;
btTransformFloatData m_rbAFrame;
btTransformFloatData m_rbBFrame;
float m_linearUpperLimit;
float m_linearLowerLimit;
float m_angularUpperLimit;
float m_angularLowerLimit;
int m_useLinearReferenceFrameA;
int m_useOffsetForConstraintFrame;
};
}
#endif//__BULLET_BTSLIDERCONSTRAINTDATA__H__

View File

@ -1,45 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTSTATICPLANESHAPEDATA__H__
#define __BULLET_BTSTATICPLANESHAPEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btCollisionShapeData.h"
#include "bullet_btVector3FloatData.h"
namespace Bullet {
// ---------------------------------------------- //
class btStaticPlaneShapeData
{
public:
btCollisionShapeData m_collisionShapeData;
btVector3FloatData m_localScaling;
btVector3FloatData m_planeNormal;
float m_planeConstant;
char m_pad[4];
};
}
#endif//__BULLET_BTSTATICPLANESHAPEDATA__H__

View File

@ -1,43 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTSTRIDINGMESHINTERFACEDATA__H__
#define __BULLET_BTSTRIDINGMESHINTERFACEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btVector3FloatData.h"
namespace Bullet {
// ---------------------------------------------- //
class btStridingMeshInterfaceData
{
public:
btMeshPartData *m_meshPartsPtr;
btVector3FloatData m_scaling;
int m_numMeshParts;
char m_padding[4];
};
}
#endif//__BULLET_BTSTRIDINGMESHINTERFACEDATA__H__

View File

@ -1,42 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTTRANSFORMDOUBLEDATA__H__
#define __BULLET_BTTRANSFORMDOUBLEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btMatrix3x3DoubleData.h"
#include "bullet_btVector3DoubleData.h"
namespace Bullet {
// ---------------------------------------------- //
class btTransformDoubleData
{
public:
btMatrix3x3DoubleData m_basis;
btVector3DoubleData m_origin;
};
}
#endif//__BULLET_BTTRANSFORMDOUBLEDATA__H__

View File

@ -1,42 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTTRANSFORMFLOATDATA__H__
#define __BULLET_BTTRANSFORMFLOATDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btMatrix3x3FloatData.h"
#include "bullet_btVector3FloatData.h"
namespace Bullet {
// ---------------------------------------------- //
class btTransformFloatData
{
public:
btMatrix3x3FloatData m_basis;
btVector3FloatData m_origin;
};
}
#endif//__BULLET_BTTRANSFORMFLOATDATA__H__

View File

@ -1,42 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTTRIANGLEINFODATA__H__
#define __BULLET_BTTRIANGLEINFODATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
namespace Bullet {
// ---------------------------------------------- //
class btTriangleInfoData
{
public:
int m_flags;
float m_edgeV0V1Angle;
float m_edgeV1V2Angle;
float m_edgeV2V0Angle;
};
}
#endif//__BULLET_BTTRIANGLEINFODATA__H__

View File

@ -1,52 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTTRIANGLEINFOMAPDATA__H__
#define __BULLET_BTTRIANGLEINFOMAPDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
namespace Bullet {
// ---------------------------------------------- //
class btTriangleInfoMapData
{
public:
int *m_hashTablePtr;
int *m_nextPtr;
btTriangleInfoData *m_valueArrayPtr;
int *m_keyArrayPtr;
float m_convexEpsilon;
float m_planarEpsilon;
float m_equalVertexThreshold;
float m_edgeDistanceThreshold;
float m_zeroAreaThreshold;
int m_nextSize;
int m_hashTableSize;
int m_numValues;
int m_numKeys;
char m_padding[4];
};
}
#endif//__BULLET_BTTRIANGLEINFOMAPDATA__H__

View File

@ -1,47 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTTRIANGLEMESHSHAPEDATA__H__
#define __BULLET_BTTRIANGLEMESHSHAPEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
#include "bullet_btCollisionShapeData.h"
#include "bullet_btStridingMeshInterfaceData.h"
namespace Bullet {
// ---------------------------------------------- //
class btTriangleMeshShapeData
{
public:
btCollisionShapeData m_collisionShapeData;
btStridingMeshInterfaceData m_meshInterface;
btQuantizedBvhFloatData *m_quantizedFloatBvh;
btQuantizedBvhDoubleData *m_quantizedDoubleBvh;
btTriangleInfoMapData *m_triangleInfoMap;
float m_collisionMargin;
char m_pad3[4];
};
}
#endif//__BULLET_BTTRIANGLEMESHSHAPEDATA__H__

View File

@ -1,49 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTTYPEDCONSTRAINTDATA__H__
#define __BULLET_BTTYPEDCONSTRAINTDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
namespace Bullet {
// ---------------------------------------------- //
class btTypedConstraintData
{
public:
bInvalidHandle *m_rbA;
bInvalidHandle *m_rbB;
char *m_name;
int m_objectType;
int m_userConstraintType;
int m_userConstraintId;
int m_needsFeedback;
float m_appliedImpulse;
float m_dbgDrawSize;
int m_disableCollisionsBetweenLinkedBodies;
char m_pad4[4];
};
}
#endif//__BULLET_BTTYPEDCONSTRAINTDATA__H__

View File

@ -1,39 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTVECTOR3DOUBLEDATA__H__
#define __BULLET_BTVECTOR3DOUBLEDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
namespace Bullet {
// ---------------------------------------------- //
class btVector3DoubleData
{
public:
double m_floats[4];
};
}
#endif//__BULLET_BTVECTOR3DOUBLEDATA__H__

View File

@ -1,39 +0,0 @@
/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
* arising from the use of this software.
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software. If you use this software
* in a product, an acknowledgment in the product documentation would be
* appreciated but is not required.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
#ifndef __BULLET_BTVECTOR3FLOATDATA__H__
#define __BULLET_BTVECTOR3FLOATDATA__H__
// -------------------------------------------------- //
#include "bullet_Common.h"
namespace Bullet {
// ---------------------------------------------- //
class btVector3FloatData
{
public:
float m_floats[4];
};
}
#endif//__BULLET_BTVECTOR3FLOATDATA__H__

View File

@ -1,7 +1,7 @@
import dump
header = """/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
header = """/* Copyright (C) 2011 Erwin Coumans & Charlie C
*
* This software is provided 'as-is', without any express or implied
* warranty. In no event will the authors be held liable for any damages
@ -19,7 +19,7 @@ header = """/* Copyright (C) 2006-2009 Erwin Coumans & Charlie C
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
*/
// Auto generated from makesdna dna.c
// Auto generated from Bullet/Extras/HeaderGenerator/bulletGenerate.py
"""
dtList = dump.DataTypeList
@ -40,17 +40,13 @@ blender = open(out+"bullet.h", 'w')
blender.write(header)
blender.write("#ifndef __BULLET_H__\n")
blender.write("#define __BULLET_H__\n")
for dt in dtList:
blender.write("#include \"%s.h\"\n"%dt.filename)
#for dt in dtList:
# blender.write("struct %s;\n"%dt.filename)
blender.write("#endif//__BULLET_H__")
blender.close()
###################################################################################
blenderC = open(out+"bullet_Common.h", 'w')
blenderC.write(header)
blenderC.write("#ifndef __BULLETCOMMON_H__\n")
blenderC.write("#define __BULLETCOMMON_H__\n")
blender.write("namespace Bullet {\n")
strUnRes = """
// put an empty struct in the case
@ -59,53 +55,29 @@ typedef struct bInvalidHandle {
}bInvalidHandle;
"""
blenderC.write(strUnRes)
blender.write(strUnRes)
blenderC.write("namespace Bullet {\n")
for dt in dtList:
write(blenderC, 4, "class %s;\n"%dt.name)
blenderC.write("}\n")
blenderC.write("#endif//__BULLETCOMMON_H__")
blenderC.close()
write(blender, 4, "class %s;\n"%dt.name)
for dt in dtList:
fp = open(out+dt.filename+".h", 'w')
fp.write(header)
strUpper = dt.filename.upper()
fp.write("#ifndef __%s__H__\n"%strUpper)
fp.write("#define __%s__H__\n"%strUpper)
fp.write("\n\n")
blender.write("// -------------------------------------------------- //\n")
write(blender, 4, "class %s\n"%dt.name)
fp.write("// -------------------------------------------------- //\n")
fp.write("#include \"bullet_Common.h\"\n")
for i in dt.includes:
fp.write("#include \"%s\"\n"%i)
fp.write("\nnamespace Bullet {\n")
fp.write("\n\n")
addSpaces(fp,4)
fp.write("// ---------------------------------------------- //\n")
write(fp, 4, "class %s\n"%dt.name)
write(fp, 4, "{\n")
write(fp, 4, "public:\n")
write(blender, 4, "{\n")
write(blender, 4, "public:\n")
for i in dt.dataTypes:
write(fp, 8, i+";\n")
write(blender, 8, i+";\n")
write(blender, 4, "};\n")
write(fp, 4, "};\n")
fp.write("}\n")
fp.write("\n\n")
fp.write("#endif//__%s__H__\n"%strUpper)
fp.close()
blender.write("\n\n")
blender.write("}\n")
blender.write("#endif//__BULLET_H__")
blender.close()

View File

@ -0,0 +1,345 @@
#include "BulletDataExtractor.h"
#include "../BulletFileLoader/btBulletFile.h"
#include <stdio.h>
///work-in-progress
///This ReadBulletSample is kept as simple as possible without dependencies to the Bullet SDK.
///It can be used to load .bullet data for other physics SDKs
///For a more complete example how to load and convert Bullet data using the Bullet SDK check out
///the Bullet/Demos/SerializeDemo and Bullet/Serialize/BulletWorldImporter
using namespace Bullet;
enum LocalBroadphaseNativeTypes
{
// polyhedral convex shapes
BOX_SHAPE_PROXYTYPE,
TRIANGLE_SHAPE_PROXYTYPE,
TETRAHEDRAL_SHAPE_PROXYTYPE,
CONVEX_TRIANGLEMESH_SHAPE_PROXYTYPE,
CONVEX_HULL_SHAPE_PROXYTYPE,
CONVEX_POINT_CLOUD_SHAPE_PROXYTYPE,
CUSTOM_POLYHEDRAL_SHAPE_TYPE,
//implicit convex shapes
IMPLICIT_CONVEX_SHAPES_START_HERE,
SPHERE_SHAPE_PROXYTYPE,
MULTI_SPHERE_SHAPE_PROXYTYPE,
CAPSULE_SHAPE_PROXYTYPE,
CONE_SHAPE_PROXYTYPE,
CONVEX_SHAPE_PROXYTYPE,
CYLINDER_SHAPE_PROXYTYPE,
UNIFORM_SCALING_SHAPE_PROXYTYPE,
MINKOWSKI_SUM_SHAPE_PROXYTYPE,
MINKOWSKI_DIFFERENCE_SHAPE_PROXYTYPE,
BOX_2D_SHAPE_PROXYTYPE,
CONVEX_2D_SHAPE_PROXYTYPE,
CUSTOM_CONVEX_SHAPE_TYPE,
//concave shapes
CONCAVE_SHAPES_START_HERE,
//keep all the convex shapetype below here, for the check IsConvexShape in broadphase proxy!
TRIANGLE_MESH_SHAPE_PROXYTYPE,
SCALED_TRIANGLE_MESH_SHAPE_PROXYTYPE,
///used for demo integration FAST/Swift collision library and Bullet
FAST_CONCAVE_MESH_PROXYTYPE,
//terrain
TERRAIN_SHAPE_PROXYTYPE,
///Used for GIMPACT Trimesh integration
GIMPACT_SHAPE_PROXYTYPE,
///Multimaterial mesh
MULTIMATERIAL_TRIANGLE_MESH_PROXYTYPE,
EMPTY_SHAPE_PROXYTYPE,
STATIC_PLANE_PROXYTYPE,
CUSTOM_CONCAVE_SHAPE_TYPE,
CONCAVE_SHAPES_END_HERE,
COMPOUND_SHAPE_PROXYTYPE,
SOFTBODY_SHAPE_PROXYTYPE,
HFFLUID_SHAPE_PROXYTYPE,
HFFLUID_BUOYANT_CONVEX_SHAPE_PROXYTYPE,
INVALID_SHAPE_PROXYTYPE,
MAX_BROADPHASE_COLLISION_TYPES
};
btBulletDataExtractor::btBulletDataExtractor()
{
}
btBulletDataExtractor::~btBulletDataExtractor()
{
}
void btBulletDataExtractor::convertAllObjects(bParse::btBulletFile* bulletFile2)
{
int i;
for (i=0;i<bulletFile2->m_collisionShapes.size();i++)
{
btCollisionShapeData* shapeData = (btCollisionShapeData*)bulletFile2->m_collisionShapes[i];
if (shapeData->m_name)
printf("converting shape %s\n", shapeData->m_name);
void* shape = convertCollisionShape(shapeData);
}
}
void* btBulletDataExtractor::convertCollisionShape( btCollisionShapeData* shapeData )
{
void* shape = 0;
switch (shapeData->m_shapeType)
{
case STATIC_PLANE_PROXYTYPE:
{
btStaticPlaneShapeData* planeData = (btStaticPlaneShapeData*)shapeData;
void* shape = createPlaneShape(planeData->m_planeNormal,planeData->m_planeConstant, planeData->m_localScaling);
break;
}
case CYLINDER_SHAPE_PROXYTYPE:
case CAPSULE_SHAPE_PROXYTYPE:
case BOX_SHAPE_PROXYTYPE:
case SPHERE_SHAPE_PROXYTYPE:
case MULTI_SPHERE_SHAPE_PROXYTYPE:
case CONVEX_HULL_SHAPE_PROXYTYPE:
{
btConvexInternalShapeData* bsd = (btConvexInternalShapeData*)shapeData;
switch (shapeData->m_shapeType)
{
case BOX_SHAPE_PROXYTYPE:
{
shape = createBoxShape(bsd->m_implicitShapeDimensions, bsd->m_localScaling,bsd->m_collisionMargin);
break;
}
case SPHERE_SHAPE_PROXYTYPE:
{
shape = createSphereShape(bsd->m_implicitShapeDimensions.m_floats[0],bsd->m_localScaling, bsd->m_collisionMargin);
break;
}
#if 0
case CAPSULE_SHAPE_PROXYTYPE:
{
btCapsuleShapeData* capData = (btCapsuleShapeData*)shapeData;
switch (capData->m_upAxis)
{
case 0:
{
shape = createCapsuleShapeX(implicitShapeDimensions.getY(),2*implicitShapeDimensions.getX());
break;
}
case 1:
{
shape = createCapsuleShapeY(implicitShapeDimensions.getX(),2*implicitShapeDimensions.getY());
break;
}
case 2:
{
shape = createCapsuleShapeZ(implicitShapeDimensions.getX(),2*implicitShapeDimensions.getZ());
break;
}
default:
{
printf("error: wrong up axis for btCapsuleShape\n");
}
};
break;
}
case CYLINDER_SHAPE_PROXYTYPE:
{
btCylinderShapeData* cylData = (btCylinderShapeData*) shapeData;
btVector3 halfExtents = implicitShapeDimensions+margin;
switch (cylData->m_upAxis)
{
case 0:
{
shape = createCylinderShapeX(halfExtents.getY(),halfExtents.getX());
break;
}
case 1:
{
shape = createCylinderShapeY(halfExtents.getX(),halfExtents.getY());
break;
}
case 2:
{
shape = createCylinderShapeZ(halfExtents.getX(),halfExtents.getZ());
break;
}
default:
{
printf("unknown Cylinder up axis\n");
}
};
break;
}
case MULTI_SPHERE_SHAPE_PROXYTYPE:
{
btMultiSphereShapeData* mss = (btMultiSphereShapeData*)bsd;
int numSpheres = mss->m_localPositionArraySize;
int i;
for ( i=0;i<numSpheres;i++)
{
tmpPos[i].deSerializeFloat(mss->m_localPositionArrayPtr[i].m_pos);
radii[i] = mss->m_localPositionArrayPtr[i].m_radius;
}
shape = new btMultiSphereShape(&tmpPos[0],&radii[0],numSpheres);
break;
}
case CONVEX_HULL_SHAPE_PROXYTYPE:
{
btConvexHullShapeData* convexData = (btConvexHullShapeData*)bsd;
int numPoints = convexData->m_numUnscaledPoints;
btAlignedObjectArray<btVector3> tmpPoints;
tmpPoints.resize(numPoints);
int i;
for ( i=0;i<numPoints;i++)
{
if (convexData->m_unscaledPointsFloatPtr)
tmpPoints[i].deSerialize(convexData->m_unscaledPointsFloatPtr[i]);
if (convexData->m_unscaledPointsDoublePtr)
tmpPoints[i].deSerializeDouble(convexData->m_unscaledPointsDoublePtr[i]);
}
shape = createConvexHullShape();
return shape;
break;
}
#endif
default:
{
printf("error: cannot create shape type (%d)\n",shapeData->m_shapeType);
}
}
break;
}
#if 0
case TRIANGLE_MESH_SHAPE_PROXYTYPE:
{
btTriangleMeshShapeData* trimesh = (btTriangleMeshShapeData*)shapeData;
btTriangleIndexVertexArray* meshInterface = createMeshInterface(trimesh->m_meshInterface);
if (!meshInterface->getNumSubParts())
{
return 0;
}
btVector3 scaling; scaling.deSerializeFloat(trimesh->m_meshInterface.m_scaling);
meshInterface->setScaling(scaling);
btOptimizedBvh* bvh = 0;
btBvhTriangleMeshShape* trimeshShape = createBvhTriangleMeshShape(meshInterface,bvh);
trimeshShape->setMargin(trimesh->m_collisionMargin);
shape = trimeshShape;
if (trimesh->m_triangleInfoMap)
{
btTriangleInfoMap* map = createTriangleInfoMap();
map->deSerialize(*trimesh->m_triangleInfoMap);
trimeshShape->setTriangleInfoMap(map);
#ifdef USE_INTERNAL_EDGE_UTILITY
gContactAddedCallback = btAdjustInternalEdgeContactsCallback;
#endif //USE_INTERNAL_EDGE_UTILITY
}
//printf("trimesh->m_collisionMargin=%f\n",trimesh->m_collisionMargin);
break;
}
case COMPOUND_SHAPE_PROXYTYPE:
{
btCompoundShapeData* compoundData = (btCompoundShapeData*)shapeData;
btCompoundShape* compoundShape = createCompoundShape();
btAlignedObjectArray<btCollisionShape*> childShapes;
for (int i=0;i<compoundData->m_numChildShapes;i++)
{
btCollisionShape* childShape = convertCollisionShape(compoundData->m_childShapePtr[i].m_childShape);
if (childShape)
{
btTransform localTransform;
localTransform.deSerializeFloat(compoundData->m_childShapePtr[i].m_transform);
compoundShape->addChildShape(localTransform,childShape);
} else
{
printf("error: couldn't create childShape for compoundShape\n");
}
}
shape = compoundShape;
break;
}
case GIMPACT_SHAPE_PROXYTYPE:
{
btGImpactMeshShapeData* gimpactData = (btGImpactMeshShapeData*) shapeData;
if (gimpactData->m_gimpactSubType == CONST_GIMPACT_TRIMESH_SHAPE)
{
btTriangleIndexVertexArray* meshInterface = createMeshInterface(gimpactData->m_meshInterface);
btGImpactMeshShape* gimpactShape = createGimpactShape(meshInterface);
btVector3 localScaling;
localScaling.deSerializeFloat(gimpactData->m_localScaling);
gimpactShape->setLocalScaling(localScaling);
gimpactShape->setMargin(btScalar(gimpactData->m_collisionMargin));
gimpactShape->updateBound();
shape = gimpactShape;
} else
{
printf("unsupported gimpact sub type\n");
}
break;
}
case SOFTBODY_SHAPE_PROXYTYPE:
{
return 0;
}
#endif
default:
{
printf("unsupported shape type (%d)\n",shapeData->m_shapeType);
}
}
return shape;
}
void* btBulletDataExtractor::createBoxShape( const Bullet::btVector3FloatData& halfDimensions, const Bullet::btVector3FloatData& localScaling, float collisionMargin)
{
printf("createBoxShape with halfDimensions %f,%f,%f\n",halfDimensions.m_floats[0], halfDimensions.m_floats[1],halfDimensions.m_floats[2]);
return 0;
}
void* btBulletDataExtractor::createSphereShape( float radius, const Bullet::btVector3FloatData& localScaling, float collisionMargin)
{
printf("createSphereShape with radius %f\n",radius);
return 0;
}
void* btBulletDataExtractor::createPlaneShape( const btVector3FloatData& planeNormal, float planeConstant, const Bullet::btVector3FloatData& localScaling)
{
printf("createPlaneShape with normal %f,%f,%f and planeConstant\n",planeNormal.m_floats[0], planeNormal.m_floats[1],planeNormal.m_floats[2],planeConstant);
return 0;
}

View File

@ -0,0 +1,32 @@
#ifndef BULLET_DATA_EXTRACTOR_H
#define BULLET_DATA_EXTRACTOR_H
#include "../BulletFileLoader/autogenerated/bullet.h"
namespace bParse
{
class btBulletFile;
};
class btBulletDataExtractor
{
public:
btBulletDataExtractor();
virtual ~btBulletDataExtractor();
virtual void convertAllObjects(bParse::btBulletFile* bulletFile);
virtual void* convertCollisionShape( Bullet::btCollisionShapeData* shapeData );
virtual void* createPlaneShape( const Bullet::btVector3FloatData& planeNormal, float planeConstant, const Bullet::btVector3FloatData& localScaling);
virtual void* createBoxShape( const Bullet::btVector3FloatData& halfDimensions, const Bullet::btVector3FloatData& localScaling, float collisionMargin);
virtual void* createSphereShape( float radius, const Bullet::btVector3FloatData& localScaling, float collisionMargin);
};
#endif //BULLET_DATA_EXTRACTOR_H

View File

@ -0,0 +1,33 @@
INCLUDE_DIRECTORIES(
${BULLET_PHYSICS_SOURCE_DIR}/src
)
LINK_LIBRARIES(
BulletFileLoader
)
IF (WIN32)
SET(ADDITIONAL_SRC
${BULLET_PHYSICS_SOURCE_DIR}/msvc/bullet.rc
)
ENDIF()
SET(READBULLET_SRC
main.cpp
BulletDataExtractor.cpp
BulletDataExtractor.h
${BULLET_PHYSICS_SOURCE_DIR}/src/LinearMath/btSerializer.cpp
${BULLET_PHYSICS_SOURCE_DIR}/src/LinearMath/btAlignedAllocator.cpp
)
ADD_EXECUTABLE(AppReadBulletSample
${READBULLET_SRC}
${ADDITIONAL_SRC}
)
IF (INTERNAL_ADD_POSTFIX_EXECUTABLE_NAMES)
SET_TARGET_PROPERTIES(AppReadBulletSample PROPERTIES DEBUG_POSTFIX "_Debug")
SET_TARGET_PROPERTIES(AppReadBulletSample PROPERTIES MINSIZEREL_POSTFIX "_MinsizeRel")
SET_TARGET_PROPERTIES(AppReadBulletSample PROPERTIES RELWITHDEBINFO_POSTFIX "_RelWithDebugInfo")
ENDIF(INTERNAL_ADD_POSTFIX_EXECUTABLE_NAMES)

View File

@ -0,0 +1,63 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2011 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#include <stdio.h>
#include "../BulletFileLoader/btBulletFile.h"
#include "BulletDataExtractor.h"
///This ReadBulletSample is kept as simple as possible without dependencies to the Bullet SDK.
///It can be used to load .bullet data for other physics SDKs
///For a more complete example how to load and convert Bullet data using the Bullet SDK check out
///the Bullet/Demos/SerializeDemo and Bullet/Serialize/BulletWorldImporter
int main(int argc, char** argv)
{
const char* fileName="testFile.bullet";
bool verboseDumpAllTypes = false;
bParse::btBulletFile* bulletFile2 = new bParse::btBulletFile(fileName);
bool ok = (bulletFile2->getFlags()& bParse::FD_OK)!=0;
if (ok)
bulletFile2->parse(verboseDumpAllTypes);
else
{
printf("Error loading file %s.\n",fileName);
exit(0);
}
ok = (bulletFile2->getFlags()& bParse::FD_OK)!=0;
if (!ok)
{
printf("Error parsing file %s.\n",fileName);
exit(0);
}
if (verboseDumpAllTypes)
{
bulletFile2->dumpChunks(bulletFile2->getFileDNA());
}
btBulletDataExtractor extractor;
extractor.convertAllObjects(bulletFile2);
delete bulletFile2;
return 0;
}