From c2a7af18b639646b647eb4cdff4168a2b9746ee4 Mon Sep 17 00:00:00 2001 From: Robert Adams Date: Sun, 30 Dec 2012 14:26:57 -0800 Subject: BulletSim: nearly complete in conversion from BulletSimAPI to BSAPITemplate. Only initialization and debug fuctions left. --- OpenSim/Region/Physics/BulletSPlugin/BSAPIUnman.cs | 418 +++++++++---- .../Region/Physics/BulletSPlugin/BSApiTemplate.cs | 664 ++++++++++++++++++++ .../Region/Physics/BulletSPlugin/BSCharacter.cs | 34 +- OpenSim/Region/Physics/BulletSPlugin/BSDynamics.cs | 12 +- .../Physics/BulletSPlugin/BSLinksetCompound.cs | 5 - .../Physics/BulletSPlugin/BSLinksetConstraints.cs | 11 +- OpenSim/Region/Physics/BulletSPlugin/BSParam.cs | 10 +- OpenSim/Region/Physics/BulletSPlugin/BSPrim.cs | 46 +- OpenSim/Region/Physics/BulletSPlugin/BSScene.cs | 2 +- .../Physics/BulletSPlugin/BSShapeCollection.cs | 10 +- OpenSim/Region/Physics/BulletSPlugin/BSShapes.cs | 6 +- .../Physics/BulletSPlugin/BSTerrainHeightmap.cs | 2 +- .../Physics/BulletSPlugin/BSTerrainManager.cs | 2 +- .../Region/Physics/BulletSPlugin/BSTerrainMesh.cs | 4 +- .../Region/Physics/BulletSPlugin/BulletSimAPI.cs | 667 --------------------- .../Region/Physics/BulletSPlugin/BulletSimData.cs | 4 +- 16 files changed, 1034 insertions(+), 863 deletions(-) create mode 100644 OpenSim/Region/Physics/BulletSPlugin/BSApiTemplate.cs delete mode 100644 OpenSim/Region/Physics/BulletSPlugin/BulletSimAPI.cs diff --git a/OpenSim/Region/Physics/BulletSPlugin/BSAPIUnman.cs b/OpenSim/Region/Physics/BulletSPlugin/BSAPIUnman.cs index 9a8a2e8..6e68053 100755 --- a/OpenSim/Region/Physics/BulletSPlugin/BSAPIUnman.cs +++ b/OpenSim/Region/Physics/BulletSPlugin/BSAPIUnman.cs @@ -34,7 +34,7 @@ using OpenMetaverse; namespace OpenSim.Region.Physics.BulletSPlugin { -public sealed class BSAPIUnman : BulletSimAPITemplate +public sealed class BSAPIUnman : BSAPITemplate { /* // Initialization and simulation @@ -55,8 +55,11 @@ public int PhysicsStep(BulletWorld world, float timeStep, int maxSubSteps, float out int collidersCount, out IntPtr collidersPtr); -public bool PushUpdate(BulletBody obj); */ +public override bool PushUpdate(BulletBody obj) +{ + return BSAPICPP.PushUpdate2(obj.ptr); +} // ===================================================================================== // Mesh, hull, shape and body creation helper routines @@ -569,146 +572,332 @@ public override void SetUserPointer(BulletBody obj, IntPtr val) BSAPICPP.SetUserPointer2(obj.ptr, val); } - /* // ===================================================================================== // btRigidBody entries -public override void ApplyGravity(BulletBody obj); - -public override void SetGravity(BulletBody obj, Vector3 val); +public override void ApplyGravity(BulletBody obj) +{ + BSAPICPP.ApplyGravity2(obj.ptr); +} -public override Vector3 GetGravity(BulletBody obj); +public override void SetGravity(BulletBody obj, Vector3 val) +{ + BSAPICPP.SetGravity2(obj.ptr, val); +} -public override void SetDamping(BulletBody obj, float lin_damping, float ang_damping); +public override Vector3 GetGravity(BulletBody obj) +{ + return BSAPICPP.GetGravity2(obj.ptr); +} -public override void SetLinearDamping(BulletBody obj, float lin_damping); +public override void SetDamping(BulletBody obj, float lin_damping, float ang_damping) +{ + BSAPICPP.SetDamping2(obj.ptr, lin_damping, ang_damping); +} -public override void SetAngularDamping(BulletBody obj, float ang_damping); +public override void SetLinearDamping(BulletBody obj, float lin_damping) +{ + BSAPICPP.SetLinearDamping2(obj.ptr, lin_damping); +} -public override float GetLinearDamping(BulletBody obj); +public override void SetAngularDamping(BulletBody obj, float ang_damping) +{ + BSAPICPP.SetAngularDamping2(obj.ptr, ang_damping); +} -public override float GetAngularDamping(BulletBody obj); +public override float GetLinearDamping(BulletBody obj) +{ + return BSAPICPP.GetLinearDamping2(obj.ptr); +} -public override float GetLinearSleepingThreshold(BulletBody obj); +public override float GetAngularDamping(BulletBody obj) +{ + return BSAPICPP.GetAngularDamping2(obj.ptr); +} +public override float GetLinearSleepingThreshold(BulletBody obj) +{ + return BSAPICPP.GetLinearSleepingThreshold2(obj.ptr); +} -public override void ApplyDamping(BulletBody obj, float timeStep); +public override void ApplyDamping(BulletBody obj, float timeStep) +{ + BSAPICPP.ApplyDamping2(obj.ptr, timeStep); +} -public override void SetMassProps(BulletBody obj, float mass, Vector3 inertia); +public override void SetMassProps(BulletBody obj, float mass, Vector3 inertia) +{ + BSAPICPP.SetMassProps2(obj.ptr, mass, inertia); +} -public override Vector3 GetLinearFactor(BulletBody obj); +public override Vector3 GetLinearFactor(BulletBody obj) +{ + return BSAPICPP.GetLinearFactor2(obj.ptr); +} -public override void SetLinearFactor(BulletBody obj, Vector3 factor); +public override void SetLinearFactor(BulletBody obj, Vector3 factor) +{ + BSAPICPP.SetLinearFactor2(obj.ptr, factor); +} -public override void SetCenterOfMassByPosRot(BulletBody obj, Vector3 pos, Quaternion rot); +public override void SetCenterOfMassByPosRot(BulletBody obj, Vector3 pos, Quaternion rot) +{ + BSAPICPP.SetCenterOfMassByPosRot2(obj.ptr, pos, rot); +} // Add a force to the object as if its mass is one. -public override void ApplyCentralForce(BulletBody obj, Vector3 force); +public override void ApplyCentralForce(BulletBody obj, Vector3 force) +{ + BSAPICPP.ApplyCentralForce2(obj.ptr, 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 void SetObjectForce(BulletBody obj, Vector3 force) +{ + BSAPICPP.SetObjectForce2(obj.ptr, force); +} -public override Vector3 GetTotalForce(BulletBody obj); +public override Vector3 GetTotalForce(BulletBody obj) +{ + return BSAPICPP.GetTotalForce2(obj.ptr); +} -public override Vector3 GetTotalTorque(BulletBody obj); +public override Vector3 GetTotalTorque(BulletBody obj) +{ + return BSAPICPP.GetTotalTorque2(obj.ptr); +} -public override Vector3 GetInvInertiaDiagLocal(BulletBody obj); +public override Vector3 GetInvInertiaDiagLocal(BulletBody obj) +{ + return BSAPICPP.GetInvInertiaDiagLocal2(obj.ptr); +} -public override void SetInvInertiaDiagLocal(BulletBody obj, Vector3 inert); +public override void SetInvInertiaDiagLocal(BulletBody obj, Vector3 inert) +{ + BSAPICPP.SetInvInertiaDiagLocal2(obj.ptr, inert); +} -public override void SetSleepingThresholds(BulletBody obj, float lin_threshold, float ang_threshold); +public override void SetSleepingThresholds(BulletBody obj, float lin_threshold, float ang_threshold) +{ + BSAPICPP.SetSleepingThresholds2(obj.ptr, lin_threshold, ang_threshold); +} -public override void ApplyTorque(BulletBody obj, Vector3 torque); +public override void ApplyTorque(BulletBody obj, Vector3 torque) +{ + BSAPICPP.ApplyTorque2(obj.ptr, torque); +} // Apply force at the given point. Will add torque to the object. -public override void ApplyForce(BulletBody obj, Vector3 force, Vector3 pos); +public override void ApplyForce(BulletBody obj, Vector3 force, Vector3 pos) +{ + BSAPICPP.ApplyForce2(obj.ptr, force, pos); +} // Apply impulse to the object. Same as "ApplycentralForce" but force scaled by object's mass. -public override void ApplyCentralImpulse(BulletBody obj, Vector3 imp); +public override void ApplyCentralImpulse(BulletBody obj, Vector3 imp) +{ + BSAPICPP.ApplyCentralImpulse2(obj.ptr, imp); +} // Apply impulse to the object's torque. Force is scaled by object's mass. -public override void ApplyTorqueImpulse(BulletBody obj, Vector3 imp); +public override void ApplyTorqueImpulse(BulletBody obj, Vector3 imp) +{ + BSAPICPP.ApplyTorqueImpulse2(obj.ptr, 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 ApplyImpulse(BulletBody obj, Vector3 imp, Vector3 pos) +{ + BSAPICPP.ApplyImpulse2(obj.ptr, imp, pos); +} -public override void ClearForces(BulletBody obj); +public override void ClearForces(BulletBody obj) +{ + BSAPICPP.ClearForces2(obj.ptr); +} -public override void ClearAllForces(BulletBody obj); +public override void ClearAllForces(BulletBody obj) +{ + BSAPICPP.ClearAllForces2(obj.ptr); +} -public override void UpdateInertiaTensor(BulletBody obj); +public override void UpdateInertiaTensor(BulletBody obj) +{ + BSAPICPP.UpdateInertiaTensor2(obj.ptr); +} -public override Vector3 GetLinearVelocity(BulletBody obj); +public override Vector3 GetLinearVelocity(BulletBody obj) +{ + return BSAPICPP.GetLinearVelocity2(obj.ptr); +} -public override Vector3 GetAngularVelocity(BulletBody obj); +public override Vector3 GetAngularVelocity(BulletBody obj) +{ + return BSAPICPP.GetAngularVelocity2(obj.ptr); +} -public override void SetLinearVelocity(BulletBody obj, Vector3 val); +public override void SetLinearVelocity(BulletBody obj, Vector3 vel) +{ + BSAPICPP.SetLinearVelocity2(obj.ptr, vel); +} -public override void SetAngularVelocity(BulletBody obj, Vector3 angularVelocity); +public override void SetAngularVelocity(BulletBody obj, Vector3 angularVelocity) +{ + BSAPICPP.SetAngularVelocity2(obj.ptr, angularVelocity); +} -public override Vector3 GetVelocityInLocalPoint(BulletBody obj, Vector3 pos); +public override Vector3 GetVelocityInLocalPoint(BulletBody obj, Vector3 pos) +{ + return BSAPICPP.GetVelocityInLocalPoint2(obj.ptr, pos); +} -public override void Translate(BulletBody obj, Vector3 trans); +public override void Translate(BulletBody obj, Vector3 trans) +{ + BSAPICPP.Translate2(obj.ptr, trans); +} -public override void UpdateDeactivation(BulletBody obj, float timeStep); +public override void UpdateDeactivation(BulletBody obj, float timeStep) +{ + BSAPICPP.UpdateDeactivation2(obj.ptr, timeStep); +} -public override bool WantsSleeping(BulletBody obj); +public override bool WantsSleeping(BulletBody obj) +{ + return BSAPICPP.WantsSleeping2(obj.ptr); +} -public override void SetAngularFactor(BulletBody obj, float factor); +public override void SetAngularFactor(BulletBody obj, float factor) +{ + BSAPICPP.SetAngularFactor2(obj.ptr, factor); +} -public override void SetAngularFactorV(BulletBody obj, Vector3 factor); +public override void SetAngularFactorV(BulletBody obj, Vector3 factor) +{ + BSAPICPP.SetAngularFactorV2(obj.ptr, factor); +} -public override Vector3 GetAngularFactor(BulletBody obj); +public override Vector3 GetAngularFactor(BulletBody obj) +{ + return BSAPICPP.GetAngularFactor2(obj.ptr); +} -public override bool IsInWorld(BulletBody obj); +public override bool IsInWorld(BulletBody obj) +{ + return BSAPICPP.IsInWorld2(obj.ptr); +} -public override void AddConstraintRef(BulletBody obj, BulletConstraint constrain); +public override void AddConstraintRef(BulletBody obj, BulletConstraint constrain) +{ + BSAPICPP.AddConstraintRef2(obj.ptr, constrain.ptr); +} -public override void RemoveConstraintRef(BulletBody obj, BulletConstraint constrain); +public override void RemoveConstraintRef(BulletBody obj, BulletConstraint constrain) +{ + BSAPICPP.RemoveConstraintRef2(obj.ptr, constrain.ptr); +} -public override BulletConstraint GetConstraintRef(BulletBody obj, int index); +public override BulletConstraint GetConstraintRef(BulletBody obj, int index) +{ + return new BulletConstraint(BSAPICPP.GetConstraintRef2(obj.ptr, index)); +} -public override int GetNumConstraintRefs(BulletBody obj); +public override int GetNumConstraintRefs(BulletBody obj) +{ + return BSAPICPP.GetNumConstraintRefs2(obj.ptr); +} -public override bool SetCollisionGroupMask(BulletBody body, uint filter, uint mask); +public override bool SetCollisionGroupMask(BulletBody body, uint filter, uint mask) +{ + return BSAPICPP.SetCollisionGroupMask2(body.ptr, filter, mask); +} // ===================================================================================== // btCollisionShape entries -public override float GetAngularMotionDisc(BulletShape shape); +public override float GetAngularMotionDisc(BulletShape shape) +{ + return BSAPICPP.GetAngularMotionDisc2(shape.ptr); +} -public override float GetContactBreakingThreshold(BulletShape shape, float defaultFactor); +public override float GetContactBreakingThreshold(BulletShape shape, float defaultFactor) +{ + return BSAPICPP.GetContactBreakingThreshold2(shape.ptr, defaultFactor); +} -public override bool IsPolyhedral(BulletShape shape); +public override bool IsPolyhedral(BulletShape shape) +{ + return BSAPICPP.IsPolyhedral2(shape.ptr); +} -public override bool IsConvex2d(BulletShape shape); +public override bool IsConvex2d(BulletShape shape) +{ + return BSAPICPP.IsConvex2d2(shape.ptr); +} -public override bool IsConvex(BulletShape shape); +public override bool IsConvex(BulletShape shape) +{ + return BSAPICPP.IsConvex2(shape.ptr); +} -public override bool IsNonMoving(BulletShape shape); +public override bool IsNonMoving(BulletShape shape) +{ + return BSAPICPP.IsNonMoving2(shape.ptr); +} -public override bool IsConcave(BulletShape shape); +public override bool IsConcave(BulletShape shape) +{ + return BSAPICPP.IsConcave2(shape.ptr); +} -public override bool IsCompound(BulletShape shape); +public override bool IsCompound(BulletShape shape) +{ + return BSAPICPP.IsCompound2(shape.ptr); +} -public override bool IsSoftBody(BulletShape shape); +public override bool IsSoftBody(BulletShape shape) +{ + return BSAPICPP.IsSoftBody2(shape.ptr); +} -public override bool IsInfinite(BulletShape shape); +public override bool IsInfinite(BulletShape shape) +{ + return BSAPICPP.IsInfinite2(shape.ptr); +} -public override void SetLocalScaling(BulletShape shape, Vector3 scale); +public override void SetLocalScaling(BulletShape shape, Vector3 scale) +{ + BSAPICPP.SetLocalScaling2(shape.ptr, scale); +} -public override Vector3 GetLocalScaling(BulletShape shape); +public override Vector3 GetLocalScaling(BulletShape shape) +{ + return BSAPICPP.GetLocalScaling2(shape.ptr); +} -public override Vector3 CalculateLocalInertia(BulletShape shape, float mass); +public override Vector3 CalculateLocalInertia(BulletShape shape, float mass) +{ + return BSAPICPP.CalculateLocalInertia2(shape.ptr, mass); +} -public override int GetShapeType(BulletShape shape); +public override int GetShapeType(BulletShape shape) +{ + return BSAPICPP.GetShapeType2(shape.ptr); +} -public override void SetMargin(BulletShape shape, float val); +public override void SetMargin(BulletShape shape, float val) +{ + BSAPICPP.SetMargin2(shape.ptr, val); +} -public override float GetMargin(BulletShape shape); - */ +public override float GetMargin(BulletShape shape) +{ + return BSAPICPP.GetMargin2(shape.ptr); +} static class BSAPICPP { +[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] +public static extern bool PushUpdate2(IntPtr obj); + // ===================================================================================== // Mesh, hull, shape and body creation helper routines [DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] @@ -1029,55 +1218,6 @@ public static extern IntPtr GetUserPointer2(IntPtr obj); [DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] public static extern void SetUserPointer2(IntPtr obj, IntPtr val); -} -} - -// =============================================================================== -// =============================================================================== -// =============================================================================== -// =============================================================================== -// =============================================================================== -// =============================================================================== -// =============================================================================== -// =============================================================================== -// =============================================================================== -// =============================================================================== -// =============================================================================== -// =============================================================================== -// =============================================================================== -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); - // ===================================================================================== // btRigidBody entries [DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] @@ -1291,6 +1431,52 @@ public static extern void SetMargin2(IntPtr shape, float val); [DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] public static extern float GetMargin2(IntPtr shape); +} +} + +// =============================================================================== +// =============================================================================== +// =============================================================================== +// =============================================================================== +// =============================================================================== +// =============================================================================== +// =============================================================================== +// =============================================================================== +// =============================================================================== +// =============================================================================== +// =============================================================================== +// =============================================================================== +// =============================================================================== +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); + // ===================================================================================== // Debugging [DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity] diff --git a/OpenSim/Region/Physics/BulletSPlugin/BSApiTemplate.cs b/OpenSim/Region/Physics/BulletSPlugin/BSApiTemplate.cs new file mode 100644 index 0000000..fbf362d --- /dev/null +++ b/OpenSim/Region/Physics/BulletSPlugin/BSApiTemplate.cs @@ -0,0 +1,664 @@ +/* + * 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 { + + // Constraint type values as defined by Bullet +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 +} + +// =============================================================================== +[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, + // following defined by BulletSim + SHAPE_GROUNDPLANE = 20, + SHAPE_TERRAIN = 21, + SHAPE_COMPOUND = 22, + SHAPE_HEIGHTMAP = 23, + SHAPE_AVATAR = 24, +}; + +// The native shapes have predefined shape hash keys +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 uint 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; // true of things bump into this + public float Static; // true if a static object. Otherwise gravity, etc. + public float Solid; // true if object cannot be passed through + public Vector3 Size; + + // note that bools are passed as floats since bool size changes by language and architecture + public const float numericTrue = 1f; + public const float numericFalse = 0f; +} +[StructLayout(LayoutKind.Sequential)] +public struct SweepHit +{ + public uint ID; + public float Fraction; + public Vector3 Normal; + public Vector3 Point; +} +[StructLayout(LayoutKind.Sequential)] +public struct RaycastHit +{ + public uint ID; + public float Fraction; + public Vector3 Normal; +} +[StructLayout(LayoutKind.Sequential)] +public struct CollisionDesc +{ + public uint aID; + public uint bID; + public Vector3 point; + public Vector3 normal; +} +[StructLayout(LayoutKind.Sequential)] +public struct EntityProperties +{ + public uint ID; + public Vector3 Position; + public Quaternion Rotation; + public Vector3 Velocity; + public Vector3 Acceleration; + public Vector3 RotationalVelocity; +} + +// Format of this structure must match the definition in the C++ code +// NOTE: adding the X causes compile breaks if used. These are unused symbols +// that can be removed from both here and the unmanaged definition of this structure. +[StructLayout(LayoutKind.Sequential)] +public struct ConfigurationParameters +{ + public float defaultFriction; + public float defaultDensity; + public float defaultRestitution; + public float collisionMargin; + public float gravity; + + public float XlinearDamping; + public float XangularDamping; + public float XdeactivationTime; + public float XlinearSleepingThreshold; + public float XangularSleepingThreshold; + public float XccdMotionThreshold; + public float XccdSweptSphereRadius; + public float XcontactProcessingThreshold; + + public float XterrainImplementation; + public float XterrainFriction; + public float XterrainHitFraction; + public float XterrainRestitution; + public float XterrainCollisionMargin; + + public float XavatarFriction; + public float XavatarStandingFriction; + public float XavatarDensity; + public float XavatarRestitution; + public float XavatarCapsuleWidth; + public float XavatarCapsuleDepth; + public float XavatarCapsuleHeight; + public float XavatarContactProcessingThreshold; + + public float XvehicleAngularDamping; + + 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 XlinksetImplementation; + public float XlinkConstraintUseFrameOffset; + public float XlinkConstraintEnableTransMotor; + public float XlinkConstraintTransMotorMaxVel; + public float XlinkConstraintTransMotorMaxForce; + public float XlinkConstraintERP; + public float XlinkConstraintCFM; + public float XlinkConstraintSolverIterations; + + public float physicsLoggingFrames; + + public const float numericTrue = 1f; + public const float numericFalse = 0f; +} + + +// The states a bullet collision object can have +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, +} + +// Values used by Bullet and BulletSim to control object properties. +// Bullet's "CollisionFlags" has more to do with operations on the +// object (if collisions happen, if gravity effects it, ...). +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, + // Following used by BulletSim to control collisions and updates + BS_SUBSCRIBE_COLLISION_EVENTS = 1 << 10, + BS_FLOATS_ON_WATER = 1 << 11, + BS_VEHICLE_COLLISIONS = 1 << 12, + BS_NONE = 0, + BS_ALL = 0xFFFFFFFF +}; + +// Values f collisions groups and masks +public enum CollisionFilterGroups : uint +{ + // Don't use the bit definitions!! Define the use in a + // filter/mask definition below. This way collision interactions + // are more easily found and debugged. + BNoneGroup = 0, + BDefaultGroup = 1 << 0, // 0001 + BStaticGroup = 1 << 1, // 0002 + BKinematicGroup = 1 << 2, // 0004 + BDebrisGroup = 1 << 3, // 0008 + BSensorTrigger = 1 << 4, // 0010 + BCharacterGroup = 1 << 5, // 0020 + BAllGroup = 0x000FFFFF, + // Filter groups defined by BulletSim + BGroundPlaneGroup = 1 << 10, // 0400 + BTerrainGroup = 1 << 11, // 0800 + BRaycastGroup = 1 << 12, // 1000 + BSolidGroup = 1 << 13, // 2000 + // BLinksetGroup = xx // a linkset proper is either static or dynamic + BLinksetChildGroup = 1 << 14, // 4000 +}; + +// CFM controls the 'hardness' of the constraint. 0=fixed, 0..1=violatable. Default=0 +// ERP controls amount of correction per tick. Usable range=0.1..0.8. Default=0.2. +public enum ConstraintParams : int +{ + BT_CONSTRAINT_ERP = 1, // this one is not used in Bullet as of 20120730 + 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, // these last three added by BulletSim so we don't have to do zillions of calls + AXIS_ANGULAR_ALL, + AXIS_ALL +}; + +public abstract class BSAPITemplate +{ + /* +// Initialization and simulation +public abstract BulletWorld Initialize(Vector3 maxPosition, IntPtr parms, + int maxCollisions, IntPtr collisionArray, + int maxUpdates, IntPtr updateArray + ); + +public abstract bool UpdateParameter(BulletWorld world, uint localID, String parm, float value); + +public abstract void SetHeightMap(BulletWorld world, float[] heightmap); + +public abstract void Shutdown(BulletWorld sim); + +public abstract int PhysicsStep(BulletWorld world, float timeStep, int maxSubSteps, float fixedTimeStep, + out int updatedEntityCount, + out IntPtr updatedEntitiesPtr, + out int collidersCount, + out IntPtr collidersPtr); + + */ +public abstract bool PushUpdate(BulletBody obj); + +// ===================================================================================== +// Mesh, hull, shape and body creation helper routines +public abstract BulletShape CreateMeshShape(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); + +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 RecalculateCompoundShapeLocalAabb(BulletShape cShape); + +public abstract BulletShape DuplicateCollisionShape(BulletWorld sim, BulletShape srcShape, uint id); + +public abstract BulletBody CreateBodyFromShapeAndInfo(BulletWorld sim, BulletShape shape, uint id, IntPtr constructionInfo); + +public abstract bool DeleteCollisionShape(BulletWorld world, BulletShape shape); + +public abstract int GetBodyType(BulletBody obj); + +public abstract BulletBody CreateBodyFromShape(BulletWorld sim, BulletShape shape, uint id, Vector3 pos, Quaternion rot); + +public abstract BulletBody CreateBodyWithDefaultMotionState(BulletShape shape, uint id, Vector3 pos, Quaternion rot); + +public abstract BulletBody CreateGhostFromShape(BulletWorld sim, BulletShape shape, uint id, Vector3 pos, Quaternion rot); + +public abstract IntPtr AllocateBodyInfo(BulletBody obj); + +public abstract void ReleaseBodyInfo(IntPtr obj); + +public abstract void DestroyObject(BulletWorld sim, BulletBody obj); + +// ===================================================================================== +// Terrain creation and helper routines +public abstract IntPtr CreateHeightMapInfo(BulletWorld sim, uint id, Vector3 minCoords, Vector3 maxCoords, + float[] heightMap, float collisionMargin); + +public abstract IntPtr FillHeightMapInfo(BulletWorld sim, IntPtr mapInfo, uint id, Vector3 minCoords, Vector3 maxCoords, + float[] heightMap, float collisionMargin); + +public abstract bool ReleaseHeightMapInfo(IntPtr heightMapInfo); + +public abstract BulletShape CreateGroundPlaneShape(uint id, float height, float collisionMargin); + +public abstract BulletShape CreateTerrainShape(IntPtr mapInfo); + +// ===================================================================================== +// Constraint creation and helper routines +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 CreateHingeConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2, + Vector3 pivotinA, Vector3 pivotinB, + Vector3 axisInA, Vector3 axisInB, + bool useLinearReferenceFrameA, 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 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); + +// ===================================================================================== +// btCollisionWorld entries +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); + +// ===================================================================================== +// btDynamicsWorld entries +public abstract bool AddObjectToWorld(BulletWorld world, BulletBody obj); + +public abstract bool RemoveObjectFromWorld(BulletWorld world, BulletBody obj); + +public abstract bool AddConstraintToWorld(BulletWorld world, BulletConstraint constrain, bool disableCollisionsBetweenLinkedObjects); + +public abstract bool RemoveConstraintFromWorld(BulletWorld world, BulletConstraint constrain); +// ===================================================================================== +// btCollisionObject entries +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 IntPtr GetBroadphaseHandle(BulletBody obj); + +public abstract void SetBroadphaseHandle(BulletBody obj, IntPtr handle); + +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); + +// ===================================================================================== +// btRigidBody entries +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); + +// Add a force to the object as if its mass is one. +public abstract void ApplyCentralForce(BulletBody obj, Vector3 force); + +// Set the force being applied to the object as if its mass is one. +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); + +// Apply force at the given point. Will add torque to the object. +public abstract void ApplyForce(BulletBody obj, Vector3 force, Vector3 pos); + +// Apply impulse to the object. Same as "ApplycentralForce" but force scaled by object's mass. +public abstract void ApplyCentralImpulse(BulletBody obj, Vector3 imp); + +// Apply impulse to the object's torque. Force is scaled by object's mass. +public abstract 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 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(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, uint filter, uint mask); + +// ===================================================================================== +// btCollisionShape entries + +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); + +}; +} diff --git a/OpenSim/Region/Physics/BulletSPlugin/BSCharacter.cs b/OpenSim/Region/Physics/BulletSPlugin/BSCharacter.cs index 328164b..103d8fc 100644 --- a/OpenSim/Region/Physics/BulletSPlugin/BSCharacter.cs +++ b/OpenSim/Region/Physics/BulletSPlugin/BSCharacter.cs @@ -153,8 +153,8 @@ public sealed class BSCharacter : BSPhysObject Flying = _flying; PhysicsScene.PE.SetRestitution(PhysBody, BSParam.AvatarRestitution); - BulletSimAPI.SetMargin2(PhysShape.ptr, PhysicsScene.Params.collisionMargin); - BulletSimAPI.SetLocalScaling2(PhysShape.ptr, Scale); + PhysicsScene.PE.SetMargin(PhysShape, PhysicsScene.Params.collisionMargin); + PhysicsScene.PE.SetLocalScaling(PhysShape, Scale); PhysicsScene.PE.SetContactProcessingThreshold(PhysBody, BSParam.ContactProcessingThreshold); if (BSParam.CcdMotionThreshold > 0f) { @@ -165,19 +165,19 @@ public sealed class BSCharacter : BSPhysObject UpdatePhysicalMassProperties(RawMass, false); // Make so capsule does not fall over - BulletSimAPI.SetAngularFactorV2(PhysBody.ptr, OMV.Vector3.Zero); + PhysicsScene.PE.SetAngularFactorV(PhysBody, OMV.Vector3.Zero); PhysicsScene.PE.AddToCollisionFlags(PhysBody, CollisionFlags.CF_CHARACTER_OBJECT); PhysicsScene.PE.AddObjectToWorld(PhysicsScene.World, PhysBody); - // PhysicsScene.PE.ForceActivationState(PhysBody, ActivationState.ACTIVE_TAG); + // PhysicsScene.PE.ForceActivationState(PhysBody, ActivationState.ACTIVE_TAG); PhysicsScene.PE.ForceActivationState(PhysBody, ActivationState.DISABLE_DEACTIVATION); PhysicsScene.PE.UpdateSingleAabb(PhysicsScene.World, PhysBody); // Do this after the object has been added to the world PhysBody.collisionType = CollisionType.Avatar; - PhysBody.ApplyCollisionMask(); + PhysBody.ApplyCollisionMask(PhysicsScene); } // The avatar's movement is controlled by this motor that speeds up and slows down @@ -265,10 +265,10 @@ public sealed class BSCharacter : BSPhysObject { if (PhysBody.HasPhysicalBody && PhysShape.HasPhysicalShape) { - BulletSimAPI.SetLocalScaling2(PhysShape.ptr, Scale); + PhysicsScene.PE.SetLocalScaling(PhysShape, Scale); UpdatePhysicalMassProperties(RawMass, true); // Make sure this change appears as a property update event - BulletSimAPI.PushUpdate2(PhysBody.ptr); + PhysicsScene.PE.PushUpdate(PhysBody); } }); @@ -309,7 +309,7 @@ public sealed class BSCharacter : BSPhysObject PhysicsScene.TaintedObject(inTaintTime, "BSCharacter.ZeroMotion", delegate() { if (PhysBody.HasPhysicalBody) - BulletSimAPI.ClearAllForces2(PhysBody.ptr); + PhysicsScene.PE.ClearAllForces(PhysBody); }); } public override void ZeroAngularMotion(bool inTaintTime) @@ -321,9 +321,9 @@ public sealed class BSCharacter : BSPhysObject if (PhysBody.HasPhysicalBody) { PhysicsScene.PE.SetInterpolationAngularVelocity(PhysBody, OMV.Vector3.Zero); - BulletSimAPI.SetAngularVelocity2(PhysBody.ptr, OMV.Vector3.Zero); + PhysicsScene.PE.SetAngularVelocity(PhysBody, OMV.Vector3.Zero); // The next also get rid of applied linear force but the linear velocity is untouched. - BulletSimAPI.ClearForces2(PhysBody.ptr); + PhysicsScene.PE.ClearForces(PhysBody); } }); } @@ -339,7 +339,7 @@ public sealed class BSCharacter : BSPhysObject public override OMV.Vector3 Position { get { // Don't refetch the position because this function is called a zillion times - // _position = BulletSimAPI.GetObjectPosition2(Scene.World.ptr, LocalID); + // _position = PhysicsScene.PE.GetObjectPosition(Scene.World, LocalID); return _position; } set { @@ -433,8 +433,8 @@ public sealed class BSCharacter : BSPhysObject } public override void UpdatePhysicalMassProperties(float physMass, bool inWorld) { - OMV.Vector3 localInertia = BulletSimAPI.CalculateLocalInertia2(PhysShape.ptr, physMass); - BulletSimAPI.SetMassProps2(PhysBody.ptr, physMass, localInertia); + OMV.Vector3 localInertia = PhysicsScene.PE.CalculateLocalInertia(PhysShape, physMass); + PhysicsScene.PE.SetMassProps(PhysBody, physMass, localInertia); } public override OMV.Vector3 Force { @@ -446,7 +446,7 @@ public sealed class BSCharacter : BSPhysObject { DetailLog("{0},BSCharacter.setForce,taint,force={1}", LocalID, _force); if (PhysBody.HasPhysicalBody) - BulletSimAPI.SetObjectForce2(PhysBody.ptr, _force); + PhysicsScene.PE.SetObjectForce(PhysBody, _force); }); } } @@ -533,7 +533,7 @@ public sealed class BSCharacter : BSPhysObject } } - BulletSimAPI.SetLinearVelocity2(PhysBody.ptr, _velocity); + PhysicsScene.PE.SetLinearVelocity(PhysBody, _velocity); PhysicsScene.PE.Activate(PhysBody, true); } } @@ -676,7 +676,7 @@ public sealed class BSCharacter : BSPhysObject // Buoyancy is faked by changing the gravity applied to the object float grav = PhysicsScene.Params.gravity * (1f - _buoyancy); if (PhysBody.HasPhysicalBody) - BulletSimAPI.SetGravity2(PhysBody.ptr, new OMV.Vector3(0f, 0f, grav)); + PhysicsScene.PE.SetGravity(PhysBody, new OMV.Vector3(0f, 0f, grav)); } } @@ -737,7 +737,7 @@ public sealed class BSCharacter : BSPhysObject // DetailLog("{0},BSCharacter.addForce,taint,force={1}", LocalID, addForce); if (PhysBody.HasPhysicalBody) { - BulletSimAPI.ApplyCentralForce2(PhysBody.ptr, addForce); + PhysicsScene.PE.ApplyCentralForce(PhysBody, addForce); } }); } diff --git a/OpenSim/Region/Physics/BulletSPlugin/BSDynamics.cs b/OpenSim/Region/Physics/BulletSPlugin/BSDynamics.cs index 5d70ef7..e4e3edc 100644 --- a/OpenSim/Region/Physics/BulletSPlugin/BSDynamics.cs +++ b/OpenSim/Region/Physics/BulletSPlugin/BSDynamics.cs @@ -564,17 +564,17 @@ namespace OpenSim.Region.Physics.BulletSPlugin // TODO: possibly set AngularFactor and LinearFactor for the type of vehicle. // Maybe compute linear and angular factor and damping from params. float angularDamping = BSParam.VehicleAngularDamping; - BulletSimAPI.SetAngularDamping2(Prim.PhysBody.ptr, angularDamping); + PhysicsScene.PE.SetAngularDamping(Prim.PhysBody, angularDamping); // Vehicles report collision events so we know when it's on the ground PhysicsScene.PE.AddToCollisionFlags(Prim.PhysBody, CollisionFlags.BS_VEHICLE_COLLISIONS); - Vector3 localInertia = BulletSimAPI.CalculateLocalInertia2(Prim.PhysShape.ptr, m_vehicleMass); - BulletSimAPI.SetMassProps2(Prim.PhysBody.ptr, m_vehicleMass, localInertia); - BulletSimAPI.UpdateInertiaTensor2(Prim.PhysBody.ptr); + Vector3 localInertia = PhysicsScene.PE.CalculateLocalInertia(Prim.PhysShape, m_vehicleMass); + PhysicsScene.PE.SetMassProps(Prim.PhysBody, m_vehicleMass, localInertia); + PhysicsScene.PE.UpdateInertiaTensor(Prim.PhysBody); Vector3 grav = PhysicsScene.DefaultGravity * (1f - Prim.Buoyancy); - BulletSimAPI.SetGravity2(Prim.PhysBody.ptr, grav); + PhysicsScene.PE.SetGravity(Prim.PhysBody, grav); VDetailLog("{0},BSDynamics.Refresh,mass={1},frict={2},inert={3},aDamp={4}", Prim.LocalID, m_vehicleMass, friction, localInertia, angularDamping); @@ -669,7 +669,7 @@ namespace OpenSim.Region.Physics.BulletSPlugin // If we set one of the values (ie, the physics engine didn't do it) we must force // an UpdateProperties event to send the changes up to the simulator. - BulletSimAPI.PushUpdate2(Prim.PhysBody.ptr); + PhysicsScene.PE.PushUpdate(Prim.PhysBody); } m_knownChanged = 0; } diff --git a/OpenSim/Region/Physics/BulletSPlugin/BSLinksetCompound.cs b/OpenSim/Region/Physics/BulletSPlugin/BSLinksetCompound.cs index 143c60c..bd03d31 100755 --- a/OpenSim/Region/Physics/BulletSPlugin/BSLinksetCompound.cs +++ b/OpenSim/Region/Physics/BulletSPlugin/BSLinksetCompound.cs @@ -387,11 +387,6 @@ public sealed class BSLinksetCompound : BSLinkset } PhysicsScene.PE.RecalculateCompoundShapeLocalAabb(LinksetRoot.PhysShape); - - // DEBUG: see of inter-linkset collisions are causing problems for constraint linksets. - // BulletSimAPI.SetCollisionFilterMask2(LinksetRoot.BSBody.ptr, - // (uint)CollisionFilterGroups.LinksetFilter, (uint)CollisionFilterGroups.LinksetMask); - } } } \ No newline at end of file diff --git a/OpenSim/Region/Physics/BulletSPlugin/BSLinksetConstraints.cs b/OpenSim/Region/Physics/BulletSPlugin/BSLinksetConstraints.cs index 629bc72..d0b2a56 100755 --- a/OpenSim/Region/Physics/BulletSPlugin/BSLinksetConstraints.cs +++ b/OpenSim/Region/Physics/BulletSPlugin/BSLinksetConstraints.cs @@ -259,7 +259,7 @@ public sealed class BSLinksetConstraints : BSLinkset if (PhysicsScene.Constraints.RemoveAndDestroyConstraint(rootPrim.PhysBody, childPrim.PhysBody)) { // Make the child refresh its location - BulletSimAPI.PushUpdate2(childPrim.PhysBody.ptr); + PhysicsScene.PE.PushUpdate(childPrim.PhysBody); ret = true; } @@ -286,9 +286,6 @@ public sealed class BSLinksetConstraints : BSLinkset float linksetMass = LinksetMass; LinksetRoot.UpdatePhysicalMassProperties(linksetMass, true); - // DEBUG: see of inter-linkset collisions are causing problems - // BulletSimAPI.SetCollisionFilterMask2(LinksetRoot.BSBody.ptr, - // (uint)CollisionFilterGroups.LinksetFilter, (uint)CollisionFilterGroups.LinksetMask); DetailLog("{0},BSLinksetConstraint.RecomputeLinksetConstraints,set,rBody={1},linksetMass={2}", LinksetRoot.LocalID, LinksetRoot.PhysBody.AddrString, linksetMass); @@ -307,11 +304,7 @@ public sealed class BSLinksetConstraints : BSLinkset } constrain.RecomputeConstraintVariables(linksetMass); - // DEBUG: see of inter-linkset collisions are causing problems - // BulletSimAPI.SetCollisionFilterMask2(child.BSBody.ptr, - // (uint)CollisionFilterGroups.LinksetFilter, (uint)CollisionFilterGroups.LinksetMask); - - // BulletSimAPI.DumpConstraint2(PhysicsScene.World.ptr, constrain.Constraint.ptr); // DEBUG DEBUG + // PhysicsScene.PE.DumpConstraint(PhysicsScene.World, constrain.Constraint); // DEBUG DEBUG } } diff --git a/OpenSim/Region/Physics/BulletSPlugin/BSParam.cs b/OpenSim/Region/Physics/BulletSPlugin/BSParam.cs index c6c2946..339722e 100755 --- a/OpenSim/Region/Physics/BulletSPlugin/BSParam.cs +++ b/OpenSim/Region/Physics/BulletSPlugin/BSParam.cs @@ -280,7 +280,7 @@ public static class BSParam (s,cf,p,v) => { s.UnmanagedParams[0].gravity = cf.GetFloat(p, v); }, (s) => { return s.UnmanagedParams[0].gravity; }, (s,p,l,v) => { s.UpdateParameterObject((x)=>{s.UnmanagedParams[0].gravity=x;}, p, PhysParameterEntry.APPLY_TO_NONE, v); }, - (s,o,v) => { BulletSimAPI.SetGravity2(s.World.ptr, new Vector3(0f,0f,v)); } ), + (s,o,v) => { s.PE.SetGravity(o.PhysBody, new Vector3(0f,0f,v)); } ), new ParameterDefn("LinearDamping", "Factor to damp linear movement per second (0.0 - 1.0)", @@ -288,13 +288,13 @@ public static class BSParam (s,cf,p,v) => { LinearDamping = cf.GetFloat(p, v); }, (s) => { return LinearDamping; }, (s,p,l,v) => { s.UpdateParameterObject((x)=>{LinearDamping=x;}, p, l, v); }, - (s,o,v) => { BulletSimAPI.SetDamping2(o.PhysBody.ptr, v, AngularDamping); } ), + (s,o,v) => { s.PE.SetDamping(o.PhysBody, v, AngularDamping); } ), new ParameterDefn("AngularDamping", "Factor to damp angular movement per second (0.0 - 1.0)", 0f, (s,cf,p,v) => { AngularDamping = cf.GetFloat(p, v); }, (s) => { return AngularDamping; }, (s,p,l,v) => { s.UpdateParameterObject((x)=>{AngularDamping=x;}, p, l, v); }, - (s,o,v) => { BulletSimAPI.SetDamping2(o.PhysBody.ptr, LinearDamping, v); } ), + (s,o,v) => { s.PE.SetDamping(o.PhysBody, LinearDamping, v); } ), new ParameterDefn("DeactivationTime", "Seconds before considering an object potentially static", 0.2f, (s,cf,p,v) => { DeactivationTime = cf.GetFloat(p, v); }, @@ -306,13 +306,13 @@ public static class BSParam (s,cf,p,v) => { LinearSleepingThreshold = cf.GetFloat(p, v); }, (s) => { return LinearSleepingThreshold; }, (s,p,l,v) => { s.UpdateParameterObject((x)=>{LinearSleepingThreshold=x;}, p, l, v); }, - (s,o,v) => { BulletSimAPI.SetSleepingThresholds2(o.PhysBody.ptr, v, v); } ), + (s,o,v) => { s.PE.SetSleepingThresholds(o.PhysBody, v, v); } ), new ParameterDefn("AngularSleepingThreshold", "Seconds to measure angular movement before considering static", 1.0f, (s,cf,p,v) => { AngularSleepingThreshold = cf.GetFloat(p, v); }, (s) => { return AngularSleepingThreshold; }, (s,p,l,v) => { s.UpdateParameterObject((x)=>{AngularSleepingThreshold=x;}, p, l, v); }, - (s,o,v) => { BulletSimAPI.SetSleepingThresholds2(o.PhysBody.ptr, v, v); } ), + (s,o,v) => { s.PE.SetSleepingThresholds(o.PhysBody, v, v); } ), new ParameterDefn("CcdMotionThreshold", "Continuious collision detection threshold (0 means no CCD)" , 0f, // set to zero to disable (s,cf,p,v) => { CcdMotionThreshold = cf.GetFloat(p, v); }, diff --git a/OpenSim/Region/Physics/BulletSPlugin/BSPrim.cs b/OpenSim/Region/Physics/BulletSPlugin/BSPrim.cs index 613606f..064ce3c 100644 --- a/OpenSim/Region/Physics/BulletSPlugin/BSPrim.cs +++ b/OpenSim/Region/Physics/BulletSPlugin/BSPrim.cs @@ -253,7 +253,7 @@ public sealed class BSPrim : BSPhysObject PhysicsScene.TaintedObject(inTaintTime, "BSPrim.ZeroMotion", delegate() { if (PhysBody.HasPhysicalBody) - BulletSimAPI.ClearAllForces2(PhysBody.ptr); + PhysicsScene.PE.ClearAllForces(PhysBody); }); } public override void ZeroAngularMotion(bool inTaintTime) @@ -266,7 +266,7 @@ public sealed class BSPrim : BSPhysObject if (PhysBody.HasPhysicalBody) { PhysicsScene.PE.SetInterpolationAngularVelocity(PhysBody, _rotationalVelocity); - BulletSimAPI.SetAngularVelocity2(PhysBody.ptr, _rotationalVelocity); + PhysicsScene.PE.SetAngularVelocity(PhysBody, _rotationalVelocity); } }); } @@ -292,7 +292,7 @@ public sealed class BSPrim : BSPhysObject */ // don't do the GetObjectPosition for root elements because this function is called a zillion times. - // _position = BulletSimAPI.GetObjectPosition2(PhysicsScene.World.ptr, BSBody.ptr); + // _position = PhysicsScene.PE.GetObjectPosition2(PhysicsScene.World, BSBody); return _position; } set { @@ -405,10 +405,10 @@ public sealed class BSPrim : BSPhysObject { if (IsStatic) { - BulletSimAPI.SetGravity2(PhysBody.ptr, PhysicsScene.DefaultGravity); + PhysicsScene.PE.SetGravity(PhysBody, PhysicsScene.DefaultGravity); Inertia = OMV.Vector3.Zero; - BulletSimAPI.SetMassProps2(PhysBody.ptr, 0f, Inertia); - BulletSimAPI.UpdateInertiaTensor2(PhysBody.ptr); + PhysicsScene.PE.SetMassProps(PhysBody, 0f, Inertia); + PhysicsScene.PE.UpdateInertiaTensor(PhysBody); } else { @@ -423,14 +423,14 @@ public sealed class BSPrim : BSPhysObject } // The computation of mass props requires gravity to be set on the object. - BulletSimAPI.SetGravity2(PhysBody.ptr, grav); + PhysicsScene.PE.SetGravity(PhysBody, grav); - Inertia = BulletSimAPI.CalculateLocalInertia2(PhysShape.ptr, physMass); - BulletSimAPI.SetMassProps2(PhysBody.ptr, physMass, Inertia); - BulletSimAPI.UpdateInertiaTensor2(PhysBody.ptr); + Inertia = PhysicsScene.PE.CalculateLocalInertia(PhysShape, physMass); + PhysicsScene.PE.SetMassProps(PhysBody, physMass, Inertia); + PhysicsScene.PE.UpdateInertiaTensor(PhysBody); // center of mass is at the zero of the object - // DEBUG DEBUG BulletSimAPI.SetCenterOfMassByPosRot2(PhysBody.ptr, ForcePosition, ForceOrientation); + // DEBUG DEBUG PhysicsScene.PE.SetCenterOfMassByPosRot(PhysBody, ForcePosition, ForceOrientation); DetailLog("{0},BSPrim.UpdateMassProperties,mass={1},localInertia={2},grav={3},inWorld={4}", LocalID, physMass, Inertia, grav, inWorld); if (inWorld) @@ -440,7 +440,7 @@ public sealed class BSPrim : BSPhysObject // Must set gravity after it has been added to the world because, for unknown reasons, // adding the object resets the object's gravity to world gravity - BulletSimAPI.SetGravity2(PhysBody.ptr, grav); + PhysicsScene.PE.SetGravity(PhysBody, grav); } } @@ -483,7 +483,7 @@ public sealed class BSPrim : BSPhysObject DetailLog("{0},BSPrim.setForce,preStep,force={1}", LocalID, _force); if (PhysBody.HasPhysicalBody) { - BulletSimAPI.ApplyCentralForce2(PhysBody.ptr, _force); + PhysicsScene.PE.ApplyCentralForce(PhysBody, _force); ActivateIfPhysical(false); } } @@ -583,7 +583,7 @@ public sealed class BSPrim : BSPhysObject _velocity = value; if (PhysBody.HasPhysicalBody) { - BulletSimAPI.SetLinearVelocity2(PhysBody.ptr, _velocity); + PhysicsScene.PE.SetLinearVelocity(PhysBody, _velocity); ActivateIfPhysical(false); } } @@ -809,7 +809,7 @@ public sealed class BSPrim : BSPhysObject PhysicsScene.PE.SetTranslation(PhysBody, _position, _orientation); // Center of mass is at the center of the object - // DEBUG DEBUG BulletSimAPI.SetCenterOfMassByPosRot2(Linkset.LinksetRoot.PhysBody, _position, _orientation); + // DEBUG DEBUG PhysicsScene.PE.SetCenterOfMassByPosRot(Linkset.LinksetRoot.PhysBody, _position, _orientation); // A dynamic object has mass UpdatePhysicalMassProperties(RawMass, false); @@ -822,9 +822,9 @@ public sealed class BSPrim : BSPhysObject } // Various values for simulation limits - BulletSimAPI.SetDamping2(PhysBody.ptr, BSParam.LinearDamping, BSParam.AngularDamping); + PhysicsScene.PE.SetDamping(PhysBody, BSParam.LinearDamping, BSParam.AngularDamping); PhysicsScene.PE.SetDeactivationTime(PhysBody, BSParam.DeactivationTime); - BulletSimAPI.SetSleepingThresholds2(PhysBody.ptr, BSParam.LinearSleepingThreshold, BSParam.AngularSleepingThreshold); + PhysicsScene.PE.SetSleepingThresholds(PhysBody, BSParam.LinearSleepingThreshold, BSParam.AngularSleepingThreshold); PhysicsScene.PE.SetContactProcessingThreshold(PhysBody, BSParam.ContactProcessingThreshold); // This collides like an object. @@ -901,10 +901,10 @@ public sealed class BSPrim : BSPhysObject // TODO: Fix this. Total kludge because adding object to world resets its gravity to default. // Replace this when the new AddObjectToWorld function is complete. - BulletSimAPI.SetGravity2(PhysBody.ptr, ComputeGravity()); + PhysicsScene.PE.SetGravity(PhysBody, ComputeGravity()); // Collision filter can be set only when the object is in the world - if (!PhysBody.ApplyCollisionMask()) + if (!PhysBody.ApplyCollisionMask(PhysicsScene)) { m_log.ErrorFormat("{0} Failed setting object collision mask: id={1}", LogHeader, LocalID); DetailLog("{0},BSPrim.UpdatePhysicalParameters,failedSetMaskGroup,cType={1}", LocalID, PhysBody.collisionType); @@ -969,7 +969,7 @@ public sealed class BSPrim : BSPhysObject _rotationalVelocity = value; if (PhysBody.HasPhysicalBody) { - BulletSimAPI.SetAngularVelocity2(PhysBody.ptr, _rotationalVelocity); + PhysicsScene.PE.SetAngularVelocity(PhysBody, _rotationalVelocity); ActivateIfPhysical(false); } } @@ -1061,7 +1061,7 @@ public sealed class BSPrim : BSPhysObject DetailLog("{0},BSPrim.addForce,taint,force={1}", LocalID, addForce); if (PhysBody.HasPhysicalBody) { - BulletSimAPI.ApplyCentralForce2(PhysBody.ptr, addForce); + PhysicsScene.PE.ApplyCentralForce(PhysBody, addForce); ActivateIfPhysical(false); } }); @@ -1085,7 +1085,7 @@ public sealed class BSPrim : BSPhysObject { if (PhysBody.HasPhysicalBody) { - BulletSimAPI.ApplyTorque2(PhysBody.ptr, angForce); + PhysicsScene.PE.ApplyTorque(PhysBody, angForce); ActivateIfPhysical(false); } }); @@ -1108,7 +1108,7 @@ public sealed class BSPrim : BSPhysObject { if (PhysBody.HasPhysicalBody) { - BulletSimAPI.ApplyTorqueImpulse2(PhysBody.ptr, applyImpulse); + PhysicsScene.PE.ApplyTorqueImpulse(PhysBody, applyImpulse); ActivateIfPhysical(false); } }); diff --git a/OpenSim/Region/Physics/BulletSPlugin/BSScene.cs b/OpenSim/Region/Physics/BulletSPlugin/BSScene.cs index bfc9df2..28c6680 100644 --- a/OpenSim/Region/Physics/BulletSPlugin/BSScene.cs +++ b/OpenSim/Region/Physics/BulletSPlugin/BSScene.cs @@ -51,7 +51,7 @@ public sealed class BSScene : PhysicsScene, IPhysicsParameters public string BulletSimVersion = "?"; // The handle to the underlying managed or unmanaged version of Bullet being used. - public BulletSimAPITemplate PE; + public BSAPITemplate PE; public Dictionary PhysObjects; public BSShapeCollection Shapes; diff --git a/OpenSim/Region/Physics/BulletSPlugin/BSShapeCollection.cs b/OpenSim/Region/Physics/BulletSPlugin/BSShapeCollection.cs index d59e455..cd77581 100755 --- a/OpenSim/Region/Physics/BulletSPlugin/BSShapeCollection.cs +++ b/OpenSim/Region/Physics/BulletSPlugin/BSShapeCollection.cs @@ -141,7 +141,7 @@ public sealed class BSShapeCollection : IDisposable if (DDetail) DetailLog("{0},BSShapeCollection.ReferenceBody,newBody,body={1}", body.ID, body); PhysicsScene.TaintedObject(inTaintTime, "BSShapeCollection.ReferenceBody", delegate() { - if (!BulletSimAPI.IsInWorld2(body.ptr)) + if (!PhysicsScene.PE.IsInWorld(body)) { PhysicsScene.PE.AddObjectToWorld(PhysicsScene.World, body); if (DDetail) DetailLog("{0},BSShapeCollection.ReferenceBody,addedToWorld,ref={1}", body.ID, body); @@ -166,7 +166,7 @@ public sealed class BSShapeCollection : IDisposable // If the caller needs to know the old body is going away, pass the event up. if (bodyCallback != null) bodyCallback(body); - if (BulletSimAPI.IsInWorld2(body.ptr)) + if (PhysicsScene.PE.IsInWorld(body)) { PhysicsScene.PE.RemoveObjectFromWorld(PhysicsScene.World, body); if (DDetail) DetailLog("{0},BSShapeCollection.DereferenceBody,removingFromWorld. Body={1}", body.ID, body); @@ -332,7 +332,7 @@ public sealed class BSShapeCollection : IDisposable // Called at taint-time. private void DereferenceCompound(BulletShape shape, ShapeDestructionCallback shapeCallback) { - if (!BulletSimAPI.IsCompound2(shape.ptr)) + if (!PhysicsScene.PE.IsCompound(shape)) { // Failed the sanity check!! PhysicsScene.Logger.ErrorFormat("{0} Attempt to free a compound shape that is not compound!! type={1}, ptr={2}", @@ -376,7 +376,7 @@ public sealed class BSShapeCollection : IDisposable } else { - if (BulletSimAPI.IsCompound2(cShape)) + if (PhysicsScene.PE.IsCompound(shapeInfo)) { shapeInfo.type = BSPhysicsShapeType.SHAPE_COMPOUND; } @@ -467,7 +467,7 @@ public sealed class BSShapeCollection : IDisposable // Get the scale of any existing shape so we can see if the new shape is same native type and same size. OMV.Vector3 scaleOfExistingShape = OMV.Vector3.Zero; if (prim.PhysShape.HasPhysicalShape) - scaleOfExistingShape = BulletSimAPI.GetLocalScaling2(prim.PhysShape.ptr); + scaleOfExistingShape = PhysicsScene.PE.GetLocalScaling(prim.PhysShape); if (DDetail) DetailLog("{0},BSShapeCollection.CreateGeom,maybeNative,force={1},primScale={2},primSize={3},primShape={4}", prim.LocalID, forceRebuild, prim.Scale, prim.Size, prim.PhysShape.type); diff --git a/OpenSim/Region/Physics/BulletSPlugin/BSShapes.cs b/OpenSim/Region/Physics/BulletSPlugin/BSShapes.cs index 423e700..c75eb9b 100755 --- a/OpenSim/Region/Physics/BulletSPlugin/BSShapes.cs +++ b/OpenSim/Region/Physics/BulletSPlugin/BSShapes.cs @@ -151,12 +151,12 @@ public class BSShapeNative : BSShape /* if (shapeType == BSPhysicsShapeType.SHAPE_CAPSULE) { - ptr = BulletSimAPI.BuildCapsuleShape2(physicsScene.World.ptr, 1f, 1f, prim.Scale); + ptr = PhysicsScene.PE.BuildCapsuleShape(physicsScene.World, 1f, 1f, prim.Scale); physicsScene.DetailLog("{0},BSShapeCollection.BuiletPhysicalNativeShape,capsule,scale={1}", prim.LocalID, prim.Scale); } else { - ptr = BulletSimAPI.BuildNativeShape2(physicsScene.World.ptr, nativeShapeData); + ptr = PhysicsScene.PE.BuildNativeShape(physicsScene.World, nativeShapeData); } if (ptr == IntPtr.Zero) { @@ -173,7 +173,7 @@ public class BSShapeNative : BSShape /* // Native shapes are not tracked and are released immediately physicsScene.DetailLog("{0},BSShapeCollection.DereferenceShape,deleteNativeShape,shape={1}", BSScene.DetailLogZero, this); - BulletSimAPI.DeleteCollisionShape2(physicsScene.World.ptr, ptr); + PhysicsScene.PE.DeleteCollisionShape(physicsScene.World, this); ptr = IntPtr.Zero; // Garbage collection will free up this instance. */ diff --git a/OpenSim/Region/Physics/BulletSPlugin/BSTerrainHeightmap.cs b/OpenSim/Region/Physics/BulletSPlugin/BSTerrainHeightmap.cs index 01966c0..cc28344 100755 --- a/OpenSim/Region/Physics/BulletSPlugin/BSTerrainHeightmap.cs +++ b/OpenSim/Region/Physics/BulletSPlugin/BSTerrainHeightmap.cs @@ -120,7 +120,7 @@ public sealed class BSTerrainHeightmap : BSTerrainPhys PhysicsScene.PE.UpdateSingleAabb(PhysicsScene.World, m_mapInfo.terrainBody); m_mapInfo.terrainBody.collisionType = CollisionType.Terrain; - m_mapInfo.terrainBody.ApplyCollisionMask(); + m_mapInfo.terrainBody.ApplyCollisionMask(PhysicsScene); // Make it so the terrain will not move or be considered for movement. PhysicsScene.PE.ForceActivationState(m_mapInfo.terrainBody, ActivationState.DISABLE_SIMULATION); diff --git a/OpenSim/Region/Physics/BulletSPlugin/BSTerrainManager.cs b/OpenSim/Region/Physics/BulletSPlugin/BSTerrainManager.cs index 590c687..2e9db39 100755 --- a/OpenSim/Region/Physics/BulletSPlugin/BSTerrainManager.cs +++ b/OpenSim/Region/Physics/BulletSPlugin/BSTerrainManager.cs @@ -143,7 +143,7 @@ public sealed class BSTerrainManager : IDisposable PhysicsScene.PE.ForceActivationState(m_groundPlane, ActivationState.DISABLE_SIMULATION); // Everything collides with the ground plane. m_groundPlane.collisionType = CollisionType.Groundplane; - m_groundPlane.ApplyCollisionMask(); + m_groundPlane.ApplyCollisionMask(PhysicsScene); // Build an initial terrain and put it in the world. This quickly gets replaced by the real region terrain. BSTerrainPhys initialTerrain = new BSTerrainHeightmap(PhysicsScene, Vector3.Zero, BSScene.TERRAIN_ID, DefaultRegionSize); diff --git a/OpenSim/Region/Physics/BulletSPlugin/BSTerrainMesh.cs b/OpenSim/Region/Physics/BulletSPlugin/BSTerrainMesh.cs index 2f55fc3..1d55ce3 100755 --- a/OpenSim/Region/Physics/BulletSPlugin/BSTerrainMesh.cs +++ b/OpenSim/Region/Physics/BulletSPlugin/BSTerrainMesh.cs @@ -120,7 +120,7 @@ public sealed class BSTerrainMesh : BSTerrainPhys PhysicsScene.PE.SetCollisionFlags(m_terrainBody, CollisionFlags.CF_STATIC_OBJECT); // Static objects are not very massive. - BulletSimAPI.SetMassProps2(m_terrainBody.ptr, 0f, Vector3.Zero); + PhysicsScene.PE.SetMassProps(m_terrainBody, 0f, Vector3.Zero); // Put the new terrain to the world of physical objects PhysicsScene.PE.AddObjectToWorld(PhysicsScene.World, m_terrainBody); @@ -129,7 +129,7 @@ public sealed class BSTerrainMesh : BSTerrainPhys PhysicsScene.PE.UpdateSingleAabb(PhysicsScene.World, m_terrainBody); m_terrainBody.collisionType = CollisionType.Terrain; - m_terrainBody.ApplyCollisionMask(); + m_terrainBody.ApplyCollisionMask(PhysicsScene); // Make it so the terrain will not move or be considered for movement. PhysicsScene.PE.ForceActivationState(m_terrainBody, ActivationState.DISABLE_SIMULATION); diff --git a/OpenSim/Region/Physics/BulletSPlugin/BulletSimAPI.cs b/OpenSim/Region/Physics/BulletSPlugin/BulletSimAPI.cs deleted file mode 100644 index b119f22..0000000 --- a/OpenSim/Region/Physics/BulletSPlugin/BulletSimAPI.cs +++ /dev/null @@ -1,667 +0,0 @@ -/* - * 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 { - - // Constraint type values as defined by Bullet -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 -} - -// =============================================================================== -[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, - // following defined by BulletSim - SHAPE_GROUNDPLANE = 20, - SHAPE_TERRAIN = 21, - SHAPE_COMPOUND = 22, - SHAPE_HEIGHTMAP = 23, - SHAPE_AVATAR = 24, -}; - -// The native shapes have predefined shape hash keys -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 uint 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; // true of things bump into this - public float Static; // true if a static object. Otherwise gravity, etc. - public float Solid; // true if object cannot be passed through - public Vector3 Size; - - // note that bools are passed as floats since bool size changes by language and architecture - public const float numericTrue = 1f; - public const float numericFalse = 0f; -} -[StructLayout(LayoutKind.Sequential)] -public struct SweepHit -{ - public uint ID; - public float Fraction; - public Vector3 Normal; - public Vector3 Point; -} -[StructLayout(LayoutKind.Sequential)] -public struct RaycastHit -{ - public uint ID; - public float Fraction; - public Vector3 Normal; -} -[StructLayout(LayoutKind.Sequential)] -public struct CollisionDesc -{ - public uint aID; - public uint bID; - public Vector3 point; - public Vector3 normal; -} -[StructLayout(LayoutKind.Sequential)] -public struct EntityProperties -{ - public uint ID; - public Vector3 Position; - public Quaternion Rotation; - public Vector3 Velocity; - public Vector3 Acceleration; - public Vector3 RotationalVelocity; -} - -// Format of this structure must match the definition in the C++ code -// NOTE: adding the X causes compile breaks if used. These are unused symbols -// that can be removed from both here and the unmanaged definition of this structure. -[StructLayout(LayoutKind.Sequential)] -public struct ConfigurationParameters -{ - public float defaultFriction; - public float defaultDensity; - public float defaultRestitution; - public float collisionMargin; - public float gravity; - - public float XlinearDamping; - public float XangularDamping; - public float XdeactivationTime; - public float XlinearSleepingThreshold; - public float XangularSleepingThreshold; - public float XccdMotionThreshold; - public float XccdSweptSphereRadius; - public float XcontactProcessingThreshold; - - public float XterrainImplementation; - public float XterrainFriction; - public float XterrainHitFraction; - public float XterrainRestitution; - public float XterrainCollisionMargin; - - public float XavatarFriction; - public float XavatarStandingFriction; - public float XavatarDensity; - public float XavatarRestitution; - public float XavatarCapsuleWidth; - public float XavatarCapsuleDepth; - public float XavatarCapsuleHeight; - public float XavatarContactProcessingThreshold; - - public float XvehicleAngularDamping; - - 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 XlinksetImplementation; - public float XlinkConstraintUseFrameOffset; - public float XlinkConstraintEnableTransMotor; - public float XlinkConstraintTransMotorMaxVel; - public float XlinkConstraintTransMotorMaxForce; - public float XlinkConstraintERP; - public float XlinkConstraintCFM; - public float XlinkConstraintSolverIterations; - - public float physicsLoggingFrames; - - public const float numericTrue = 1f; - public const float numericFalse = 0f; -} - - -// The states a bullet collision object can have -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, -} - -// Values used by Bullet and BulletSim to control object properties. -// Bullet's "CollisionFlags" has more to do with operations on the -// object (if collisions happen, if gravity effects it, ...). -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, - // Following used by BulletSim to control collisions and updates - BS_SUBSCRIBE_COLLISION_EVENTS = 1 << 10, - BS_FLOATS_ON_WATER = 1 << 11, - BS_VEHICLE_COLLISIONS = 1 << 12, - BS_NONE = 0, - BS_ALL = 0xFFFFFFFF -}; - -// Values f collisions groups and masks -public enum CollisionFilterGroups : uint -{ - // Don't use the bit definitions!! Define the use in a - // filter/mask definition below. This way collision interactions - // are more easily found and debugged. - BNoneGroup = 0, - BDefaultGroup = 1 << 0, // 0001 - BStaticGroup = 1 << 1, // 0002 - BKinematicGroup = 1 << 2, // 0004 - BDebrisGroup = 1 << 3, // 0008 - BSensorTrigger = 1 << 4, // 0010 - BCharacterGroup = 1 << 5, // 0020 - BAllGroup = 0x000FFFFF, - // Filter groups defined by BulletSim - BGroundPlaneGroup = 1 << 10, // 0400 - BTerrainGroup = 1 << 11, // 0800 - BRaycastGroup = 1 << 12, // 1000 - BSolidGroup = 1 << 13, // 2000 - // BLinksetGroup = xx // a linkset proper is either static or dynamic - BLinksetChildGroup = 1 << 14, // 4000 -}; - -// CFM controls the 'hardness' of the constraint. 0=fixed, 0..1=violatable. Default=0 -// ERP controls amount of correction per tick. Usable range=0.1..0.8. Default=0.2. -public enum ConstraintParams : int -{ - BT_CONSTRAINT_ERP = 1, // this one is not used in Bullet as of 20120730 - 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, // these last three added by BulletSim so we don't have to do zillions of calls - AXIS_ANGULAR_ALL, - AXIS_ALL -}; - -public abstract class BulletSimAPITemplate -{ - /* -// Initialization and simulation -public abstract BulletWorld Initialize(Vector3 maxPosition, IntPtr parms, - int maxCollisions, IntPtr collisionArray, - int maxUpdates, IntPtr updateArray - ); - -public abstract bool UpdateParameter(BulletWorld world, uint localID, String parm, float value); - -public abstract void SetHeightMap(BulletWorld world, float[] heightmap); - -public abstract void Shutdown(BulletWorld sim); - -public abstract int PhysicsStep(BulletWorld world, float timeStep, int maxSubSteps, float fixedTimeStep, - out int updatedEntityCount, - out IntPtr updatedEntitiesPtr, - out int collidersCount, - out IntPtr collidersPtr); - -public abstract bool PushUpdate(BulletBody obj); - */ - -// ===================================================================================== -// Mesh, hull, shape and body creation helper routines -public abstract BulletShape CreateMeshShape(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); - -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 RecalculateCompoundShapeLocalAabb(BulletShape cShape); - -public abstract BulletShape DuplicateCollisionShape(BulletWorld sim, BulletShape srcShape, uint id); - -public abstract BulletBody CreateBodyFromShapeAndInfo(BulletWorld sim, BulletShape shape, uint id, IntPtr constructionInfo); - -public abstract bool DeleteCollisionShape(BulletWorld world, BulletShape shape); - -public abstract int GetBodyType(BulletBody obj); - -public abstract BulletBody CreateBodyFromShape(BulletWorld sim, BulletShape shape, uint id, Vector3 pos, Quaternion rot); - -public abstract BulletBody CreateBodyWithDefaultMotionState(BulletShape shape, uint id, Vector3 pos, Quaternion rot); - -public abstract BulletBody CreateGhostFromShape(BulletWorld sim, BulletShape shape, uint id, Vector3 pos, Quaternion rot); - -public abstract IntPtr AllocateBodyInfo(BulletBody obj); - -public abstract void ReleaseBodyInfo(IntPtr obj); - -public abstract void DestroyObject(BulletWorld sim, BulletBody obj); - -// ===================================================================================== -// Terrain creation and helper routines -public abstract IntPtr CreateHeightMapInfo(BulletWorld sim, uint id, Vector3 minCoords, Vector3 maxCoords, - float[] heightMap, float collisionMargin); - -public abstract IntPtr FillHeightMapInfo(BulletWorld sim, IntPtr mapInfo, uint id, Vector3 minCoords, Vector3 maxCoords, - float[] heightMap, float collisionMargin); - -public abstract bool ReleaseHeightMapInfo(IntPtr heightMapInfo); - -public abstract BulletShape CreateGroundPlaneShape(uint id, float height, float collisionMargin); - -public abstract BulletShape CreateTerrainShape(IntPtr mapInfo); - -// ===================================================================================== -// Constraint creation and helper routines -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 CreateHingeConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2, - Vector3 pivotinA, Vector3 pivotinB, - Vector3 axisInA, Vector3 axisInB, - bool useLinearReferenceFrameA, 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 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); - -// ===================================================================================== -// btCollisionWorld entries -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); - -// ===================================================================================== -// btDynamicsWorld entries -public abstract bool AddObjectToWorld(BulletWorld world, BulletBody obj); - -public abstract bool RemoveObjectFromWorld(BulletWorld world, BulletBody obj); - -public abstract bool AddConstraintToWorld(BulletWorld world, BulletConstraint constrain, bool disableCollisionsBetweenLinkedObjects); - -public abstract bool RemoveConstraintFromWorld(BulletWorld world, BulletConstraint constrain); -// ===================================================================================== -// btCollisionObject entries -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 IntPtr GetBroadphaseHandle(BulletBody obj); - -public abstract void SetBroadphaseHandle(BulletBody obj, IntPtr handle); - -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); - - /* -// ===================================================================================== -// btRigidBody entries -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); - -// Add a force to the object as if its mass is one. -public abstract void ApplyCentralForce(BulletBody obj, Vector3 force); - -// Set the force being applied to the object as if its mass is one. -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); - -// Apply force at the given point. Will add torque to the object. -public abstract void ApplyForce(BulletBody obj, Vector3 force, Vector3 pos); - -// Apply impulse to the object. Same as "ApplycentralForce" but force scaled by object's mass. -public abstract void ApplyCentralImpulse(BulletBody obj, Vector3 imp); - -// Apply impulse to the object's torque. Force is scaled by object's mass. -public abstract 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 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(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, uint filter, uint mask); - -// ===================================================================================== -// btCollisionShape entries - -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); - */ - -}; -} diff --git a/OpenSim/Region/Physics/BulletSPlugin/BulletSimData.cs b/OpenSim/Region/Physics/BulletSPlugin/BulletSimData.cs index c10d75e..a040928 100755 --- a/OpenSim/Region/Physics/BulletSPlugin/BulletSimData.cs +++ b/OpenSim/Region/Physics/BulletSPlugin/BulletSimData.cs @@ -72,12 +72,12 @@ public class BulletBody public bool HasPhysicalBody { get { return ptr != IntPtr.Zero; } } // Apply the specificed collision mask into the physical world - public bool ApplyCollisionMask() + public bool ApplyCollisionMask(BSScene physicsScene) { // Should assert the body has been added to the physical world. // (The collision masks are stored in the collision proxy cache which only exists for // a collision body that is in the world.) - return BulletSimAPI.SetCollisionGroupMask2(ptr, + return physicsScene.PE.SetCollisionGroupMask(this, BulletSimData.CollisionTypeMasks[collisionType].group, BulletSimData.CollisionTypeMasks[collisionType].mask); } -- cgit v1.1