aboutsummaryrefslogtreecommitdiffstatshomepage
path: root/OpenSim/Region/PhysicsModules/BulletS/BSApiTemplate.cs
diff options
context:
space:
mode:
Diffstat (limited to 'OpenSim/Region/PhysicsModules/BulletS/BSApiTemplate.cs')
-rw-r--r--OpenSim/Region/PhysicsModules/BulletS/BSApiTemplate.cs763
1 files changed, 763 insertions, 0 deletions
diff --git a/OpenSim/Region/PhysicsModules/BulletS/BSApiTemplate.cs b/OpenSim/Region/PhysicsModules/BulletS/BSApiTemplate.cs
new file mode 100644
index 0000000..8491c0f
--- /dev/null
+++ b/OpenSim/Region/PhysicsModules/BulletS/BSApiTemplate.cs
@@ -0,0 +1,763 @@
1/*
2 * Copyright (c) Contributors, http://opensimulator.org/
3 * See CONTRIBUTORS.TXT for a full list of copyright holders.
4 *
5 * Redistribution and use in source and binary forms, with or without
6 * modification, are permitted provided that the following conditions are met:
7 * * Redistributions of source code must retain the above copyright
8 * notice, this list of conditions and the following disclaimer.
9 * * Redistributions in binary form must reproduce the above copyright
10 * notice, this list of conditions and the following disclaimer in the
11 * documentation and/or other materials provided with the distribution.
12 * * Neither the name of the OpenSimulator Project nor the
13 * names of its contributors may be used to endorse or promote products
14 * derived from this software without specific prior written permission.
15 *
16 * THIS SOFTWARE IS PROVIDED BY THE DEVELOPERS ``AS IS'' AND ANY
17 * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 * DISCLAIMED. IN NO EVENT SHALL THE CONTRIBUTORS BE LIABLE FOR ANY
20 * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27using System;
28using System.Collections.Generic;
29using System.Runtime.InteropServices;
30using System.Security;
31using System.Text;
32using OpenMetaverse;
33
34namespace OpenSim.Region.Physics.BulletSPlugin {
35
36 // Constraint type values as defined by Bullet
37public enum ConstraintType : int
38{
39 POINT2POINT_CONSTRAINT_TYPE = 3,
40 HINGE_CONSTRAINT_TYPE,
41 CONETWIST_CONSTRAINT_TYPE,
42 D6_CONSTRAINT_TYPE,
43 SLIDER_CONSTRAINT_TYPE,
44 CONTACT_CONSTRAINT_TYPE,
45 D6_SPRING_CONSTRAINT_TYPE,
46 GEAR_CONSTRAINT_TYPE, // added in Bullet 2.82
47 FIXED_CONSTRAINT_TYPE, // added in Bullet 2.82
48 MAX_CONSTRAINT_TYPE, // last type defined by Bullet
49 //
50 BS_FIXED_CONSTRAINT_TYPE = 1234 // BulletSim constraint that is fixed and unmoving
51}
52
53// ===============================================================================
54[StructLayout(LayoutKind.Sequential)]
55public struct ConvexHull
56{
57 Vector3 Offset;
58 int VertexCount;
59 Vector3[] Vertices;
60}
61public enum BSPhysicsShapeType
62{
63 SHAPE_UNKNOWN = 0,
64 SHAPE_CAPSULE = 1,
65 SHAPE_BOX = 2,
66 SHAPE_CONE = 3,
67 SHAPE_CYLINDER = 4,
68 SHAPE_SPHERE = 5,
69 SHAPE_MESH = 6,
70 SHAPE_HULL = 7,
71 // following defined by BulletSim
72 SHAPE_GROUNDPLANE = 20,
73 SHAPE_TERRAIN = 21,
74 SHAPE_COMPOUND = 22,
75 SHAPE_HEIGHTMAP = 23,
76 SHAPE_AVATAR = 24,
77 SHAPE_CONVEXHULL= 25,
78 SHAPE_GIMPACT = 26,
79};
80
81// The native shapes have predefined shape hash keys
82public enum FixedShapeKey : ulong
83{
84 KEY_NONE = 0,
85 KEY_BOX = 1,
86 KEY_SPHERE = 2,
87 KEY_CONE = 3,
88 KEY_CYLINDER = 4,
89 KEY_CAPSULE = 5,
90 KEY_AVATAR = 6,
91}
92
93[StructLayout(LayoutKind.Sequential)]
94public struct ShapeData
95{
96 public UInt32 ID;
97 public BSPhysicsShapeType Type;
98 public Vector3 Position;
99 public Quaternion Rotation;
100 public Vector3 Velocity;
101 public Vector3 Scale;
102 public float Mass;
103 public float Buoyancy;
104 public System.UInt64 HullKey;
105 public System.UInt64 MeshKey;
106 public float Friction;
107 public float Restitution;
108 public float Collidable; // true of things bump into this
109 public float Static; // true if a static object. Otherwise gravity, etc.
110 public float Solid; // true if object cannot be passed through
111 public Vector3 Size;
112
113 // note that bools are passed as floats since bool size changes by language and architecture
114 public const float numericTrue = 1f;
115 public const float numericFalse = 0f;
116}
117[StructLayout(LayoutKind.Sequential)]
118public struct SweepHit
119{
120 public UInt32 ID;
121 public float Fraction;
122 public Vector3 Normal;
123 public Vector3 Point;
124}
125[StructLayout(LayoutKind.Sequential)]
126public struct RaycastHit
127{
128 public UInt32 ID;
129 public float Fraction;
130 public Vector3 Normal;
131}
132[StructLayout(LayoutKind.Sequential)]
133public struct CollisionDesc
134{
135 public UInt32 aID;
136 public UInt32 bID;
137 public Vector3 point;
138 public Vector3 normal;
139 public float penetration;
140}
141[StructLayout(LayoutKind.Sequential)]
142public struct EntityProperties
143{
144 public UInt32 ID;
145 public Vector3 Position;
146 public Quaternion Rotation;
147 public Vector3 Velocity;
148 public Vector3 Acceleration;
149 public Vector3 RotationalVelocity;
150
151 public override string ToString()
152 {
153 StringBuilder buff = new StringBuilder();
154 buff.Append("<i=");
155 buff.Append(ID.ToString());
156 buff.Append(",p=");
157 buff.Append(Position.ToString());
158 buff.Append(",r=");
159 buff.Append(Rotation.ToString());
160 buff.Append(",v=");
161 buff.Append(Velocity.ToString());
162 buff.Append(",a=");
163 buff.Append(Acceleration.ToString());
164 buff.Append(",rv=");
165 buff.Append(RotationalVelocity.ToString());
166 buff.Append(">");
167 return buff.ToString();
168 }
169}
170
171// Format of this structure must match the definition in the C++ code
172// NOTE: adding the X causes compile breaks if used. These are unused symbols
173// that can be removed from both here and the unmanaged definition of this structure.
174[StructLayout(LayoutKind.Sequential)]
175public struct ConfigurationParameters
176{
177 public float defaultFriction;
178 public float defaultDensity;
179 public float defaultRestitution;
180 public float collisionMargin;
181 public float gravity;
182
183 public float maxPersistantManifoldPoolSize;
184 public float maxCollisionAlgorithmPoolSize;
185 public float shouldDisableContactPoolDynamicAllocation;
186 public float shouldForceUpdateAllAabbs;
187 public float shouldRandomizeSolverOrder;
188 public float shouldSplitSimulationIslands;
189 public float shouldEnableFrictionCaching;
190 public float numberOfSolverIterations;
191 public float useSingleSidedMeshes;
192 public float globalContactBreakingThreshold;
193
194 public float physicsLoggingFrames;
195
196 public const float numericTrue = 1f;
197 public const float numericFalse = 0f;
198}
199
200// Parameters passed for the conversion of a mesh to a hull using Bullet's HACD library.
201[StructLayout(LayoutKind.Sequential)]
202public struct HACDParams
203{
204 // usual default values
205 public float maxVerticesPerHull; // 100
206 public float minClusters; // 2
207 public float compacityWeight; // 0.1
208 public float volumeWeight; // 0.0
209 public float concavity; // 100
210 public float addExtraDistPoints; // false
211 public float addNeighboursDistPoints; // false
212 public float addFacesPoints; // false
213 public float shouldAdjustCollisionMargin; // false
214 // VHACD
215 public float whichHACD; // zero if Bullet HACD, non-zero says VHACD
216 // http://kmamou.blogspot.ca/2014/12/v-hacd-20-parameters-description.html
217 public float vHACDresolution; // 100,000 max number of voxels generated during voxelization stage
218 public float vHACDdepth; // 20 max number of clipping stages
219 public float vHACDconcavity; // 0.0025 maximum concavity
220 public float vHACDplaneDownsampling; // 4 granularity of search for best clipping plane
221 public float vHACDconvexHullDownsampling; // 4 precision of hull gen process
222 public float vHACDalpha; // 0.05 bias toward clipping along symmetry planes
223 public float vHACDbeta; // 0.05 bias toward clipping along revolution axis
224 public float vHACDgamma; // 0.00125 max concavity when merging
225 public float vHACDpca; // 0 on/off normalizing mesh before decomp
226 public float vHACDmode; // 0 0:voxel based, 1: tetrahedron based
227 public float vHACDmaxNumVerticesPerCH; // 64 max triangles per convex hull
228 public float vHACDminVolumePerCH; // 0.0001 sampling of generated convex hulls
229}
230
231// The states a bullet collision object can have
232public enum ActivationState : uint
233{
234 ACTIVE_TAG = 1,
235 ISLAND_SLEEPING,
236 WANTS_DEACTIVATION,
237 DISABLE_DEACTIVATION,
238 DISABLE_SIMULATION,
239}
240
241public enum CollisionObjectTypes : int
242{
243 CO_COLLISION_OBJECT = 1 << 0,
244 CO_RIGID_BODY = 1 << 1,
245 CO_GHOST_OBJECT = 1 << 2,
246 CO_SOFT_BODY = 1 << 3,
247 CO_HF_FLUID = 1 << 4,
248 CO_USER_TYPE = 1 << 5,
249}
250
251// Values used by Bullet and BulletSim to control object properties.
252// Bullet's "CollisionFlags" has more to do with operations on the
253// object (if collisions happen, if gravity effects it, ...).
254public enum CollisionFlags : uint
255{
256 CF_STATIC_OBJECT = 1 << 0,
257 CF_KINEMATIC_OBJECT = 1 << 1,
258 CF_NO_CONTACT_RESPONSE = 1 << 2,
259 CF_CUSTOM_MATERIAL_CALLBACK = 1 << 3,
260 CF_CHARACTER_OBJECT = 1 << 4,
261 CF_DISABLE_VISUALIZE_OBJECT = 1 << 5,
262 CF_DISABLE_SPU_COLLISION_PROCESS = 1 << 6,
263 // Following used by BulletSim to control collisions and updates
264 BS_SUBSCRIBE_COLLISION_EVENTS = 1 << 10, // return collision events from unmanaged to managed
265 BS_FLOATS_ON_WATER = 1 << 11, // the object should float at water level
266 BS_VEHICLE_COLLISIONS = 1 << 12, // return collisions for vehicle ground checking
267 BS_RETURN_ROOT_COMPOUND_SHAPE = 1 << 13, // return the pos/rot of the root shape in a compound shape
268 BS_NONE = 0,
269 BS_ALL = 0x7FFF // collision flags are a signed short
270};
271
272// Values f collisions groups and masks
273public enum CollisionFilterGroups : uint
274{
275 // Don't use the bit definitions!! Define the use in a
276 // filter/mask definition below. This way collision interactions
277 // are more easily found and debugged.
278 BNoneGroup = 0,
279 BDefaultGroup = 1 << 0, // 0001
280 BStaticGroup = 1 << 1, // 0002
281 BKinematicGroup = 1 << 2, // 0004
282 BDebrisGroup = 1 << 3, // 0008
283 BSensorTrigger = 1 << 4, // 0010
284 BCharacterGroup = 1 << 5, // 0020
285 BAllGroup = 0x0007FFF, // collision flags are a signed short
286 // Filter groups defined by BulletSim
287 BGroundPlaneGroup = 1 << 8, // 0400
288 BTerrainGroup = 1 << 9, // 0800
289 BRaycastGroup = 1 << 10, // 1000
290 BSolidGroup = 1 << 11, // 2000
291 // BLinksetGroup = xx // a linkset proper is either static or dynamic
292 BLinksetChildGroup = 1 << 12, // 4000
293};
294
295// CFM controls the 'hardness' of the constraint. 0=fixed, 0..1=violatable. Default=0
296// ERP controls amount of correction per tick. Usable range=0.1..0.8. Default=0.2.
297public enum ConstraintParams : int
298{
299 BT_CONSTRAINT_ERP = 1, // this one is not used in Bullet as of 20120730
300 BT_CONSTRAINT_STOP_ERP,
301 BT_CONSTRAINT_CFM,
302 BT_CONSTRAINT_STOP_CFM,
303};
304public enum ConstraintParamAxis : int
305{
306 AXIS_LINEAR_X = 0,
307 AXIS_LINEAR_Y,
308 AXIS_LINEAR_Z,
309 AXIS_ANGULAR_X,
310 AXIS_ANGULAR_Y,
311 AXIS_ANGULAR_Z,
312 AXIS_LINEAR_ALL = 20, // added by BulletSim so we don't have to do zillions of calls
313 AXIS_ANGULAR_ALL,
314 AXIS_ALL
315};
316
317public abstract class BSAPITemplate
318{
319// Returns the name of the underlying Bullet engine
320public abstract string BulletEngineName { get; }
321public abstract string BulletEngineVersion { get; protected set;}
322
323// Initialization and simulation
324public abstract BulletWorld Initialize(Vector3 maxPosition, ConfigurationParameters parms,
325 int maxCollisions, ref CollisionDesc[] collisionArray,
326 int maxUpdates, ref EntityProperties[] updateArray
327 );
328
329public abstract int PhysicsStep(BulletWorld world, float timeStep, int maxSubSteps, float fixedTimeStep,
330 out int updatedEntityCount, out int collidersCount);
331
332public abstract bool UpdateParameter(BulletWorld world, UInt32 localID, String parm, float value);
333
334public abstract void Shutdown(BulletWorld sim);
335
336public abstract bool PushUpdate(BulletBody obj);
337
338// =====================================================================================
339// Mesh, hull, shape and body creation helper routines
340public abstract BulletShape CreateMeshShape(BulletWorld world,
341 int indicesCount, int[] indices,
342 int verticesCount, float[] vertices );
343
344public abstract BulletShape CreateGImpactShape(BulletWorld world,
345 int indicesCount, int[] indices,
346 int verticesCount, float[] vertices );
347
348public abstract BulletShape CreateHullShape(BulletWorld world,
349 int hullCount, float[] hulls);
350
351public abstract BulletShape BuildHullShapeFromMesh(BulletWorld world, BulletShape meshShape, HACDParams parms);
352
353public abstract BulletShape BuildConvexHullShapeFromMesh(BulletWorld world, BulletShape meshShape);
354
355public abstract BulletShape CreateConvexHullShape(BulletWorld world,
356 int indicesCount, int[] indices,
357 int verticesCount, float[] vertices );
358
359public abstract BulletShape BuildNativeShape(BulletWorld world, ShapeData shapeData);
360
361public abstract bool IsNativeShape(BulletShape shape);
362
363public abstract void SetShapeCollisionMargin(BulletShape shape, float margin);
364
365public abstract BulletShape BuildCapsuleShape(BulletWorld world, float radius, float height, Vector3 scale);
366
367public abstract BulletShape CreateCompoundShape(BulletWorld sim, bool enableDynamicAabbTree);
368
369public abstract int GetNumberOfCompoundChildren(BulletShape cShape);
370
371public abstract void AddChildShapeToCompoundShape(BulletShape cShape, BulletShape addShape, Vector3 pos, Quaternion rot);
372
373public abstract BulletShape GetChildShapeFromCompoundShapeIndex(BulletShape cShape, int indx);
374
375public abstract BulletShape RemoveChildShapeFromCompoundShapeIndex(BulletShape cShape, int indx);
376
377public abstract void RemoveChildShapeFromCompoundShape(BulletShape cShape, BulletShape removeShape);
378
379public abstract void UpdateChildTransform(BulletShape pShape, int childIndex, Vector3 pos, Quaternion rot, bool shouldRecalculateLocalAabb);
380
381public abstract void RecalculateCompoundShapeLocalAabb(BulletShape cShape);
382
383public abstract BulletShape DuplicateCollisionShape(BulletWorld sim, BulletShape srcShape, UInt32 id);
384
385public abstract bool DeleteCollisionShape(BulletWorld world, BulletShape shape);
386
387public abstract CollisionObjectTypes GetBodyType(BulletBody obj);
388
389public abstract BulletBody CreateBodyFromShape(BulletWorld sim, BulletShape shape, UInt32 id, Vector3 pos, Quaternion rot);
390
391public abstract BulletBody CreateBodyWithDefaultMotionState(BulletShape shape, UInt32 id, Vector3 pos, Quaternion rot);
392
393public abstract BulletBody CreateGhostFromShape(BulletWorld sim, BulletShape shape, UInt32 id, Vector3 pos, Quaternion rot);
394
395public abstract void DestroyObject(BulletWorld sim, BulletBody obj);
396
397// =====================================================================================
398public abstract BulletShape CreateGroundPlaneShape(UInt32 id, float height, float collisionMargin);
399
400public abstract BulletShape CreateTerrainShape(UInt32 id, Vector3 size, float minHeight, float maxHeight, float[] heightMap,
401 float scaleFactor, float collisionMargin);
402
403// =====================================================================================
404// Constraint creation and helper routines
405public abstract BulletConstraint Create6DofConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
406 Vector3 frame1loc, Quaternion frame1rot,
407 Vector3 frame2loc, Quaternion frame2rot,
408 bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
409
410public abstract BulletConstraint Create6DofConstraintToPoint(BulletWorld world, BulletBody obj1, BulletBody obj2,
411 Vector3 joinPoint,
412 bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
413
414public abstract BulletConstraint Create6DofConstraintFixed(BulletWorld world, BulletBody obj1,
415 Vector3 frameInBloc, Quaternion frameInBrot,
416 bool useLinearReferenceFrameB, bool disableCollisionsBetweenLinkedBodies);
417
418public abstract BulletConstraint Create6DofSpringConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
419 Vector3 frame1loc, Quaternion frame1rot,
420 Vector3 frame2loc, Quaternion frame2rot,
421 bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
422
423public abstract BulletConstraint CreateHingeConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
424 Vector3 pivotinA, Vector3 pivotinB,
425 Vector3 axisInA, Vector3 axisInB,
426 bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
427
428public abstract BulletConstraint CreateSliderConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
429 Vector3 frameInAloc, Quaternion frameInArot,
430 Vector3 frameInBloc, Quaternion frameInBrot,
431 bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
432
433public abstract BulletConstraint CreateConeTwistConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
434 Vector3 frameInAloc, Quaternion frameInArot,
435 Vector3 frameInBloc, Quaternion frameInBrot,
436 bool disableCollisionsBetweenLinkedBodies);
437
438public abstract BulletConstraint CreateGearConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
439 Vector3 axisInA, Vector3 axisInB,
440 float ratio, bool disableCollisionsBetweenLinkedBodies);
441
442public abstract BulletConstraint CreatePoint2PointConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
443 Vector3 pivotInA, Vector3 pivotInB,
444 bool disableCollisionsBetweenLinkedBodies);
445
446public abstract void SetConstraintEnable(BulletConstraint constrain, float numericTrueFalse);
447
448public abstract void SetConstraintNumSolverIterations(BulletConstraint constrain, float iterations);
449
450public abstract bool SetFrames(BulletConstraint constrain,
451 Vector3 frameA, Quaternion frameArot, Vector3 frameB, Quaternion frameBrot);
452
453public abstract bool SetLinearLimits(BulletConstraint constrain, Vector3 low, Vector3 hi);
454
455public abstract bool SetAngularLimits(BulletConstraint constrain, Vector3 low, Vector3 hi);
456
457public abstract bool UseFrameOffset(BulletConstraint constrain, float enable);
458
459public abstract bool TranslationalLimitMotor(BulletConstraint constrain, float enable, float targetVel, float maxMotorForce);
460
461public abstract bool SetBreakingImpulseThreshold(BulletConstraint constrain, float threshold);
462
463public const int HINGE_NOT_SPECIFIED = -1;
464public abstract bool HingeSetLimits(BulletConstraint constrain, float low, float high, float softness, float bias, float relaxation);
465
466public abstract bool SpringEnable(BulletConstraint constrain, int index, float numericTrueFalse);
467
468public const int SPRING_NOT_SPECIFIED = -1;
469public abstract bool SpringSetEquilibriumPoint(BulletConstraint constrain, int index, float equilibriumPoint);
470
471public abstract bool SpringSetStiffness(BulletConstraint constrain, int index, float stiffnesss);
472
473public abstract bool SpringSetDamping(BulletConstraint constrain, int index, float damping);
474
475public const int SLIDER_LOWER_LIMIT = 0;
476public const int SLIDER_UPPER_LIMIT = 1;
477public const int SLIDER_LINEAR = 2;
478public const int SLIDER_ANGULAR = 3;
479public abstract bool SliderSetLimits(BulletConstraint constrain, int lowerUpper, int linAng, float val);
480
481public const int SLIDER_SET_SOFTNESS = 4;
482public const int SLIDER_SET_RESTITUTION = 5;
483public const int SLIDER_SET_DAMPING = 6;
484public const int SLIDER_SET_DIRECTION = 7;
485public const int SLIDER_SET_LIMIT = 8;
486public const int SLIDER_SET_ORTHO = 9;
487public abstract bool SliderSet(BulletConstraint constrain, int softRestDamp, int dirLimOrtho, int linAng, float val);
488
489public abstract bool SliderMotorEnable(BulletConstraint constrain, int linAng, float numericTrueFalse);
490
491public const int SLIDER_MOTOR_VELOCITY = 10;
492public const int SLIDER_MAX_MOTOR_FORCE = 11;
493public abstract bool SliderMotor(BulletConstraint constrain, int forceVel, int linAng, float val);
494
495public abstract bool CalculateTransforms(BulletConstraint constrain);
496
497public abstract bool SetConstraintParam(BulletConstraint constrain, ConstraintParams paramIndex, float value, ConstraintParamAxis axis);
498
499public abstract bool DestroyConstraint(BulletWorld world, BulletConstraint constrain);
500
501// =====================================================================================
502// btCollisionWorld entries
503public abstract void UpdateSingleAabb(BulletWorld world, BulletBody obj);
504
505public abstract void UpdateAabbs(BulletWorld world);
506
507public abstract bool GetForceUpdateAllAabbs(BulletWorld world);
508
509public abstract void SetForceUpdateAllAabbs(BulletWorld world, bool force);
510
511// =====================================================================================
512// btDynamicsWorld entries
513// public abstract bool AddObjectToWorld(BulletWorld world, BulletBody obj, Vector3 pos, Quaternion rot);
514public abstract bool AddObjectToWorld(BulletWorld world, BulletBody obj);
515
516public abstract bool RemoveObjectFromWorld(BulletWorld world, BulletBody obj);
517
518public abstract bool ClearCollisionProxyCache(BulletWorld world, BulletBody obj);
519
520public abstract bool AddConstraintToWorld(BulletWorld world, BulletConstraint constrain, bool disableCollisionsBetweenLinkedObjects);
521
522public abstract bool RemoveConstraintFromWorld(BulletWorld world, BulletConstraint constrain);
523// =====================================================================================
524// btCollisionObject entries
525public abstract Vector3 GetAnisotripicFriction(BulletConstraint constrain);
526
527public abstract Vector3 SetAnisotripicFriction(BulletConstraint constrain, Vector3 frict);
528
529public abstract bool HasAnisotripicFriction(BulletConstraint constrain);
530
531public abstract void SetContactProcessingThreshold(BulletBody obj, float val);
532
533public abstract float GetContactProcessingThreshold(BulletBody obj);
534
535public abstract bool IsStaticObject(BulletBody obj);
536
537public abstract bool IsKinematicObject(BulletBody obj);
538
539public abstract bool IsStaticOrKinematicObject(BulletBody obj);
540
541public abstract bool HasContactResponse(BulletBody obj);
542
543public abstract void SetCollisionShape(BulletWorld sim, BulletBody obj, BulletShape shape);
544
545public abstract BulletShape GetCollisionShape(BulletBody obj);
546
547public abstract int GetActivationState(BulletBody obj);
548
549public abstract void SetActivationState(BulletBody obj, int state);
550
551public abstract void SetDeactivationTime(BulletBody obj, float dtime);
552
553public abstract float GetDeactivationTime(BulletBody obj);
554
555public abstract void ForceActivationState(BulletBody obj, ActivationState state);
556
557public abstract void Activate(BulletBody obj, bool forceActivation);
558
559public abstract bool IsActive(BulletBody obj);
560
561public abstract void SetRestitution(BulletBody obj, float val);
562
563public abstract float GetRestitution(BulletBody obj);
564
565public abstract void SetFriction(BulletBody obj, float val);
566
567public abstract float GetFriction(BulletBody obj);
568
569public abstract Vector3 GetPosition(BulletBody obj);
570
571public abstract Quaternion GetOrientation(BulletBody obj);
572
573public abstract void SetTranslation(BulletBody obj, Vector3 position, Quaternion rotation);
574
575// public abstract IntPtr GetBroadphaseHandle(BulletBody obj);
576
577// public abstract void SetBroadphaseHandle(BulletBody obj, IntPtr handle);
578
579public abstract void SetInterpolationLinearVelocity(BulletBody obj, Vector3 vel);
580
581public abstract void SetInterpolationAngularVelocity(BulletBody obj, Vector3 vel);
582
583public abstract void SetInterpolationVelocity(BulletBody obj, Vector3 linearVel, Vector3 angularVel);
584
585public abstract float GetHitFraction(BulletBody obj);
586
587public abstract void SetHitFraction(BulletBody obj, float val);
588
589public abstract CollisionFlags GetCollisionFlags(BulletBody obj);
590
591public abstract CollisionFlags SetCollisionFlags(BulletBody obj, CollisionFlags flags);
592
593public abstract CollisionFlags AddToCollisionFlags(BulletBody obj, CollisionFlags flags);
594
595public abstract CollisionFlags RemoveFromCollisionFlags(BulletBody obj, CollisionFlags flags);
596
597public abstract float GetCcdMotionThreshold(BulletBody obj);
598
599public abstract void SetCcdMotionThreshold(BulletBody obj, float val);
600
601public abstract float GetCcdSweptSphereRadius(BulletBody obj);
602
603public abstract void SetCcdSweptSphereRadius(BulletBody obj, float val);
604
605public abstract IntPtr GetUserPointer(BulletBody obj);
606
607public abstract void SetUserPointer(BulletBody obj, IntPtr val);
608
609// =====================================================================================
610// btRigidBody entries
611public abstract void ApplyGravity(BulletBody obj);
612
613public abstract void SetGravity(BulletBody obj, Vector3 val);
614
615public abstract Vector3 GetGravity(BulletBody obj);
616
617public abstract void SetDamping(BulletBody obj, float lin_damping, float ang_damping);
618
619public abstract void SetLinearDamping(BulletBody obj, float lin_damping);
620
621public abstract void SetAngularDamping(BulletBody obj, float ang_damping);
622
623public abstract float GetLinearDamping(BulletBody obj);
624
625public abstract float GetAngularDamping(BulletBody obj);
626
627public abstract float GetLinearSleepingThreshold(BulletBody obj);
628
629public abstract void ApplyDamping(BulletBody obj, float timeStep);
630
631public abstract void SetMassProps(BulletBody obj, float mass, Vector3 inertia);
632
633public abstract Vector3 GetLinearFactor(BulletBody obj);
634
635public abstract void SetLinearFactor(BulletBody obj, Vector3 factor);
636
637public abstract void SetCenterOfMassByPosRot(BulletBody obj, Vector3 pos, Quaternion rot);
638
639// Add a force to the object as if its mass is one.
640public abstract void ApplyCentralForce(BulletBody obj, Vector3 force);
641
642// Set the force being applied to the object as if its mass is one.
643public abstract void SetObjectForce(BulletBody obj, Vector3 force);
644
645public abstract Vector3 GetTotalForce(BulletBody obj);
646
647public abstract Vector3 GetTotalTorque(BulletBody obj);
648
649public abstract Vector3 GetInvInertiaDiagLocal(BulletBody obj);
650
651public abstract void SetInvInertiaDiagLocal(BulletBody obj, Vector3 inert);
652
653public abstract void SetSleepingThresholds(BulletBody obj, float lin_threshold, float ang_threshold);
654
655public abstract void ApplyTorque(BulletBody obj, Vector3 torque);
656
657// Apply force at the given point. Will add torque to the object.
658public abstract void ApplyForce(BulletBody obj, Vector3 force, Vector3 pos);
659
660// Apply impulse to the object. Same as "ApplycentralForce" but force scaled by object's mass.
661public abstract void ApplyCentralImpulse(BulletBody obj, Vector3 imp);
662
663// Apply impulse to the object's torque. Force is scaled by object's mass.
664public abstract void ApplyTorqueImpulse(BulletBody obj, Vector3 imp);
665
666// Apply impulse at the point given. For is scaled by object's mass and effects both linear and angular forces.
667public abstract void ApplyImpulse(BulletBody obj, Vector3 imp, Vector3 pos);
668
669public abstract void ClearForces(BulletBody obj);
670
671public abstract void ClearAllForces(BulletBody obj);
672
673public abstract void UpdateInertiaTensor(BulletBody obj);
674
675public abstract Vector3 GetLinearVelocity(BulletBody obj);
676
677public abstract Vector3 GetAngularVelocity(BulletBody obj);
678
679public abstract void SetLinearVelocity(BulletBody obj, Vector3 val);
680
681public abstract void SetAngularVelocity(BulletBody obj, Vector3 angularVelocity);
682
683public abstract Vector3 GetVelocityInLocalPoint(BulletBody obj, Vector3 pos);
684
685public abstract void Translate(BulletBody obj, Vector3 trans);
686
687public abstract void UpdateDeactivation(BulletBody obj, float timeStep);
688
689public abstract bool WantsSleeping(BulletBody obj);
690
691public abstract void SetAngularFactor(BulletBody obj, float factor);
692
693public abstract void SetAngularFactorV(BulletBody obj, Vector3 factor);
694
695public abstract Vector3 GetAngularFactor(BulletBody obj);
696
697public abstract bool IsInWorld(BulletWorld world, BulletBody obj);
698
699public abstract void AddConstraintRef(BulletBody obj, BulletConstraint constrain);
700
701public abstract void RemoveConstraintRef(BulletBody obj, BulletConstraint constrain);
702
703public abstract BulletConstraint GetConstraintRef(BulletBody obj, int index);
704
705public abstract int GetNumConstraintRefs(BulletBody obj);
706
707public abstract bool SetCollisionGroupMask(BulletBody body, UInt32 filter, UInt32 mask);
708
709// =====================================================================================
710// btCollisionShape entries
711
712public abstract float GetAngularMotionDisc(BulletShape shape);
713
714public abstract float GetContactBreakingThreshold(BulletShape shape, float defaultFactor);
715
716public abstract bool IsPolyhedral(BulletShape shape);
717
718public abstract bool IsConvex2d(BulletShape shape);
719
720public abstract bool IsConvex(BulletShape shape);
721
722public abstract bool IsNonMoving(BulletShape shape);
723
724public abstract bool IsConcave(BulletShape shape);
725
726public abstract bool IsCompound(BulletShape shape);
727
728public abstract bool IsSoftBody(BulletShape shape);
729
730public abstract bool IsInfinite(BulletShape shape);
731
732public abstract void SetLocalScaling(BulletShape shape, Vector3 scale);
733
734public abstract Vector3 GetLocalScaling(BulletShape shape);
735
736public abstract Vector3 CalculateLocalInertia(BulletShape shape, float mass);
737
738public abstract int GetShapeType(BulletShape shape);
739
740public abstract void SetMargin(BulletShape shape, float val);
741
742public abstract float GetMargin(BulletShape shape);
743
744// =====================================================================================
745// Debugging
746public virtual void DumpRigidBody(BulletWorld sim, BulletBody collisionObject) { }
747
748public virtual void DumpCollisionShape(BulletWorld sim, BulletShape collisionShape) { }
749
750public virtual void DumpConstraint(BulletWorld sim, BulletConstraint constrain) { }
751
752public virtual void DumpActivationInfo(BulletWorld sim) { }
753
754public virtual void DumpAllInfo(BulletWorld sim) { }
755
756public virtual void DumpPhysicsStatistics(BulletWorld sim) { }
757
758public virtual void ResetBroadphasePool(BulletWorld sim) { }
759
760public virtual void ResetConstraintSolver(BulletWorld sim) { }
761
762};
763}