From 9fd0e1b0805ccc97b8e4f19727d98b26fb5fa89d Mon Sep 17 00:00:00 2001 From: Robert Adams Date: Sat, 29 Dec 2012 21:44:13 -0800 Subject: BulletSim: add the implementation files for the two versions of Bullet: unmanaged (C++) and managed (C#). --- OpenSim/Region/Physics/BulletSPlugin/BSAPIUnman.cs | 1107 ++++++++++++++++++++ OpenSim/Region/Physics/BulletSPlugin/BSAPIXNA.cs | 39 + 2 files changed, 1146 insertions(+) create mode 100755 OpenSim/Region/Physics/BulletSPlugin/BSAPIUnman.cs create mode 100755 OpenSim/Region/Physics/BulletSPlugin/BSAPIXNA.cs (limited to 'OpenSim/Region') diff --git a/OpenSim/Region/Physics/BulletSPlugin/BSAPIUnman.cs b/OpenSim/Region/Physics/BulletSPlugin/BSAPIUnman.cs new file mode 100755 index 0000000..bbfc1f8 --- /dev/null +++ b/OpenSim/Region/Physics/BulletSPlugin/BSAPIUnman.cs @@ -0,0 +1,1107 @@ +/* + * Copyright (c) Contributors, http://opensimulator.org/ + * See CONTRIBUTORS.TXT for a full list of copyright holders. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyrightD + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the OpenSimulator Project nor the + * names of its contributors may be used to endorse or promote products + * derived from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE DEVELOPERS ``AS IS'' AND ANY + * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE CONTRIBUTORS BE LIABLE FOR ANY + * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ +using System; +using System.Collections.Generic; +using System.Runtime.InteropServices; +using System.Security; +using System.Text; + +using OpenMetaverse; + +namespace OpenSim.Region.Physics.BulletSPlugin +{ +public sealed class BSAPIUnman : BulletSimAPITemplate +{ + /* +// Initialization and simulation +public BulletWorld Initialize(Vector3 maxPosition, IntPtr parms, + int maxCollisions, IntPtr collisionArray, + int maxUpdates, IntPtr updateArray + ); + +public bool UpdateParameter(BulletWorld world, uint localID, String parm, float value); + +public void SetHeightMap(BulletWorld world, float[] heightmap); + +public void Shutdown(BulletWorld sim); + +public int PhysicsStep(BulletWorld world, float timeStep, int maxSubSteps, float fixedTimeStep, + out int updatedEntityCount, + out IntPtr updatedEntitiesPtr, + out int collidersCount, + out IntPtr collidersPtr); + +public bool PushUpdate(BulletBody obj); + */ + +// ===================================================================================== +// Mesh, hull, shape and body creation helper routines +public override BulletShape CreateMeshShape(BulletWorld world, + int indicesCount, int[] indices, + int verticesCount, float[] vertices) +{ + return new BulletShape( + BSAPI.CreateMeshShape2(world.ptr, indicesCount, indices, verticesCount, vertices), + BSPhysicsShapeType.SHAPE_MESH); +} + +public override BulletShape CreateHullShape(BulletWorld world, int hullCount, float[] hulls) +{ + return new BulletShape( + BSAPI.CreateHullShape2(world.ptr, hullCount, hulls), + BSPhysicsShapeType.SHAPE_HULL); +} + +public override BulletShape BuildHullShapeFromMesh(BulletWorld world, BulletShape meshShape) +{ + return new BulletShape( + BSAPI.BuildHullShapeFromMesh2(world.ptr, meshShape.ptr), + BSPhysicsShapeType.SHAPE_HULL); +} + +public override BulletShape BuildNativeShape( BulletWorld world, ShapeData shapeData) +{ + return new BulletShape( + BSAPI.BuildNativeShape2(world.ptr, shapeData), + shapeData.Type); +} + +public override bool IsNativeShape(BulletShape shape) +{ + if (shape.HasPhysicalShape) + return BSAPI.IsNativeShape2(shape.ptr); + return false; +} + +public override void SetShapeCollisionMargin(BulletShape shape, float margin) +{ + if (shape.HasPhysicalShape) + BSAPI.SetShapeCollisionMargin2(shape.ptr, margin); +} + +public override BulletShape BuildCapsuleShape(BulletWorld world, float radius, float height, Vector3 scale) +{ + return new BulletShape( + BSAPI.BuildCapsuleShape2(world.ptr, radius, height, scale), + BSPhysicsShapeType.SHAPE_CAPSULE); +} + +public override BulletShape CreateCompoundShape(BulletWorld sim, bool enableDynamicAabbTree) +{ + return new BulletShape( + BSAPI.CreateCompoundShape2(sim.ptr, enableDynamicAabbTree), + BSPhysicsShapeType.SHAPE_COMPOUND); + +} + +public override int GetNumberOfCompoundChildren(BulletShape shape) +{ + if (shape.HasPhysicalShape) + return BSAPI.GetNumberOfCompoundChildren2(shape.ptr); + return 0; +} + +public override void AddChildShapeToCompoundShape(BulletShape cShape, BulletShape addShape, Vector3 pos, Quaternion rot) +{ + BSAPI.AddChildShapeToCompoundShape2(cShape.ptr, addShape.ptr, pos, rot); +} + +public override BulletShape GetChildShapeFromCompoundShapeIndex(BulletShape cShape, int indx) +{ + return new BulletShape(BSAPI.GetChildShapeFromCompoundShapeIndex2(cShape.ptr, indx)); +} + +public override BulletShape RemoveChildShapeFromCompoundShapeIndex(BulletShape cShape, int indx) +{ + return new BulletShape(BSAPI.RemoveChildShapeFromCompoundShapeIndex2(cShape.ptr, indx)); +} + +public override void RemoveChildShapeFromCompoundShape(BulletShape cShape, BulletShape removeShape) +{ + BSAPI.RemoveChildShapeFromCompoundShape2(cShape.ptr, removeShape.ptr); +} + +public override void RecalculateCompoundShapeLocalAabb(BulletShape cShape) +{ + BSAPI.RecalculateCompoundShapeLocalAabb2(cShape.ptr); +} + +public override BulletShape DuplicateCollisionShape(BulletWorld sim, BulletShape srcShape, uint id) +{ + return new BulletShape(BSAPI.DuplicateCollisionShape2(sim.ptr, srcShape.ptr, id), srcShape.type); +} + +public override BulletBody CreateBodyFromShapeAndInfo(BulletWorld sim, BulletShape shape, uint id, IntPtr constructionInfo) +{ + return new BulletBody(id, BSAPI.CreateBodyFromShapeAndInfo2(sim.ptr, shape.ptr, id, constructionInfo)); +} + +public override bool DeleteCollisionShape(BulletWorld world, BulletShape shape) +{ + return BSAPI.DeleteCollisionShape2(world.ptr, shape.ptr); +} + +public override int GetBodyType(BulletBody obj) +{ + return BSAPI.GetBodyType2(obj.ptr); +} + +public override BulletBody CreateBodyFromShape(BulletWorld sim, BulletShape shape, uint id, Vector3 pos, Quaternion rot) +{ + return new BulletBody(id, BSAPI.CreateBodyFromShape2(sim.ptr, shape.ptr, id, pos, rot)); +} + +public override BulletBody CreateBodyWithDefaultMotionState(BulletShape shape, uint id, Vector3 pos, Quaternion rot) +{ + return new BulletBody(id, BSAPI.CreateBodyWithDefaultMotionState2(shape.ptr, id, pos, rot)); +} + +public override BulletBody CreateGhostFromShape(BulletWorld sim, BulletShape shape, uint id, Vector3 pos, Quaternion rot) +{ + return new BulletBody(id, BSAPI.CreateGhostFromShape2(sim.ptr, shape.ptr, id, pos, rot)); +} + +public override IntPtr AllocateBodyInfo(BulletBody obj) +{ + return BSAPI.AllocateBodyInfo2(obj.ptr); +} + +public override void ReleaseBodyInfo(IntPtr obj) +{ + BSAPI.ReleaseBodyInfo2(obj); +} + +public override void DestroyObject(BulletWorld sim, BulletBody obj) +{ + BSAPI.DestroyObject2(sim.ptr, obj.ptr); +} + + /* +// ===================================================================================== +// Terrain creation and helper routines +public override IntPtr CreateHeightMapInfo(BulletWorld sim, uint id, Vector3 minCoords, Vector3 maxCoords, + [MarshalAs(UnmanagedType.LPArray)] float[] heightMap, float collisionMargin); + +public override IntPtr FillHeightMapInfo(BulletWorld sim, IntPtr mapInfo, uint id, Vector3 minCoords, Vector3 maxCoords, + [MarshalAs(UnmanagedType.LPArray)] float[] heightMap, float collisionMargin); + +public override bool ReleaseHeightMapInfo(IntPtr heightMapInfo); + +public override BulletBody CreateGroundPlaneShape(uint id, float height, float collisionMargin); + +public override BulletBody CreateTerrainShape(IntPtr mapInfo); + +// ===================================================================================== +// Constraint creation and helper routines +public override BulletConstraint Create6DofConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2, + Vector3 frame1loc, Quaternion frame1rot, + Vector3 frame2loc, Quaternion frame2rot, + bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies); + +public override BulletConstraint Create6DofConstraintToPoint(BulletWorld world, BulletBody obj1, BulletBody obj2, + Vector3 joinPoint, + bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies); + +public override BulletConstraint CreateHingeConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2, + Vector3 pivotinA, Vector3 pivotinB, + Vector3 axisInA, Vector3 axisInB, + bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies); + +public override void SetConstraintEnable(BulletConstraint constrain, float numericTrueFalse); + +public override void SetConstraintNumSolverIterations(BulletConstraint constrain, float iterations); + +public override bool SetFrames(BulletConstraint constrain, + Vector3 frameA, Quaternion frameArot, Vector3 frameB, Quaternion frameBrot); + +public override bool SetLinearLimits(BulletConstraint constrain, Vector3 low, Vector3 hi); + +public override bool SetAngularLimits(BulletConstraint constrain, Vector3 low, Vector3 hi); + +public override bool UseFrameOffset(BulletConstraint constrain, float enable); + +public override bool TranslationalLimitMotor(BulletConstraint constrain, float enable, float targetVel, float maxMotorForce); + +public override bool SetBreakingImpulseThreshold(BulletConstraint constrain, float threshold); + +public override bool CalculateTransforms(BulletConstraint constrain); + +public override bool SetConstraintParam(BulletConstraint constrain, ConstraintParams paramIndex, float value, ConstraintParamAxis axis); + +public override bool DestroyConstraint(BulletWorld world, BulletConstraint constrain); + +// ===================================================================================== +// btCollisionWorld entries +public override void UpdateSingleAabb(BulletWorld world, BulletBody obj); + +public override void UpdateAabbs(BulletWorld world); + +public override bool GetForceUpdateAllAabbs(BulletWorld world); + +public override void SetForceUpdateAllAabbs(BulletWorld world, bool force); + +// ===================================================================================== +// btDynamicsWorld entries +public override bool AddObjectToWorld(BulletWorld world, BulletBody obj); + +public override bool RemoveObjectFromWorld(BulletWorld world, BulletBody obj); + +public override bool AddConstraintToWorld(BulletWorld world, BulletConstraint constrain, bool disableCollisionsBetweenLinkedObjects); + +public override bool RemoveConstraintFromWorld(BulletWorld world, BulletConstraint constrain); +// ===================================================================================== +// btCollisionObject entries +public override Vector3 GetAnisotripicFriction(BulletConstraint constrain); + +public override Vector3 SetAnisotripicFriction(BulletConstraint constrain, Vector3 frict); + +public override bool HasAnisotripicFriction(BulletConstraint constrain); + +public override void SetContactProcessingThreshold(BulletBody obj, float val); + +public override float GetContactProcessingThreshold(BulletBody obj); + +public override bool IsStaticObject(BulletBody obj); + +public override bool IsKinematicObject(BulletBody obj); + +public override bool IsStaticOrKinematicObject(BulletBody obj); + +public override bool HasContactResponse(BulletBody obj); + +public override void SetCollisionShape(BulletWorld sim, BulletBody obj, BulletBody shape); + +public override BulletShape GetCollisionShape(BulletBody obj); + +public override int GetActivationState(BulletBody obj); + +public override void SetActivationState(BulletBody obj, int state); + +public override void SetDeactivationTime(BulletBody obj, float dtime); + +public override float GetDeactivationTime(BulletBody obj); + +public override void ForceActivationState(BulletBody obj, ActivationState state); + +public override void Activate(BulletBody obj, bool forceActivation); + +public override bool IsActive(BulletBody obj); + +public override void SetRestitution(BulletBody obj, float val); + +public override float GetRestitution(BulletBody obj); + +public override void SetFriction(BulletBody obj, float val); + +public override float GetFriction(BulletBody obj); + +public override Vector3 GetPosition(BulletBody obj); + +public override Quaternion GetOrientation(BulletBody obj); + +public override void SetTranslation(BulletBody obj, Vector3 position, Quaternion rotation); + +public override IntPtr GetBroadphaseHandle(BulletBody obj); + +public override void SetBroadphaseHandle(BulletBody obj, IntPtr handle); + +public override void SetInterpolationLinearVelocity(BulletBody obj, Vector3 vel); + +public override void SetInterpolationAngularVelocity(BulletBody obj, Vector3 vel); + +public override void SetInterpolationVelocity(BulletBody obj, Vector3 linearVel, Vector3 angularVel); + +public override float GetHitFraction(BulletBody obj); + +public override void SetHitFraction(BulletBody obj, float val); + +public override CollisionFlags GetCollisionFlags(BulletBody obj); + +public override CollisionFlags SetCollisionFlags(BulletBody obj, CollisionFlags flags); + +public override CollisionFlags AddToCollisionFlags(BulletBody obj, CollisionFlags flags); + +public override CollisionFlags RemoveFromCollisionFlags(BulletBody obj, CollisionFlags flags); + +public override float GetCcdMotionThreshold(BulletBody obj); + +public override void SetCcdMotionThreshold(BulletBody obj, float val); + +public override float GetCcdSweptSphereRadius(BulletBody obj); + +public override void SetCcdSweptSphereRadius(BulletBody obj, float val); + +public override IntPtr GetUserPointer(BulletBody obj); + +public override void SetUserPointer(BulletBody obj, IntPtr val); + +// ===================================================================================== +// btRigidBody entries +public override void ApplyGravity(BulletBody obj); + +public override void SetGravity(BulletBody obj, Vector3 val); + +public override Vector3 GetGravity(BulletBody obj); + +public override void SetDamping(BulletBody obj, float lin_damping, float ang_damping); + +public override void SetLinearDamping(BulletBody obj, float lin_damping); + +public override void SetAngularDamping(BulletBody obj, float ang_damping); + +public override float GetLinearDamping(BulletBody obj); + +public override float GetAngularDamping(BulletBody obj); + +public override float GetLinearSleepingThreshold(BulletBody obj); + + +public override void ApplyDamping(BulletBody obj, float timeStep); + +public override void SetMassProps(BulletBody obj, float mass, Vector3 inertia); + +public override Vector3 GetLinearFactor(BulletBody obj); + +public override void SetLinearFactor(BulletBody obj, Vector3 factor); + +public override void SetCenterOfMassByPosRot(BulletBody obj, Vector3 pos, Quaternion rot); + +// Add a force to the object as if its mass is one. +public override void ApplyCentralForce(BulletBody obj, Vector3 force); + +// Set the force being applied to the object as if its mass is one. +public override void SetObjectForce(BulletBody obj, Vector3 force); + +public override Vector3 GetTotalForce(BulletBody obj); + +public override Vector3 GetTotalTorque(BulletBody obj); + +public override Vector3 GetInvInertiaDiagLocal(BulletBody obj); + +public override void SetInvInertiaDiagLocal(BulletBody obj, Vector3 inert); + +public override void SetSleepingThresholds(BulletBody obj, float lin_threshold, float ang_threshold); + +public override void ApplyTorque(BulletBody obj, Vector3 torque); + +// Apply force at the given point. Will add torque to the object. +public override void ApplyForce(BulletBody obj, Vector3 force, Vector3 pos); + +// Apply impulse to the object. Same as "ApplycentralForce" but force scaled by object's mass. +public override void ApplyCentralImpulse(BulletBody obj, Vector3 imp); + +// Apply impulse to the object's torque. Force is scaled by object's mass. +public override void ApplyTorqueImpulse(BulletBody obj, Vector3 imp); + +// Apply impulse at the point given. For is scaled by object's mass and effects both linear and angular forces. +public override void ApplyImpulse(BulletBody obj, Vector3 imp, Vector3 pos); + +public override void ClearForces(BulletBody obj); + +public override void ClearAllForces(BulletBody obj); + +public override void UpdateInertiaTensor(BulletBody obj); + +public override Vector3 GetLinearVelocity(BulletBody obj); + +public override Vector3 GetAngularVelocity(BulletBody obj); + +public override void SetLinearVelocity(BulletBody obj, Vector3 val); + +public override void SetAngularVelocity(BulletBody obj, Vector3 angularVelocity); + +public override Vector3 GetVelocityInLocalPoint(BulletBody obj, Vector3 pos); + +public override void Translate(BulletBody obj, Vector3 trans); + +public override void UpdateDeactivation(BulletBody obj, float timeStep); + +public override bool WantsSleeping(BulletBody obj); + +public override void SetAngularFactor(BulletBody obj, float factor); + +public override void SetAngularFactorV(BulletBody obj, Vector3 factor); + +public override Vector3 GetAngularFactor(BulletBody obj); + +public override bool IsInWorld(BulletBody obj); + +public override void AddConstraintRef(BulletBody obj, BulletConstraint constrain); + +public override void RemoveConstraintRef(BulletBody obj, BulletConstraint constrain); + +public override BulletConstraint GetConstraintRef(BulletBody obj, int index); + +public override int GetNumConstraintRefs(BulletBody obj); + +public override bool SetCollisionGroupMask(BulletBody body, uint filter, uint mask); + +// ===================================================================================== +// btCollisionShape entries + +public override float GetAngularMotionDisc(BulletShape shape); + +public override float GetContactBreakingThreshold(BulletShape shape, float defaultFactor); + +public override bool IsPolyhedral(BulletShape shape); + +public override bool IsConvex2d(BulletShape shape); + +public override bool IsConvex(BulletShape shape); + +public override bool IsNonMoving(BulletShape shape); + +public override bool IsConcave(BulletShape shape); + +public override bool IsCompound(BulletShape shape); + +public override bool IsSoftBody(BulletShape shape); + +public override bool IsInfinite(BulletShape shape); + +public override void SetLocalScaling(BulletShape shape, Vector3 scale); + +public override Vector3 GetLocalScaling(BulletShape shape); + +public override Vector3 CalculateLocalInertia(BulletShape shape, float mass); + +public override int GetShapeType(BulletShape shape); + +public override void SetMargin(BulletShape shape, float val); + +public override float GetMargin(BulletShape shape); + */ + +static class BSAPI +{ +// ===================================================================================== +// Mesh, hull, shape and body creation helper routines +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr CreateMeshShape2(IntPtr world, + int indicesCount, [MarshalAs(UnmanagedType.LPArray)] int[] indices, + int verticesCount, [MarshalAs(UnmanagedType.LPArray)] float[] vertices ); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr CreateHullShape2(IntPtr world, + int hullCount, [MarshalAs(UnmanagedType.LPArray)] float[] hulls); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr BuildHullShapeFromMesh2(IntPtr world, IntPtr meshShape); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr BuildNativeShape2(IntPtr world, ShapeData shapeData); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool IsNativeShape2(IntPtr shape); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetShapeCollisionMargin2(IntPtr shape, float margin); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr BuildCapsuleShape2(IntPtr world, float radius, float height, Vector3 scale); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr CreateCompoundShape2(IntPtr sim, bool enableDynamicAabbTree); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern int GetNumberOfCompoundChildren2(IntPtr cShape); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void AddChildShapeToCompoundShape2(IntPtr cShape, IntPtr addShape, Vector3 pos, Quaternion rot); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr GetChildShapeFromCompoundShapeIndex2(IntPtr cShape, int indx); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr RemoveChildShapeFromCompoundShapeIndex2(IntPtr cShape, int indx); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void RemoveChildShapeFromCompoundShape2(IntPtr cShape, IntPtr removeShape); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void RecalculateCompoundShapeLocalAabb2(IntPtr cShape); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr DuplicateCollisionShape2(IntPtr sim, IntPtr srcShape, uint id); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr CreateBodyFromShapeAndInfo2(IntPtr sim, IntPtr shape, uint id, IntPtr constructionInfo); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool DeleteCollisionShape2(IntPtr world, IntPtr shape); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern int GetBodyType2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr CreateBodyFromShape2(IntPtr sim, IntPtr shape, uint id, Vector3 pos, Quaternion rot); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr CreateBodyWithDefaultMotionState2(IntPtr shape, uint id, Vector3 pos, Quaternion rot); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr CreateGhostFromShape2(IntPtr sim, IntPtr shape, uint id, Vector3 pos, Quaternion rot); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr AllocateBodyInfo2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void ReleaseBodyInfo2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void DestroyObject2(IntPtr sim, IntPtr obj); + +} +} + +// =============================================================================== +// =============================================================================== +// =============================================================================== +// =============================================================================== +// =============================================================================== +// =============================================================================== +// =============================================================================== +// =============================================================================== +// =============================================================================== +// =============================================================================== +// =============================================================================== +// =============================================================================== +// =============================================================================== +static class BulletSimAPI { +// =============================================================================== +// Link back to the managed code for outputting log messages +[UnmanagedFunctionPointer(CallingConvention.Cdecl)] +public delegate void DebugLogCallback([MarshalAs(UnmanagedType.LPStr)]string msg); + +// =============================================================================== +// Initialization and simulation +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr Initialize2(Vector3 maxPosition, IntPtr parms, + int maxCollisions, IntPtr collisionArray, + int maxUpdates, IntPtr updateArray, + DebugLogCallback logRoutine); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool UpdateParameter2(IntPtr world, uint localID, String parm, float value); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetHeightMap2(IntPtr world, float[] heightmap); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void Shutdown2(IntPtr sim); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern int PhysicsStep2(IntPtr world, float timeStep, int maxSubSteps, float fixedTimeStep, + out int updatedEntityCount, + out IntPtr updatedEntitiesPtr, + out int collidersCount, + out IntPtr collidersPtr); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool PushUpdate2(IntPtr obj); + +// ===================================================================================== +// Terrain creation and helper routines +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr CreateHeightMapInfo2(IntPtr sim, uint id, Vector3 minCoords, Vector3 maxCoords, + [MarshalAs(UnmanagedType.LPArray)] float[] heightMap, float collisionMargin); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr FillHeightMapInfo2(IntPtr sim, IntPtr mapInfo, uint id, Vector3 minCoords, Vector3 maxCoords, + [MarshalAs(UnmanagedType.LPArray)] float[] heightMap, float collisionMargin); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool ReleaseHeightMapInfo2(IntPtr heightMapInfo); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr CreateGroundPlaneShape2(uint id, float height, float collisionMargin); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr CreateTerrainShape2(IntPtr mapInfo); + +// ===================================================================================== +// Constraint creation and helper routines +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr Create6DofConstraint2(IntPtr world, IntPtr obj1, IntPtr obj2, + Vector3 frame1loc, Quaternion frame1rot, + Vector3 frame2loc, Quaternion frame2rot, + bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr Create6DofConstraintToPoint2(IntPtr world, IntPtr obj1, IntPtr obj2, + Vector3 joinPoint, + bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr CreateHingeConstraint2(IntPtr world, IntPtr obj1, IntPtr obj2, + Vector3 pivotinA, Vector3 pivotinB, + Vector3 axisInA, Vector3 axisInB, + bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetConstraintEnable2(IntPtr constrain, float numericTrueFalse); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetConstraintNumSolverIterations2(IntPtr constrain, float iterations); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool SetFrames2(IntPtr constrain, + Vector3 frameA, Quaternion frameArot, Vector3 frameB, Quaternion frameBrot); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool SetLinearLimits2(IntPtr constrain, Vector3 low, Vector3 hi); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool SetAngularLimits2(IntPtr constrain, Vector3 low, Vector3 hi); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool UseFrameOffset2(IntPtr constrain, float enable); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool TranslationalLimitMotor2(IntPtr constrain, float enable, float targetVel, float maxMotorForce); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool SetBreakingImpulseThreshold2(IntPtr constrain, float threshold); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool CalculateTransforms2(IntPtr constrain); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool SetConstraintParam2(IntPtr constrain, ConstraintParams paramIndex, float value, ConstraintParamAxis axis); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool DestroyConstraint2(IntPtr world, IntPtr constrain); + +// ===================================================================================== +// btCollisionWorld entries +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void UpdateSingleAabb2(IntPtr world, IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void UpdateAabbs2(IntPtr world); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool GetForceUpdateAllAabbs2(IntPtr world); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetForceUpdateAllAabbs2(IntPtr world, bool force); + +// ===================================================================================== +// btDynamicsWorld entries +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool AddObjectToWorld2(IntPtr world, IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool RemoveObjectFromWorld2(IntPtr world, IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool AddConstraintToWorld2(IntPtr world, IntPtr constrain, bool disableCollisionsBetweenLinkedObjects); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool RemoveConstraintFromWorld2(IntPtr world, IntPtr constrain); +// ===================================================================================== +// btCollisionObject entries +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern Vector3 GetAnisotripicFriction2(IntPtr constrain); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern Vector3 SetAnisotripicFriction2(IntPtr constrain, Vector3 frict); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool HasAnisotripicFriction2(IntPtr constrain); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetContactProcessingThreshold2(IntPtr obj, float val); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern float GetContactProcessingThreshold2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool IsStaticObject2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool IsKinematicObject2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool IsStaticOrKinematicObject2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool HasContactResponse2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetCollisionShape2(IntPtr sim, IntPtr obj, IntPtr shape); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr GetCollisionShape2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern int GetActivationState2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetActivationState2(IntPtr obj, int state); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetDeactivationTime2(IntPtr obj, float dtime); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern float GetDeactivationTime2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void ForceActivationState2(IntPtr obj, ActivationState state); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void Activate2(IntPtr obj, bool forceActivation); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool IsActive2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetRestitution2(IntPtr obj, float val); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern float GetRestitution2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetFriction2(IntPtr obj, float val); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern float GetFriction2(IntPtr obj); + + /* Haven't defined the type 'Transform' +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern Transform GetWorldTransform2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void setWorldTransform2(IntPtr obj, Transform trans); + */ + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern Vector3 GetPosition2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern Quaternion GetOrientation2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetTranslation2(IntPtr obj, Vector3 position, Quaternion rotation); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr GetBroadphaseHandle2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetBroadphaseHandle2(IntPtr obj, IntPtr handle); + + /* +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern Transform GetInterpolationWorldTransform2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetInterpolationWorldTransform2(IntPtr obj, Transform trans); + */ + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetInterpolationLinearVelocity2(IntPtr obj, Vector3 vel); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetInterpolationAngularVelocity2(IntPtr obj, Vector3 vel); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetInterpolationVelocity2(IntPtr obj, Vector3 linearVel, Vector3 angularVel); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern float GetHitFraction2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetHitFraction2(IntPtr obj, float val); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern CollisionFlags GetCollisionFlags2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern CollisionFlags SetCollisionFlags2(IntPtr obj, CollisionFlags flags); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern CollisionFlags AddToCollisionFlags2(IntPtr obj, CollisionFlags flags); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern CollisionFlags RemoveFromCollisionFlags2(IntPtr obj, CollisionFlags flags); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern float GetCcdMotionThreshold2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetCcdMotionThreshold2(IntPtr obj, float val); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern float GetCcdSweptSphereRadius2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetCcdSweptSphereRadius2(IntPtr obj, float val); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr GetUserPointer2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetUserPointer2(IntPtr obj, IntPtr val); + +// ===================================================================================== +// btRigidBody entries +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void ApplyGravity2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetGravity2(IntPtr obj, Vector3 val); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern Vector3 GetGravity2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetDamping2(IntPtr obj, float lin_damping, float ang_damping); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetLinearDamping2(IntPtr obj, float lin_damping); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetAngularDamping2(IntPtr obj, float ang_damping); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern float GetLinearDamping2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern float GetAngularDamping2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern float GetLinearSleepingThreshold2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern float GetAngularSleepingThreshold2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void ApplyDamping2(IntPtr obj, float timeStep); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetMassProps2(IntPtr obj, float mass, Vector3 inertia); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern Vector3 GetLinearFactor2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetLinearFactor2(IntPtr obj, Vector3 factor); + + /* +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetCenterOfMassTransform2(IntPtr obj, Transform trans); + */ + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetCenterOfMassByPosRot2(IntPtr obj, Vector3 pos, Quaternion rot); + +// Add a force to the object as if its mass is one. +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void ApplyCentralForce2(IntPtr obj, Vector3 force); + +// Set the force being applied to the object as if its mass is one. +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetObjectForce2(IntPtr obj, Vector3 force); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern Vector3 GetTotalForce2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern Vector3 GetTotalTorque2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern Vector3 GetInvInertiaDiagLocal2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetInvInertiaDiagLocal2(IntPtr obj, Vector3 inert); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetSleepingThresholds2(IntPtr obj, float lin_threshold, float ang_threshold); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void ApplyTorque2(IntPtr obj, Vector3 torque); + +// Apply force at the given point. Will add torque to the object. +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void ApplyForce2(IntPtr obj, Vector3 force, Vector3 pos); + +// Apply impulse to the object. Same as "ApplycentralForce" but force scaled by object's mass. +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void ApplyCentralImpulse2(IntPtr obj, Vector3 imp); + +// Apply impulse to the object's torque. Force is scaled by object's mass. +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void ApplyTorqueImpulse2(IntPtr obj, Vector3 imp); + +// Apply impulse at the point given. For is scaled by object's mass and effects both linear and angular forces. +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void ApplyImpulse2(IntPtr obj, Vector3 imp, Vector3 pos); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void ClearForces2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void ClearAllForces2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void UpdateInertiaTensor2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern Vector3 GetCenterOfMassPosition2(IntPtr obj); + + /* +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern Transform GetCenterOfMassTransform2(IntPtr obj); + */ + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern Vector3 GetLinearVelocity2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern Vector3 GetAngularVelocity2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetLinearVelocity2(IntPtr obj, Vector3 val); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetAngularVelocity2(IntPtr obj, Vector3 angularVelocity); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern Vector3 GetVelocityInLocalPoint2(IntPtr obj, Vector3 pos); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void Translate2(IntPtr obj, Vector3 trans); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void UpdateDeactivation2(IntPtr obj, float timeStep); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool WantsSleeping2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetAngularFactor2(IntPtr obj, float factor); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetAngularFactorV2(IntPtr obj, Vector3 factor); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern Vector3 GetAngularFactor2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool IsInWorld2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void AddConstraintRef2(IntPtr obj, IntPtr constrain); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void RemoveConstraintRef2(IntPtr obj, IntPtr constrain); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern IntPtr GetConstraintRef2(IntPtr obj, int index); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern int GetNumConstraintRefs2(IntPtr obj); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool SetCollisionGroupMask2(IntPtr body, uint filter, uint mask); + +// ===================================================================================== +// btCollisionShape entries + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern float GetAngularMotionDisc2(IntPtr shape); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern float GetContactBreakingThreshold2(IntPtr shape, float defaultFactor); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool IsPolyhedral2(IntPtr shape); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool IsConvex2d2(IntPtr shape); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool IsConvex2(IntPtr shape); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool IsNonMoving2(IntPtr shape); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool IsConcave2(IntPtr shape); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool IsCompound2(IntPtr shape); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool IsSoftBody2(IntPtr shape); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool IsInfinite2(IntPtr shape); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetLocalScaling2(IntPtr shape, Vector3 scale); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern Vector3 GetLocalScaling2(IntPtr shape); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern Vector3 CalculateLocalInertia2(IntPtr shape, float mass); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern int GetShapeType2(IntPtr shape); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void SetMargin2(IntPtr shape, float val); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern float GetMargin2(IntPtr shape); + +// ===================================================================================== +// Debugging +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void DumpRigidBody2(IntPtr sim, IntPtr collisionObject); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void DumpCollisionShape2(IntPtr sim, IntPtr collisionShape); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void DumpMapInfo2(IntPtr sim, IntPtr manInfo); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void DumpConstraint2(IntPtr sim, IntPtr constrain); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void DumpActivationInfo2(IntPtr sim); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void DumpAllInfo2(IntPtr sim); + +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern void DumpPhysicsStatistics2(IntPtr sim); + +} +} diff --git a/OpenSim/Region/Physics/BulletSPlugin/BSAPIXNA.cs b/OpenSim/Region/Physics/BulletSPlugin/BSAPIXNA.cs new file mode 100755 index 0000000..a56a817 --- /dev/null +++ b/OpenSim/Region/Physics/BulletSPlugin/BSAPIXNA.cs @@ -0,0 +1,39 @@ +/* + * Copyright (c) Contributors, http://opensimulator.org/ + * See CONTRIBUTORS.TXT for a full list of copyright holders. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyrightD + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the OpenSimulator Project nor the + * names of its contributors may be used to endorse or promote products + * derived from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE DEVELOPERS ``AS IS'' AND ANY + * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE CONTRIBUTORS BE LIABLE FOR ANY + * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ +using System; +using System.Collections.Generic; +using System.Linq; +using System.Text; + +namespace OpenSim.Region.Physics.BulletSPlugin +{ + /* +public sealed class BSAPIXNA : BulletSimAPITemplate +{ +} + */ +} -- cgit v1.1