(I did the same thing you're doing a while back
Moderator: Alain
class MainClass
{
int wld;
int col;
int body;
Matrix mm;
Vector3 vec;
public MainClass()
{
wld = Newton.Create(0, 0);
Newton.SetSolverModel(wld, 8);
Newton.SetFrictionModel(wld, 1);
col = Newton.CreateBox(wld, 1, 1, 1, null);
body = Newton.CreateBody(wld, col);
Newton.ReleaseCollision(wld, col);
Newton.BodySetForceAndTorqueCallback(body, forcecb);
Newton.BodySetTransformCallback(body, transformcallback);
Newton.BodySetMassMatrix(body, 1, 1, 1, 1);
Matrix mat = Matrix.Identity;
Newton.BodySetMatrix(body, ref mat);
for (int i = 0; i <22; i++)
{
Newton.Update(wld, 0.02f);
}
Newton.Destroy(wld);
Console.ReadLine();
}
void transformcallback(int body, ref Matrix m)
{
Console.WriteLine("TransformMatrix: ");
Console.WriteLine(m);
}
void forcecb(int body)
{
vec = new Vector3(0, -5, 0);
Newton.BodySetForce(body, ref vec);
}
public static void Main()
{
MainClass mc = new MainClass();
}
}
SetForceAndTorqueCB fat = new SetForceAndTorqueCB(forcecb);
SetTransformCB tf = new SetTransformCB(transformcallback);
Newton.BodySetForceAndTorqueCallback(body, fat);
Newton.BodySetTransformCallback(body, tf);
#region Using directives
using System;
using System.Collections;
using System.Text;
using System.Runtime.InteropServices; // DllImport
using Microsoft.DirectX;
using Microsoft.DirectX.Direct3D;
using Haddd.Scene;
#endregion
/*
ATENCION
Debo crear a veces 2 métodos diferentes, porque al esperar un float *, es posible
que se le pase un null desde la aplicación.
Si paso un null esperando como un parámetro ref Matrix, me da un error
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateBox")]
public static extern int CreateBox(int newtonWorld, float dx, float dy, float dz, ref Matrix offsetMatrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateBox")]
public static extern int CreateBox(int newtonWorld, float dx, float dy, float dz, float[] matrix);
*/
namespace Haddd.Physics
{
#region structs
public struct NewtonHingeSliderUpdateDesc
{
public float accel;
public float minFriction;
public float maxFriction;
public float timestep;
};
#endregion
#region Delegates
[UnmanagedFunctionPointer(System.Runtime.InteropServices.CallingConvention.Cdecl)]
public delegate void SetTransformCB(int body, ref Matrix matrix);
[UnmanagedFunctionPointer(System.Runtime.InteropServices.CallingConvention.Cdecl)]
public delegate void SetForceAndTorqueCB(int body);
[UnmanagedFunctionPointer(System.Runtime.InteropServices.CallingConvention.Cdecl)]
public delegate void CreateTreeCollision(int bodyWithTreeCollision,int body,float[] vertex,int vertexstrideInBytes, int indexCount, int[] indexArray);
[UnmanagedFunctionPointer(System.Runtime.InteropServices.CallingConvention.Cdecl)]
public delegate int MaterialSetCollisionBegin(int material, int body0, int body1);
[UnmanagedFunctionPointer(System.Runtime.InteropServices.CallingConvention.Cdecl)]
public delegate int MaterialSetCollisionProcess(int material, int contact);
[UnmanagedFunctionPointer(System.Runtime.InteropServices.CallingConvention.Cdecl)]
public delegate void MaterialSetCollisionEnd(int material);
[UnmanagedFunctionPointer(System.Runtime.InteropServices.CallingConvention.Cdecl)]
public delegate void BodyLeaveWorld(int body);
[UnmanagedFunctionPointer(System.Runtime.InteropServices.CallingConvention.Cdecl)]
public delegate void BodyIterator(int body);
[UnmanagedFunctionPointer(System.Runtime.InteropServices.CallingConvention.Cdecl)]
public delegate float WorldRayCastCB(int body, ref Vector3 normal, int collisionID, [MarshalAs(UnmanagedType.IUnknown)] Object userData, float intersetParam);
[UnmanagedFunctionPointer(System.Runtime.InteropServices.CallingConvention.Cdecl)]
public delegate void CollisionIteratorCB(int body, int vertexCount, IntPtr faceVert, int ID);
[UnmanagedFunctionPointer(System.Runtime.InteropServices.CallingConvention.Cdecl)]
public delegate int HingeJointCB(int joint, ref NewtonHingeSliderUpdateDesc desc);
[UnmanagedFunctionPointer(System.Runtime.InteropServices.CallingConvention.Cdecl)]
public delegate int SliderJointCB(int joint, ref NewtonHingeSliderUpdateDesc desc);
[UnmanagedFunctionPointer(System.Runtime.InteropServices.CallingConvention.Cdecl)]
public delegate int UniversalJointCB(int joint, IntPtr desc);
#endregion
#region Wrapper
public class NewtonWrapper
{
#region WorldInterface
[DllImport("Newton.Dll",EntryPoint="NewtonCreate")]public static extern int Create(int a, int b);
[DllImport("Newton.Dll", EntryPoint = "NewtonGetGlobalScale")]public static extern float GetGlobalScale(int newtonWorld);
[DllImport("Newton.Dll", EntryPoint = "NewtonSetSolverModel")]public static extern void SetSolverModel(int a, int b);
[DllImport("Newton.Dll", EntryPoint = "NewtonSetFrictionModel")]public static extern void SetFrictionModel(int a, int b);
[DllImport("Newton.Dll", EntryPoint = "NewtonUpdate")]public static extern void Update(int newtonWorld, float timestep);
[DllImport("Newton.Dll", EntryPoint = "NewtonWorldCollide")]public static extern void WorldCollide(int newtonWorld, int maxSize,int collisionA,ref Matrix offsetA,int collisionB,ref Matrix offsetB,float[] contacts,float[] normals,float[] penetration);
[DllImport("Newton.Dll", EntryPoint = "NewtonDestroy")]public static extern void Destroy(int newtonWorld);
[DllImport("Newton.Dll", EntryPoint = "NewtonSetMinimumFrameRate")]public static extern void SetMinimumFrameRate(int newtonWorld, float frameRate);
[DllImport("Newton.Dll", EntryPoint = "NewtonGetTimeStep")]public static extern float GetTimeStep(int newtonWorld);
[DllImport("Newton.Dll", EntryPoint = "NewtonDestroyAllBodies")]public static extern void DestroyAllBodies(int newtonWorld);
[DllImport("Newton.Dll", EntryPoint = "NewtonSetWorldSize")]public static extern void SetWorldSize(int newtonWorld, ref Vector3 min,ref Vector3 max);
[DllImport("Newton.Dll", EntryPoint = "NewtonSetBodyLeaveWorldEvent")]public static extern void SetBodyLeaveWorldEvent(int newtonWorld, BodyLeaveWorld cb);
[DllImport("Newton.Dll", EntryPoint = "NewtonWorldFreezeBody")]public static extern void WorldFreezeBody(int newtonWorld,int body);
[DllImport("Newton.Dll", EntryPoint = "NewtonWorldUnfreezeBody")]public static extern void WorldUnfreezeBody(int newtonWorld, int body);
[DllImport("Newton.Dll", EntryPoint = "NewtonWorldForEachBodyDo")]public static extern void WorldForEachBodyDo(int newtonWorld, BodyIterator cb);
[DllImport("Newton.Dll", EntryPoint = "NewtonGetVersion")]public static extern int GetVersion(int newtonWorld);
[DllImport("Newton.Dll", EntryPoint = "NewtonWorldSetUserData")]public static extern void WorldSetUserData(int bodyPtr, [MarshalAs(UnmanagedType.IUnknown)] Object o);
[DllImport("Newton.Dll", EntryPoint = "NewtonWorldGetUserData")][return: MarshalAs(UnmanagedType.IUnknown)]public static extern Object WorldGetUserData(int bodyPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonWorldRayCast")]
public static extern void WorldRayCast(int newtonWorld, ref Vector3 p0, ref Vector3 p1, WorldRayCastCB cb, [MarshalAs(UnmanagedType.IUnknown)] Object userData);
#endregion
#region GroupID interface
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialGetDefaultGroupID")]public static extern int MaterialGetDefaultGroupID(int newtonWorld);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialCreateGroupID")]public static extern int MaterialCreateGroupID(int newtonWorld);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialDestroyAllGroupID")]
public static extern void MaterialDestroyAllGroupID(int newtonWorld);
#endregion
#region Material setup interface
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialSetDefaultSoftness")]public static extern void MaterialSetDefaultSoftness(int newtonWorld, int id0, int id1, float softnessCoef);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialSetDefaultElasticity")]public static extern void MaterialSetDefaultElasticity(int newtonWorld, int id0, int id1, float elasticCoef);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialSetDefaultCollidable")]public static extern void MaterialSetDefaultCollidable(int newtonWorld, int id0, int id1, int state);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialSetDefaultFriction")]public static extern void MaterialSetDefaultFriction(int newtonWorld, int id0, int id1, float staticFriction,float kineticFriction);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialSetCollisionCallback")]public static extern void MaterialSetCollisionCallback(int newtonWorld, int id0, int id1, [MarshalAs(UnmanagedType.IUnknown)] Object UserData, MaterialSetCollisionBegin cb1, MaterialSetCollisionProcess cb2, MaterialSetCollisionEnd cb3);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialGetUserData ")]
public static extern int MaterialGetUserData(int newtonWorld, int id0, int id1);
#endregion
#region Contact behavior control interface
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialDisableContact")]
public static extern void MaterialDisableContact(int materialHandle);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialGetMaterialPairUserData")]
[return: MarshalAs(UnmanagedType.IUnknown)]
public static extern Object MaterialGetMaterialPairUserData(int materialHandle);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialGetContactFaceAttribute")]
public static extern uint MaterialGetContactFaceAttribute(int materialHandle);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialGetCurrentTimestep")]
public static extern float MaterialGetCurrentTimestep(int materialHandle);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialGetContactNormalSpeed")]
public static extern float MaterialGetContactNormalSpeed(int materialHandle, int contactHandle);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialGetContactTangentSpeed")]
public static extern float MaterialGetContactTangentSpeed(int materialHandle, int contactHandle, int index);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialGetContactPositionAndNormal")]
public static extern void MaterialGetContactPositionAndNormal(int materialHandle, ref Vector3 position, ref Vector3 normal);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialGetContactForce")]
public static extern void MaterialGetContactForce(int materialHandle, ref Vector3 force);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialGetContactTangentDirections")]
public static extern void MaterialGetContactTangentDirections(int materialHandle, ref Vector3 dir0, ref Vector3 dir1);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialGetBodyCollisionID")]
public static extern uint MaterialGetBodyCollisionID(int materialHandle,int body);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialSetContactSoftness")]
public static extern void MaterialSetContactSoftness(int materialHandle, float softness);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialSetContactElasticity")]
public static extern void MaterialSetContactElasticity(int materialHandle, float restitution);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialSetContactFrictionState")]
public static extern void MaterialSetContactFrictionState(int materialHandle, int state,int index);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialSetContactStaticFrictionCoef")]
public static extern void MaterialSetContactStaticFrictionCoef(int materialHandle, float coef, int index);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialSetContactKineticFrictionCoef")]
public static extern void MaterialSetContactKineticFrictionCoef(int materialHandle, float coef, int index);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialSetContactTangentAcceleration")]
public static extern void MaterialSetContactTangentAcceleration(int materialHandle, float accel, int index);
[DllImport("Newton.Dll", EntryPoint = "NewtonMaterialContactRotateTangentDirections")]
public static extern void MaterialContactRotateTangentDirections(int materialHandle, ref Vector3 alignVector);
#endregion
#region Convex collision primitives interface
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateNull")]
public static extern int CreateNull(int newtonWorld, float dx, float dy, float dz, ref Matrix offsetMatrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateBox")]
public static extern int CreateBox(int newtonWorld, float dx, float dy, float dz, ref Matrix offsetMatrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateBox")]
public static extern int CreateBox(int newtonWorld, float dx, float dy, float dz, float[] matrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateSphere")]
public static extern int CreateSphere(int newtonWorld, float rx, float ry, float rz, ref Matrix offsetMatrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateSphere")]
public static extern int CreateSphere(int newtonWorld, float rx, float ry, float rz, float[] matrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateCone")]
public static extern int CreateCone(int newtonWorld, float radius, float height, ref Matrix offsetMatrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateCone")]
public static extern int CreateCone(int newtonWorld, float radius, float height, float[] matrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateCapsule")]
public static extern int CreateCapsule(int newtonWorld, float radius, float height, ref Matrix offsetMatrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateCapsule")]
public static extern int CreateCapsule(int newtonWorld, float radius, float height, float[] matrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateCylinder")]
public static extern int CreateCylinder(int newtonWorld, float radius, float height, ref Matrix offsetMatrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateCylinder")]
public static extern int CreateCylinder(int newtonWorld, float radius, float height, float[] matrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateChamferCylinder")]
public static extern int CreateChamferCylinder(int newtonWorld, float radius, float height, ref Matrix offsetMatrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateChamferCylinder")]
public static extern int CreateChamferCylinder(int newtonWorld, float radius, float height, float[] matrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateConvexHull")]
public static extern int CreateConvexHull(int newtonWorld, int count, float[] vertexCloud, int strideInBytes,ref Matrix offsetMatrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateConvexHullModifier")]
public static extern int CreateConvexHullModifier(int newtonWorld, int convexHullCollision);
[DllImport("Newton.Dll", EntryPoint = "NewtonConvexHullModifierGetMatrix ")]
public static extern void ConvexHullModifierGetMatrix(int convexHullCollision, ref Matrix matrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonConvexHullModifierSetMatrix ")]
public static extern void ConvexHullModifierSetMatrix(int convexHullCollision, ref Matrix matrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateCompoundCollision")]
public static extern int CreateCompoundCollision(int newtonWorld, int count, int[] collisionPrimitiveArray);
[DllImport("Newton.Dll", EntryPoint = "NewtonConvexCollisionSetUserID")]
public static extern void ConvexCollisionSetUserID(int newtonWorld, uint id);
[DllImport("Newton.Dll", EntryPoint = "NewtonConvexCollisionGetUserID")]
public static extern uint ConvexCollisionSetUserID(int newtonWorld);
#endregion
#region Complex collision primitives interface
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateTreeCollision")]
public static extern int CreateTreeCollision(int bodyPtr, CreateTreeCollision cb);
[DllImport("Newton.Dll", EntryPoint = "NewtonTreeCollisionBeginBuild")]
public static extern void TreeCollisionBeginBuild(int treeCollision);
[DllImport("Newton.Dll", EntryPoint = "NewtonTreeCollisionAddFace")]
public static extern void TreeCollisionAddFace(int bodyPtr, int vertexCount, float[] vertexPtr, int strideInBytes, int faceAttribute);
[DllImport("Newton.Dll", EntryPoint = "NewtonTreeCollisionEndBuild")]
public static extern void TreeCollisionEndBuild(int treeCollision, int optimize);
[DllImport("Newton.Dll", EntryPoint = "NewtonTreeCollisionGetFaceAtribute")]
public static extern void TreeCollisionGetFaceAtribute(int treeCollision, int[] faceIndexArray);
#endregion
#region Collision miscellaneous interface
[DllImport("Newton.Dll", EntryPoint = "NewtonReleaseCollision")]public static extern void ReleaseCollision(int newtonWorld, int collisionPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonCollisionCalculateAABB")]public static extern void CollisionCalculateAABB(int collisionPtr, ref Matrix offsetMatrix,ref Vector3 min,ref Vector3 max);
[DllImport("Newton.Dll", EntryPoint = "NewtonCollisionRayCast")]
public static extern float CollisionRayCast(int collisionPtr, ref Vector3 p0, ref Vector3 p1,ref Vector3 Normal,int[] attribute);
#endregion
#region Transform utility functions
[DllImport("Newton.Dll", EntryPoint = "NewtonGetEulerAngle ")]
public static extern void GetEulerAngle(ref Matrix matrix,ref Vector3 angles);
[DllImport("Newton.Dll", EntryPoint = "NewtonSetEulerAngle ")]
public static extern void SetEulerAngle(ref Matrix matrix, ref Vector3 angles);
#endregion
#region Rigid body interface
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateBody")]
public static extern int CreateBody(int newtonWorld, int collisionPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodySetUserData")]
public static extern void BodySetUserData(int bodyPtr, [MarshalAs(UnmanagedType.IUnknown)] Object o);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyGetUserData")]
[return: MarshalAs(UnmanagedType.IUnknown)]
public static extern Object BodyGetUserData(int bodyPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyGetWorld")]
public static extern int BodyGetWorld(int bodyPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodySetTransformCallback")]
public static extern void BodySetTransformCallback(int bodyPtr, SetTransformCB cb);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodySetForceAndTorqueCallback")]
public static extern void BodySetForceAndTorqueCallback(int bodyPtr, SetForceAndTorqueCB cb);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodySetMassMatrix")]
public static extern void BodySetMassMatrix(int bodyPtr, float mass, float Ixx, float Iyy, float Izz);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyGetMassMatrix")]
public static extern void BodyGetMassMatrix(int bodyPtr, out float mass, out float Ixx, out float Iyy, out float Izz);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyGetInvMass")]
public static extern void BodyGetInvMass(int bodyPtr, out float mass, out float Ixx, out float Iyy, out float Izz);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodySetMatrix")]
public static extern void BodySetMatrix(int bodyPtr, ref Matrix matrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodySetMatrixRecursive")]
public static extern void BodySetMatrixRecursive(int bodyPtr, ref Matrix matrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyGetMatrix")]
public static extern void BodyGetMatrix(int bodyPtr, ref Matrix matrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodySetForce")]
public static extern void BodySetForce(int bodyPtr, ref Vector3 force);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyAddForce")]
public static extern void BodyAddForce(int bodyPtr, ref Vector3 force);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyGetForce")]
public static extern void BodyGetForce(int bodyPtr, ref Vector3 force);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodySetTorque")]
public static extern void BodySetTorque(int bodyPtr, ref Vector3 torque);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyAddTorque")]
public static extern void BodyAddTorque(int bodyPtr, ref Vector3 torque);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyGetTorque")]
public static extern void BodyGetTorque(int bodyPtr, ref Vector3 torque);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyGetTotalVolume")]
public static extern float BodyGetTotalVolume(int bodyPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyAddBuoyancyForce")]
public static extern void BodyAddBuoyancyForce(int bodyPtr,float fluidDensity,float fluidLinearViscosity,float fluidAngularViscosity,float[] gravityVector,int buoyancyPlane);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodySetCollision")]
public static extern void BodySetCollision(int bodyPtr, int collision);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyCoriolisForcesMode")]
public static extern void BodyCoriolisForcesMode(int bodyPtr, int mode);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyGetCollision")]
public static extern int BodyGetCollision(int bodyPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodySetMaterialGroupID")]
public static extern void BodySetMaterialGroupID(int bodyPtr, int materialID);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyGetMaterialGroupID")]
public static extern int BodyGetMaterialGroupID(int bodyPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodySetJointRecursiveCollision")]
public static extern void BodySetJointRecursiveCollision(int bodyPtr, int state);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyGetJointRecursiveCollision")]
public static extern int BodyGetJointRecursiveCollision(int bodyPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodySetAutoFreeze")]
public static extern void BodySetAutoFreeze(int bodyPtr, int state);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyGetAutoFreeze")]
public static extern int BodyGetAutoFreeze(int bodyPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyGetSleepingState")]
public static extern int NewtonBodyGetSleepingState(int bodyPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodySetFreezeTreshold")]
public static extern void BodySetFreezeTreshold(int bodyPtr, float freezeSpeedMag2, float freezeOmegaMag2, int framesCount);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyGetFreezeTreshold")]
public static extern void BodyGetFreezeTreshold(int bodyPtr, ref float freezeSpeedMag2, ref float freezeOmegaMag2);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyGetAABB")]
public static extern void BodyGetAABB(int bodyPtr, ref Vector3 min,ref Vector3 max);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodySetVelocity")]
public static extern void BodySetVelocity(int bodyPtr, ref Vector3 velocity);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyGetVelocity")]
public static extern void BodyGetVelocity(int bodyPtr, ref Vector3 velocity);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodySetOmega")]
public static extern void BodySetOmega(int bodyPtr, ref Vector3 omega);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyGetOmega")]
public static extern void BodyGetOmega(int bodyPtr, ref Vector3 omega);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodySetLinearDamping")]
public static extern void BodySetLinearDamping(int bodyPtr, float linearDamp);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyGetLinearDamping")]
public static extern float BodyGetLinearDamping(int bodyPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodySetAngularDamping")]
public static extern void BodySetAngularDamping(int bodyPtr, ref Vector3 angularDamp);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyGetAngularDamping")]
public static extern void BodyGetAngularDamping(int bodyPtr, ref Vector3 angularDamp);
[DllImport("Newton.Dll", EntryPoint = "NewtonBodyForEachPolygonDo")]
public static extern void BodyForEachPolygonDo(int bodyPtr, CollisionIteratorCB cb);
[DllImport("Newton.Dll", EntryPoint = "NewtonAddBodyImpulse")]
public static extern void AddBodyImpulse(int bodyPtr, ref Vector3 pointDeltaVeloc, ref Vector3 pointPosit);
#endregion
#region Ball and Socket joint interface
[DllImport("Newton.Dll", EntryPoint = "NewtonConstraintCreateBall")]
public static extern int ConstraintCreateBall(int world, ref Vector3 pivotPoint, int childBody, int parentBody);
[DllImport("Newton.Dll", EntryPoint = "NewtonBallSetConeLimits")]
public static extern void BallSetConeLimits(int bodyPtr, ref Vector3 pin, float maxConeAngle, float maxTwistAngle);
[DllImport("Newton.Dll", EntryPoint = "NewtonBallGetJointAngle")]
public static extern void BallGetJointAngle(int jointPtr, ref Vector3 angle);
[DllImport("Newton.Dll", EntryPoint = "NewtonBallGetJointOmega")]
public static extern void BallGetJointOmega(int jointPtr, ref Vector3 omega);
[DllImport("Newton.Dll", EntryPoint = "NewtonBallGetJointForce")]
public static extern void BallGetJointForce(int jointPtr, ref Vector3 force);
#endregion
#region Hinge joint interface
[DllImport("Newton.Dll", EntryPoint = "NewtonConstraintCreateHinge")]
public static extern int ConstraintCreateHinge(int bodyPtr, ref Vector3 pivotPoint, ref Vector3 pinDir, int childBody, int parentBody);
[DllImport("Newton.Dll", EntryPoint = "NewtonHingeGetJointAngle")]
public static extern float HingeGetJointAngle(int jointPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonHingeGetJointOmega")]
public static extern float HingeGetJointOmega(int jointPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonHingleGetJointForce")]
public static extern void HingleGetJointForce(int jointPtr, ref Vector3 force);
[DllImport("Newton.Dll", EntryPoint = "NewtonHingeCalculateStopAlpha")]
public static extern float HingeCalculateStopAlpha(int jointPtr, ref NewtonHingeSliderUpdateDesc desc,float angleLimit);
[DllImport("Newton.Dll", EntryPoint = "NewtonHingeSetUserCallback")]
public static extern void HingeSetUserCallback(int jointPtr, HingeJointCB callback);
#endregion
#region Slider joint interface
[DllImport("Newton.Dll", EntryPoint = "NewtonConstraintCreateSlider")]
public static extern int ConstraintCreateSlider(int bodyPtr, ref Vector3 pivotPoint, ref Vector3 pinDir, int childBody, int parentBody);
[DllImport("Newton.Dll", EntryPoint = "NewtonSliderGetJointPosit")]
public static extern float SliderGetJointPosit(int jointPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonSliderGetJointVeloc")]
public static extern float SliderGetJointVeloc(int jointPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonSliderGetJointForce")]
public static extern void SliderGetJointForce(int jointPtr, ref Vector3 force);
[DllImport("Newton.Dll", EntryPoint = "NewtonSliderSetUserCallback")]
public static extern void SliderSetUserCallback(int jointPtr, SliderJointCB callback);
[DllImport("Newton.Dll", EntryPoint = "NewtonSliderCalculateStopAccel")]
public static extern float SliderCalculateStopAccel(int jointPtr, ref NewtonHingeSliderUpdateDesc desc, float angleLimit);
#endregion
#region Corkscrew joint interface
[DllImport("Newton.Dll", EntryPoint = "NewtonConstraintCreateCorkscrew")]
public static extern void ConstraintCreateCorkscrew(int bodyPtr, float[] pivotPoint, float[] pinDir, int childBody, int parentBody);
[DllImport("Newton.Dll", EntryPoint = "NewtonCorkscrewGetJointPosit ")]
public static extern float CorkscrewGetJointPosit(int jointPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonCorkscrewGetJointVeloc")]
public static extern float CorkscrewGetJointVeloc(int jointPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonCorkscrewGetJointAngle ")]
public static extern float CorkscrewGetJointAngle(int jointPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonCorkscrewGetJointOmega")]
public static extern float NewtonCorkscrewGetJointOmega(int jointPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonCorkscrewGetJointForce")]
public static extern void CorkscrewGetJointForce(int jointPtr, ref Vector3 force);
#endregion
#region Universal joint interface
[DllImport("Newton.Dll", EntryPoint = "NewtonConstraintCreateUniversal")]
public static extern int ConstraintCreateUniversal(int nWorld, ref Vector3 pivotPoint, ref Vector3 pinDir0, ref Vector3 pinDir1, int childBody, int parentBody);
[DllImport("Newton.Dll", EntryPoint = "NewtonUniversalGetJointAngle0")]
public static extern float UniversalGetJointAngle0(int jointPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonUniversalGetJointAngle1")]
public static extern float UniversalGetJointAngle1(int jointPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonUniversalGetJointOmega0")]
public static extern float UniversalGetJointOmega0(int jointPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonUniversalGetJointOmega1")]
public static extern float UniversalGetJointOmega1(int jointPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonUniversalGetJointForce")]
public static extern void UniversalGetJointForce(int jointPtr, ref Vector3 force);
[DllImport("Newton.Dll", EntryPoint = "NewtonUniversalSetUserCallback")]
public static extern void UniversalSetUserCallback(int jointPtr, UniversalJointCB callback);
[DllImport("Newton.Dll", EntryPoint = "NewtonUniversalCalculateStopAlpha0")]
public static extern float UniversalCalculateStopAlpha0(int jointPtr, IntPtr desc, float angleLimit);
[DllImport("Newton.Dll", EntryPoint = "NewtonUniversalCalculateStopAlpha1")]
public static extern float UniversalCalculateStopAlpha1(int jointPtr, IntPtr desc, float angleLimit);
#endregion
#region UpVector joint interface
[DllImport("Newton.Dll", EntryPoint = "NewtonConstraintCreateUpVector")]
public static extern int ConstraintCreateUpVector(int nWorld, ref Vector3 pinDir, int body);
[DllImport("Newton.Dll", EntryPoint = "NewtonUpVectorGetPin")]
public static extern void UpVectorGetPin(int jointPtr, ref Vector3 pin);
[DllImport("Newton.Dll", EntryPoint = "NewtonUpVectorSetPin")]
public static extern void UpVectorSetPin(int jointPtr, ref Vector3 pin);
#endregion
#region Joint common functions
[DllImport("Newton.Dll", EntryPoint = "NewtonJointSetUserData")]
public static extern void JointSetUserData(int jointPtr, [MarshalAs(UnmanagedType.IUnknown)] Object o);
[DllImport("Newton.Dll", EntryPoint = "NewtonJointGetUserData")]
[return: MarshalAs(UnmanagedType.IUnknown)]
public static extern Object JointGetUserData(int jointPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonJointSetCollisionState")]
public static extern void JointSetCollisionState(int jointPtr, int state);
[DllImport("Newton.Dll", EntryPoint = "NewtonJointGetCollisionState")]
public static extern int JointGetCollisionState(int jointPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonJointSetStiffness")]
public static extern void JointSetStiffness(int jointPtr, float stifness);
[DllImport("Newton.Dll", EntryPoint = "NewtonJointGetStiffness")]
public static extern float JointGetStiffness(int jointPtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonDestroyJoint")]
public static extern void DestroyJoint(int nWorld,int jointPtr);
#endregion
#region Rag doll joint container Interface
[DllImport("Newton.Dll", EntryPoint = "NewtonCreateRagDoll")]
public static extern int CreateRagDoll(int nWorld);
[DllImport("Newton.Dll", EntryPoint = "NewtonDestroyRagDoll")]
public static extern void DestroyRagDoll(int nWorld, int ragDoll);
[DllImport("Newton.Dll", EntryPoint = "NewtonRagDollBegin")]
public static extern void RagDollBegin(int ragDoll);
[DllImport("Newton.Dll", EntryPoint = "NewtonRagDollEnd")]
public static extern void RagDollEnd(int ragDoll);
[DllImport("Newton.Dll", EntryPoint = "NewtonRagDollAddBone")]
public static extern void NewtonRagDollAddBone(int ragDoll, int parentBone, [MarshalAs(UnmanagedType.IUnknown)] Object o,float mass,ref Matrix matrix,int boneCollision,ref Vector3 size);
[DllImport("Newton.Dll", EntryPoint = "NewtonRagDollBoneGetUserData")]
[return: MarshalAs(UnmanagedType.IUnknown)]
public static extern Object RagDollBoneGetUserData(int ragdollBonePtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonRagDollBoneSetID")]
public static extern void RagDollBoneSetID(int ragdollBonePtr, int id);
[DllImport("Newton.Dll", EntryPoint = "NewtonRagDollFindBone")]
public static extern int RagDollFindBone(int ragdollBonePtr, int id);
[DllImport("Newton.Dll", EntryPoint = "NewtonRagDollBoneGetBody")]
public static extern int RagDollBoneGetBody(int ragdollBonePtr);
[DllImport("Newton.Dll", EntryPoint = "NewtonRagDollBoneSetLimits")]
public static extern void RagDollBoneSetLimits(int ragdollBonePtr,ref Vector3 coneDir,float minConeAngle,float maxConeAngle,float maxTwistAngle,float[] lateralConeDir,float negativeBilateralConeAngle,float positiveBilateralConeAngle);
[DllImport("Newton.Dll", EntryPoint = "NewtonRagDollBoneGetLocalMatrix")]
public static extern void RagDollBoneGetLocalMatrix(int ragdollBonePtr, ref Matrix matrix);
[DllImport("Newton.Dll", EntryPoint = "NewtonRagDollBoneGetGlobalMatrix")]
public static extern void RagDollBoneGetGlobalMatrix(int ragdollBonePtr, ref Matrix matrix);
#endregion
}
#endregion
}
class Foo
{
protected static TransformCallback m_callback = new TransformCallback(MyCallbackFunction)
....
}
class NObject
{
private int m_world;
public int body;
public int collision;
// Body Matrix
Matrix mat;
// Transform matrix
Matrix trans;
public Vector3 omega = new Vector3(1.0f, 1.0f, 1.0f);
/// <summary>
/// Creates a Box as NObject
/// </summary>
/// <param name="world"></param>
/// <param name="x"></param>
/// <param name="y"></param>
/// <param name="z"></param>
/// <param name="transform"></param>
/// <returns></returns>
public static NObject CreateBox(Device device,
int world, float x, float y, float z, Matrix transform)
{
// temporary holder for the matrix
NObject obj = new NObject();
// |
// ---> Create the Newton Object
// save the world for obj object
obj.m_world = world;
// Create the Collision holder
obj.trans = transform;
obj.collision = Newton.CreateBox( world, x, y, z, ref obj.trans);
// Create the Rigid body for the collision
obj.body = Newton.CreateBody(world, obj.collision);
// Get rid of the collision
Newton.ReleaseCollision(world, obj.collision);
// Set Mass and interia
Newton.BodySetMassMatrix(obj.body, 1f, 1f, 1f, 1f);
// Set the transformation matrix
obj.mat = Matrix.Identity;
Newton.BodySetMatrix(obj.body, ref obj.mat);
//------Use of the delegate------------------------------------------------------
Newton.BodySetForceAndTorqueCallback(obj.body,
new SetForceAndTorqueCB(obj.ApplyForceAndTorque));
return obj;
}
/// <summary>
/// Applies force and torgue to the pBody
/// </summary>
/// <param name="pBody"></param>
private void ApplyForceAndTorque(int pBody)
{
Newton.BodySetOmega(pBody, ref omega);
}
}
class NObject
{
protected static SetForceAndTorqueCB m_callback = new SetForceAndTorqueCB(ApplyForceAndTorque);
.....
Newton.BodySetForceAndTorqueCallback(obj.body,
m_callback);
.....
}
private static void ApplyForceAndTorque(int pBody)
{
Newton.BodySetOmega(pBody, ref omega);
}
Users browsing this forum: No registered users and 1 guest