123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746 |
- using System;
- using System.Collections.Generic;
- using System.Runtime.InteropServices;
- using System.Security;
- using System.Text;
- using OpenMetaverse;
- namespace OpenSim.Region.Physics.BulletSPlugin {
-
- public enum ConstraintType : int
- {
- POINT2POINT_CONSTRAINT_TYPE = 3,
- HINGE_CONSTRAINT_TYPE,
- CONETWIST_CONSTRAINT_TYPE,
- D6_CONSTRAINT_TYPE,
- SLIDER_CONSTRAINT_TYPE,
- CONTACT_CONSTRAINT_TYPE,
- D6_SPRING_CONSTRAINT_TYPE,
- MAX_CONSTRAINT_TYPE,
-
- FIXED_CONSTRAINT_TYPE = 1234
- }
- [StructLayout(LayoutKind.Sequential)]
- public struct ConvexHull
- {
- Vector3 Offset;
- int VertexCount;
- Vector3[] Vertices;
- }
- public enum BSPhysicsShapeType
- {
- SHAPE_UNKNOWN = 0,
- SHAPE_CAPSULE = 1,
- SHAPE_BOX = 2,
- SHAPE_CONE = 3,
- SHAPE_CYLINDER = 4,
- SHAPE_SPHERE = 5,
- SHAPE_MESH = 6,
- SHAPE_HULL = 7,
-
- SHAPE_GROUNDPLANE = 20,
- SHAPE_TERRAIN = 21,
- SHAPE_COMPOUND = 22,
- SHAPE_HEIGHTMAP = 23,
- SHAPE_AVATAR = 24,
- SHAPE_CONVEXHULL= 25,
- SHAPE_GIMPACT = 26,
- };
- public enum FixedShapeKey : ulong
- {
- KEY_NONE = 0,
- KEY_BOX = 1,
- KEY_SPHERE = 2,
- KEY_CONE = 3,
- KEY_CYLINDER = 4,
- KEY_CAPSULE = 5,
- KEY_AVATAR = 6,
- }
- [StructLayout(LayoutKind.Sequential)]
- public struct ShapeData
- {
- public UInt32 ID;
- public BSPhysicsShapeType Type;
- public Vector3 Position;
- public Quaternion Rotation;
- public Vector3 Velocity;
- public Vector3 Scale;
- public float Mass;
- public float Buoyancy;
- public System.UInt64 HullKey;
- public System.UInt64 MeshKey;
- public float Friction;
- public float Restitution;
- public float Collidable;
- public float Static;
- public float Solid;
- public Vector3 Size;
-
- public const float numericTrue = 1f;
- public const float numericFalse = 0f;
- }
- [StructLayout(LayoutKind.Sequential)]
- public struct SweepHit
- {
- public UInt32 ID;
- public float Fraction;
- public Vector3 Normal;
- public Vector3 Point;
- }
- [StructLayout(LayoutKind.Sequential)]
- public struct RaycastHit
- {
- public UInt32 ID;
- public float Fraction;
- public Vector3 Normal;
- }
- [StructLayout(LayoutKind.Sequential)]
- public struct CollisionDesc
- {
- public UInt32 aID;
- public UInt32 bID;
- public Vector3 point;
- public Vector3 normal;
- public float penetration;
- }
- [StructLayout(LayoutKind.Sequential)]
- public struct EntityProperties
- {
- public UInt32 ID;
- public Vector3 Position;
- public Quaternion Rotation;
- public Vector3 Velocity;
- public Vector3 Acceleration;
- public Vector3 RotationalVelocity;
- public override string ToString()
- {
- StringBuilder buff = new StringBuilder();
- buff.Append("<i=");
- buff.Append(ID.ToString());
- buff.Append(",p=");
- buff.Append(Position.ToString());
- buff.Append(",r=");
- buff.Append(Rotation.ToString());
- buff.Append(",v=");
- buff.Append(Velocity.ToString());
- buff.Append(",a=");
- buff.Append(Acceleration.ToString());
- buff.Append(",rv=");
- buff.Append(RotationalVelocity.ToString());
- buff.Append(">");
- return buff.ToString();
- }
- }
- [StructLayout(LayoutKind.Sequential)]
- public struct ConfigurationParameters
- {
- public float defaultFriction;
- public float defaultDensity;
- public float defaultRestitution;
- public float collisionMargin;
- public float gravity;
- public float maxPersistantManifoldPoolSize;
- public float maxCollisionAlgorithmPoolSize;
- public float shouldDisableContactPoolDynamicAllocation;
- public float shouldForceUpdateAllAabbs;
- public float shouldRandomizeSolverOrder;
- public float shouldSplitSimulationIslands;
- public float shouldEnableFrictionCaching;
- public float numberOfSolverIterations;
- public float useSingleSidedMeshes;
- public float globalContactBreakingThreshold;
- public float physicsLoggingFrames;
- public const float numericTrue = 1f;
- public const float numericFalse = 0f;
- }
- [StructLayout(LayoutKind.Sequential)]
- public struct HACDParams
- {
-
- public float maxVerticesPerHull;
- public float minClusters;
- public float compacityWeight;
- public float volumeWeight;
- public float concavity;
- public float addExtraDistPoints;
- public float addNeighboursDistPoints;
- public float addFacesPoints;
- public float shouldAdjustCollisionMargin;
- }
- public enum ActivationState : uint
- {
- ACTIVE_TAG = 1,
- ISLAND_SLEEPING,
- WANTS_DEACTIVATION,
- DISABLE_DEACTIVATION,
- DISABLE_SIMULATION,
- }
- public enum CollisionObjectTypes : int
- {
- CO_COLLISION_OBJECT = 1 << 0,
- CO_RIGID_BODY = 1 << 1,
- CO_GHOST_OBJECT = 1 << 2,
- CO_SOFT_BODY = 1 << 3,
- CO_HF_FLUID = 1 << 4,
- CO_USER_TYPE = 1 << 5,
- }
- public enum CollisionFlags : uint
- {
- CF_STATIC_OBJECT = 1 << 0,
- CF_KINEMATIC_OBJECT = 1 << 1,
- CF_NO_CONTACT_RESPONSE = 1 << 2,
- CF_CUSTOM_MATERIAL_CALLBACK = 1 << 3,
- CF_CHARACTER_OBJECT = 1 << 4,
- CF_DISABLE_VISUALIZE_OBJECT = 1 << 5,
- CF_DISABLE_SPU_COLLISION_PROCESS = 1 << 6,
-
- BS_SUBSCRIBE_COLLISION_EVENTS = 1 << 10,
- BS_FLOATS_ON_WATER = 1 << 11,
- BS_VEHICLE_COLLISIONS = 1 << 12,
- BS_RETURN_ROOT_COMPOUND_SHAPE = 1 << 13,
- BS_NONE = 0,
- BS_ALL = 0x7FFF
- };
- public enum CollisionFilterGroups : uint
- {
-
-
-
- BNoneGroup = 0,
- BDefaultGroup = 1 << 0,
- BStaticGroup = 1 << 1,
- BKinematicGroup = 1 << 2,
- BDebrisGroup = 1 << 3,
- BSensorTrigger = 1 << 4,
- BCharacterGroup = 1 << 5,
- BAllGroup = 0x0007FFF,
-
- BGroundPlaneGroup = 1 << 8,
- BTerrainGroup = 1 << 9,
- BRaycastGroup = 1 << 10,
- BSolidGroup = 1 << 11,
-
- BLinksetChildGroup = 1 << 12,
- };
- public enum ConstraintParams : int
- {
- BT_CONSTRAINT_ERP = 1,
- BT_CONSTRAINT_STOP_ERP,
- BT_CONSTRAINT_CFM,
- BT_CONSTRAINT_STOP_CFM,
- };
- public enum ConstraintParamAxis : int
- {
- AXIS_LINEAR_X = 0,
- AXIS_LINEAR_Y,
- AXIS_LINEAR_Z,
- AXIS_ANGULAR_X,
- AXIS_ANGULAR_Y,
- AXIS_ANGULAR_Z,
- AXIS_LINEAR_ALL = 20,
- AXIS_ANGULAR_ALL,
- AXIS_ALL
- };
- public abstract class BSAPITemplate
- {
- public abstract string BulletEngineName { get; }
- public abstract string BulletEngineVersion { get; protected set;}
- public abstract BulletWorld Initialize(Vector3 maxPosition, ConfigurationParameters parms,
- int maxCollisions, ref CollisionDesc[] collisionArray,
- int maxUpdates, ref EntityProperties[] updateArray
- );
- public abstract int PhysicsStep(BulletWorld world, float timeStep, int maxSubSteps, float fixedTimeStep,
- out int updatedEntityCount, out int collidersCount);
- public abstract bool UpdateParameter(BulletWorld world, UInt32 localID, String parm, float value);
- public abstract void Shutdown(BulletWorld sim);
- public abstract bool PushUpdate(BulletBody obj);
- public abstract BulletShape CreateMeshShape(BulletWorld world,
- int indicesCount, int[] indices,
- int verticesCount, float[] vertices );
- public abstract BulletShape CreateGImpactShape(BulletWorld world,
- int indicesCount, int[] indices,
- int verticesCount, float[] vertices );
- public abstract BulletShape CreateHullShape(BulletWorld world,
- int hullCount, float[] hulls);
- public abstract BulletShape BuildHullShapeFromMesh(BulletWorld world, BulletShape meshShape, HACDParams parms);
- public abstract BulletShape BuildConvexHullShapeFromMesh(BulletWorld world, BulletShape meshShape);
- public abstract BulletShape CreateConvexHullShape(BulletWorld world,
- int indicesCount, int[] indices,
- int verticesCount, float[] vertices );
- public abstract BulletShape BuildNativeShape(BulletWorld world, ShapeData shapeData);
- public abstract bool IsNativeShape(BulletShape shape);
- public abstract void SetShapeCollisionMargin(BulletShape shape, float margin);
- public abstract BulletShape BuildCapsuleShape(BulletWorld world, float radius, float height, Vector3 scale);
- public abstract BulletShape CreateCompoundShape(BulletWorld sim, bool enableDynamicAabbTree);
- public abstract int GetNumberOfCompoundChildren(BulletShape cShape);
- public abstract void AddChildShapeToCompoundShape(BulletShape cShape, BulletShape addShape, Vector3 pos, Quaternion rot);
- public abstract BulletShape GetChildShapeFromCompoundShapeIndex(BulletShape cShape, int indx);
- public abstract BulletShape RemoveChildShapeFromCompoundShapeIndex(BulletShape cShape, int indx);
- public abstract void RemoveChildShapeFromCompoundShape(BulletShape cShape, BulletShape removeShape);
- public abstract void UpdateChildTransform(BulletShape pShape, int childIndex, Vector3 pos, Quaternion rot, bool shouldRecalculateLocalAabb);
- public abstract void RecalculateCompoundShapeLocalAabb(BulletShape cShape);
- public abstract BulletShape DuplicateCollisionShape(BulletWorld sim, BulletShape srcShape, UInt32 id);
- public abstract bool DeleteCollisionShape(BulletWorld world, BulletShape shape);
- public abstract CollisionObjectTypes GetBodyType(BulletBody obj);
- public abstract BulletBody CreateBodyFromShape(BulletWorld sim, BulletShape shape, UInt32 id, Vector3 pos, Quaternion rot);
- public abstract BulletBody CreateBodyWithDefaultMotionState(BulletShape shape, UInt32 id, Vector3 pos, Quaternion rot);
- public abstract BulletBody CreateGhostFromShape(BulletWorld sim, BulletShape shape, UInt32 id, Vector3 pos, Quaternion rot);
- public abstract void DestroyObject(BulletWorld sim, BulletBody obj);
- public abstract BulletShape CreateGroundPlaneShape(UInt32 id, float height, float collisionMargin);
- public abstract BulletShape CreateTerrainShape(UInt32 id, Vector3 size, float minHeight, float maxHeight, float[] heightMap,
- float scaleFactor, float collisionMargin);
- public abstract BulletConstraint Create6DofConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
- Vector3 frame1loc, Quaternion frame1rot,
- Vector3 frame2loc, Quaternion frame2rot,
- bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
- public abstract BulletConstraint Create6DofConstraintToPoint(BulletWorld world, BulletBody obj1, BulletBody obj2,
- Vector3 joinPoint,
- bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
- public abstract BulletConstraint Create6DofConstraintFixed(BulletWorld world, BulletBody obj1,
- Vector3 frameInBloc, Quaternion frameInBrot,
- bool useLinearReferenceFrameB, bool disableCollisionsBetweenLinkedBodies);
- public abstract BulletConstraint Create6DofSpringConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
- Vector3 frame1loc, Quaternion frame1rot,
- Vector3 frame2loc, Quaternion frame2rot,
- bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
- public abstract BulletConstraint CreateHingeConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
- Vector3 pivotinA, Vector3 pivotinB,
- Vector3 axisInA, Vector3 axisInB,
- bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
- public abstract BulletConstraint CreateSliderConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
- Vector3 frameInAloc, Quaternion frameInArot,
- Vector3 frameInBloc, Quaternion frameInBrot,
- bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
- public abstract BulletConstraint CreateConeTwistConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
- Vector3 frameInAloc, Quaternion frameInArot,
- Vector3 frameInBloc, Quaternion frameInBrot,
- bool disableCollisionsBetweenLinkedBodies);
- public abstract BulletConstraint CreateGearConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
- Vector3 axisInA, Vector3 axisInB,
- float ratio, bool disableCollisionsBetweenLinkedBodies);
- public abstract BulletConstraint CreatePoint2PointConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
- Vector3 pivotInA, Vector3 pivotInB,
- bool disableCollisionsBetweenLinkedBodies);
- public abstract void SetConstraintEnable(BulletConstraint constrain, float numericTrueFalse);
- public abstract void SetConstraintNumSolverIterations(BulletConstraint constrain, float iterations);
- public abstract bool SetFrames(BulletConstraint constrain,
- Vector3 frameA, Quaternion frameArot, Vector3 frameB, Quaternion frameBrot);
- public abstract bool SetLinearLimits(BulletConstraint constrain, Vector3 low, Vector3 hi);
- public abstract bool SetAngularLimits(BulletConstraint constrain, Vector3 low, Vector3 hi);
- public abstract bool UseFrameOffset(BulletConstraint constrain, float enable);
- public abstract bool TranslationalLimitMotor(BulletConstraint constrain, float enable, float targetVel, float maxMotorForce);
- public abstract bool SetBreakingImpulseThreshold(BulletConstraint constrain, float threshold);
- public const int HINGE_NOT_SPECIFIED = -1;
- public abstract bool HingeSetLimits(BulletConstraint constrain, float low, float high, float softness, float bias, float relaxation);
- public abstract bool SpringEnable(BulletConstraint constrain, int index, float numericTrueFalse);
- public const int SPRING_NOT_SPECIFIED = -1;
- public abstract bool SpringSetEquilibriumPoint(BulletConstraint constrain, int index, float equilibriumPoint);
- public abstract bool SpringSetStiffness(BulletConstraint constrain, int index, float stiffnesss);
- public abstract bool SpringSetDamping(BulletConstraint constrain, int index, float damping);
- public const int SLIDER_LOWER_LIMIT = 0;
- public const int SLIDER_UPPER_LIMIT = 1;
- public const int SLIDER_LINEAR = 2;
- public const int SLIDER_ANGULAR = 3;
- public abstract bool SliderSetLimits(BulletConstraint constrain, int lowerUpper, int linAng, float val);
- public const int SLIDER_SET_SOFTNESS = 4;
- public const int SLIDER_SET_RESTITUTION = 5;
- public const int SLIDER_SET_DAMPING = 6;
- public const int SLIDER_SET_DIRECTION = 7;
- public const int SLIDER_SET_LIMIT = 8;
- public const int SLIDER_SET_ORTHO = 9;
- public abstract bool SliderSet(BulletConstraint constrain, int softRestDamp, int dirLimOrtho, int linAng, float val);
- public abstract bool SliderMotorEnable(BulletConstraint constrain, int linAng, float numericTrueFalse);
- public const int SLIDER_MOTOR_VELOCITY = 10;
- public const int SLIDER_MAX_MOTOR_FORCE = 11;
- public abstract bool SliderMotor(BulletConstraint constrain, int forceVel, int linAng, float val);
- public abstract bool CalculateTransforms(BulletConstraint constrain);
- public abstract bool SetConstraintParam(BulletConstraint constrain, ConstraintParams paramIndex, float value, ConstraintParamAxis axis);
- public abstract bool DestroyConstraint(BulletWorld world, BulletConstraint constrain);
- public abstract void UpdateSingleAabb(BulletWorld world, BulletBody obj);
- public abstract void UpdateAabbs(BulletWorld world);
- public abstract bool GetForceUpdateAllAabbs(BulletWorld world);
- public abstract void SetForceUpdateAllAabbs(BulletWorld world, bool force);
- public abstract bool AddObjectToWorld(BulletWorld world, BulletBody obj);
- public abstract bool RemoveObjectFromWorld(BulletWorld world, BulletBody obj);
- public abstract bool ClearCollisionProxyCache(BulletWorld world, BulletBody obj);
- public abstract bool AddConstraintToWorld(BulletWorld world, BulletConstraint constrain, bool disableCollisionsBetweenLinkedObjects);
- public abstract bool RemoveConstraintFromWorld(BulletWorld world, BulletConstraint constrain);
- public abstract Vector3 GetAnisotripicFriction(BulletConstraint constrain);
- public abstract Vector3 SetAnisotripicFriction(BulletConstraint constrain, Vector3 frict);
- public abstract bool HasAnisotripicFriction(BulletConstraint constrain);
- public abstract void SetContactProcessingThreshold(BulletBody obj, float val);
- public abstract float GetContactProcessingThreshold(BulletBody obj);
- public abstract bool IsStaticObject(BulletBody obj);
- public abstract bool IsKinematicObject(BulletBody obj);
- public abstract bool IsStaticOrKinematicObject(BulletBody obj);
- public abstract bool HasContactResponse(BulletBody obj);
- public abstract void SetCollisionShape(BulletWorld sim, BulletBody obj, BulletShape shape);
- public abstract BulletShape GetCollisionShape(BulletBody obj);
- public abstract int GetActivationState(BulletBody obj);
- public abstract void SetActivationState(BulletBody obj, int state);
- public abstract void SetDeactivationTime(BulletBody obj, float dtime);
- public abstract float GetDeactivationTime(BulletBody obj);
- public abstract void ForceActivationState(BulletBody obj, ActivationState state);
- public abstract void Activate(BulletBody obj, bool forceActivation);
- public abstract bool IsActive(BulletBody obj);
- public abstract void SetRestitution(BulletBody obj, float val);
- public abstract float GetRestitution(BulletBody obj);
- public abstract void SetFriction(BulletBody obj, float val);
- public abstract float GetFriction(BulletBody obj);
- public abstract Vector3 GetPosition(BulletBody obj);
- public abstract Quaternion GetOrientation(BulletBody obj);
- public abstract void SetTranslation(BulletBody obj, Vector3 position, Quaternion rotation);
- public abstract void SetInterpolationLinearVelocity(BulletBody obj, Vector3 vel);
- public abstract void SetInterpolationAngularVelocity(BulletBody obj, Vector3 vel);
- public abstract void SetInterpolationVelocity(BulletBody obj, Vector3 linearVel, Vector3 angularVel);
- public abstract float GetHitFraction(BulletBody obj);
- public abstract void SetHitFraction(BulletBody obj, float val);
- public abstract CollisionFlags GetCollisionFlags(BulletBody obj);
- public abstract CollisionFlags SetCollisionFlags(BulletBody obj, CollisionFlags flags);
- public abstract CollisionFlags AddToCollisionFlags(BulletBody obj, CollisionFlags flags);
- public abstract CollisionFlags RemoveFromCollisionFlags(BulletBody obj, CollisionFlags flags);
- public abstract float GetCcdMotionThreshold(BulletBody obj);
- public abstract void SetCcdMotionThreshold(BulletBody obj, float val);
- public abstract float GetCcdSweptSphereRadius(BulletBody obj);
- public abstract void SetCcdSweptSphereRadius(BulletBody obj, float val);
- public abstract IntPtr GetUserPointer(BulletBody obj);
- public abstract void SetUserPointer(BulletBody obj, IntPtr val);
- public abstract void ApplyGravity(BulletBody obj);
- public abstract void SetGravity(BulletBody obj, Vector3 val);
- public abstract Vector3 GetGravity(BulletBody obj);
- public abstract void SetDamping(BulletBody obj, float lin_damping, float ang_damping);
- public abstract void SetLinearDamping(BulletBody obj, float lin_damping);
- public abstract void SetAngularDamping(BulletBody obj, float ang_damping);
- public abstract float GetLinearDamping(BulletBody obj);
- public abstract float GetAngularDamping(BulletBody obj);
- public abstract float GetLinearSleepingThreshold(BulletBody obj);
- public abstract void ApplyDamping(BulletBody obj, float timeStep);
- public abstract void SetMassProps(BulletBody obj, float mass, Vector3 inertia);
- public abstract Vector3 GetLinearFactor(BulletBody obj);
- public abstract void SetLinearFactor(BulletBody obj, Vector3 factor);
- public abstract void SetCenterOfMassByPosRot(BulletBody obj, Vector3 pos, Quaternion rot);
- public abstract void ApplyCentralForce(BulletBody obj, Vector3 force);
- public abstract void SetObjectForce(BulletBody obj, Vector3 force);
- public abstract Vector3 GetTotalForce(BulletBody obj);
- public abstract Vector3 GetTotalTorque(BulletBody obj);
- public abstract Vector3 GetInvInertiaDiagLocal(BulletBody obj);
- public abstract void SetInvInertiaDiagLocal(BulletBody obj, Vector3 inert);
- public abstract void SetSleepingThresholds(BulletBody obj, float lin_threshold, float ang_threshold);
- public abstract void ApplyTorque(BulletBody obj, Vector3 torque);
- public abstract void ApplyForce(BulletBody obj, Vector3 force, Vector3 pos);
- public abstract void ApplyCentralImpulse(BulletBody obj, Vector3 imp);
- public abstract void ApplyTorqueImpulse(BulletBody obj, Vector3 imp);
- public abstract void ApplyImpulse(BulletBody obj, Vector3 imp, Vector3 pos);
- public abstract void ClearForces(BulletBody obj);
- public abstract void ClearAllForces(BulletBody obj);
- public abstract void UpdateInertiaTensor(BulletBody obj);
- public abstract Vector3 GetLinearVelocity(BulletBody obj);
- public abstract Vector3 GetAngularVelocity(BulletBody obj);
- public abstract void SetLinearVelocity(BulletBody obj, Vector3 val);
- public abstract void SetAngularVelocity(BulletBody obj, Vector3 angularVelocity);
- public abstract Vector3 GetVelocityInLocalPoint(BulletBody obj, Vector3 pos);
- public abstract void Translate(BulletBody obj, Vector3 trans);
- public abstract void UpdateDeactivation(BulletBody obj, float timeStep);
- public abstract bool WantsSleeping(BulletBody obj);
- public abstract void SetAngularFactor(BulletBody obj, float factor);
- public abstract void SetAngularFactorV(BulletBody obj, Vector3 factor);
- public abstract Vector3 GetAngularFactor(BulletBody obj);
- public abstract bool IsInWorld(BulletWorld world, BulletBody obj);
- public abstract void AddConstraintRef(BulletBody obj, BulletConstraint constrain);
- public abstract void RemoveConstraintRef(BulletBody obj, BulletConstraint constrain);
- public abstract BulletConstraint GetConstraintRef(BulletBody obj, int index);
- public abstract int GetNumConstraintRefs(BulletBody obj);
- public abstract bool SetCollisionGroupMask(BulletBody body, UInt32 filter, UInt32 mask);
- public abstract float GetAngularMotionDisc(BulletShape shape);
- public abstract float GetContactBreakingThreshold(BulletShape shape, float defaultFactor);
- public abstract bool IsPolyhedral(BulletShape shape);
- public abstract bool IsConvex2d(BulletShape shape);
- public abstract bool IsConvex(BulletShape shape);
- public abstract bool IsNonMoving(BulletShape shape);
- public abstract bool IsConcave(BulletShape shape);
- public abstract bool IsCompound(BulletShape shape);
- public abstract bool IsSoftBody(BulletShape shape);
- public abstract bool IsInfinite(BulletShape shape);
- public abstract void SetLocalScaling(BulletShape shape, Vector3 scale);
- public abstract Vector3 GetLocalScaling(BulletShape shape);
- public abstract Vector3 CalculateLocalInertia(BulletShape shape, float mass);
- public abstract int GetShapeType(BulletShape shape);
- public abstract void SetMargin(BulletShape shape, float val);
- public abstract float GetMargin(BulletShape shape);
- public virtual void DumpRigidBody(BulletWorld sim, BulletBody collisionObject) { }
- public virtual void DumpCollisionShape(BulletWorld sim, BulletShape collisionShape) { }
- public virtual void DumpConstraint(BulletWorld sim, BulletConstraint constrain) { }
- public virtual void DumpActivationInfo(BulletWorld sim) { }
- public virtual void DumpAllInfo(BulletWorld sim) { }
- public virtual void DumpPhysicsStatistics(BulletWorld sim) { }
- public virtual void ResetBroadphasePool(BulletWorld sim) { }
- public virtual void ResetConstraintSolver(BulletWorld sim) { }
- };
- }
|