aboutsummaryrefslogtreecommitdiffstatshomepage
path: root/OpenSim/Region/Physics/BulletSPlugin/BSApiTemplate.cs
diff options
context:
space:
mode:
Diffstat (limited to 'OpenSim/Region/Physics/BulletSPlugin/BSApiTemplate.cs')
-rw-r--r--OpenSim/Region/Physics/BulletSPlugin/BSApiTemplate.cs683
1 files changed, 683 insertions, 0 deletions
diff --git a/OpenSim/Region/Physics/BulletSPlugin/BSApiTemplate.cs b/OpenSim/Region/Physics/BulletSPlugin/BSApiTemplate.cs
new file mode 100644
index 0000000..5765b0d
--- /dev/null
+++ b/OpenSim/Region/Physics/BulletSPlugin/BSApiTemplate.cs
@@ -0,0 +1,683 @@
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 MAX_CONSTRAINT_TYPE
47}
48
49// ===============================================================================
50[StructLayout(LayoutKind.Sequential)]
51public struct ConvexHull
52{
53 Vector3 Offset;
54 int VertexCount;
55 Vector3[] Vertices;
56}
57public enum BSPhysicsShapeType
58{
59 SHAPE_UNKNOWN = 0,
60 SHAPE_CAPSULE = 1,
61 SHAPE_BOX = 2,
62 SHAPE_CONE = 3,
63 SHAPE_CYLINDER = 4,
64 SHAPE_SPHERE = 5,
65 SHAPE_MESH = 6,
66 SHAPE_HULL = 7,
67 // following defined by BulletSim
68 SHAPE_GROUNDPLANE = 20,
69 SHAPE_TERRAIN = 21,
70 SHAPE_COMPOUND = 22,
71 SHAPE_HEIGHTMAP = 23,
72 SHAPE_AVATAR = 24,
73};
74
75// The native shapes have predefined shape hash keys
76public enum FixedShapeKey : ulong
77{
78 KEY_NONE = 0,
79 KEY_BOX = 1,
80 KEY_SPHERE = 2,
81 KEY_CONE = 3,
82 KEY_CYLINDER = 4,
83 KEY_CAPSULE = 5,
84 KEY_AVATAR = 6,
85}
86
87[StructLayout(LayoutKind.Sequential)]
88public struct ShapeData
89{
90 public UInt32 ID;
91 public BSPhysicsShapeType Type;
92 public Vector3 Position;
93 public Quaternion Rotation;
94 public Vector3 Velocity;
95 public Vector3 Scale;
96 public float Mass;
97 public float Buoyancy;
98 public System.UInt64 HullKey;
99 public System.UInt64 MeshKey;
100 public float Friction;
101 public float Restitution;
102 public float Collidable; // true of things bump into this
103 public float Static; // true if a static object. Otherwise gravity, etc.
104 public float Solid; // true if object cannot be passed through
105 public Vector3 Size;
106
107 // note that bools are passed as floats since bool size changes by language and architecture
108 public const float numericTrue = 1f;
109 public const float numericFalse = 0f;
110}
111[StructLayout(LayoutKind.Sequential)]
112public struct SweepHit
113{
114 public UInt32 ID;
115 public float Fraction;
116 public Vector3 Normal;
117 public Vector3 Point;
118}
119[StructLayout(LayoutKind.Sequential)]
120public struct RaycastHit
121{
122 public UInt32 ID;
123 public float Fraction;
124 public Vector3 Normal;
125}
126[StructLayout(LayoutKind.Sequential)]
127public struct CollisionDesc
128{
129 public UInt32 aID;
130 public UInt32 bID;
131 public Vector3 point;
132 public Vector3 normal;
133 public float penetration;
134}
135[StructLayout(LayoutKind.Sequential)]
136public struct EntityProperties
137{
138 public UInt32 ID;
139 public Vector3 Position;
140 public Quaternion Rotation;
141 public Vector3 Velocity;
142 public Vector3 Acceleration;
143 public Vector3 RotationalVelocity;
144
145 public override string ToString()
146 {
147 StringBuilder buff = new StringBuilder();
148 buff.Append("<i=");
149 buff.Append(ID.ToString());
150 buff.Append(",p=");
151 buff.Append(Position.ToString());
152 buff.Append(",r=");
153 buff.Append(Rotation.ToString());
154 buff.Append(",v=");
155 buff.Append(Velocity.ToString());
156 buff.Append(",a=");
157 buff.Append(Acceleration.ToString());
158 buff.Append(",rv=");
159 buff.Append(RotationalVelocity.ToString());
160 buff.Append(">");
161 return buff.ToString();
162 }
163}
164
165// Format of this structure must match the definition in the C++ code
166// NOTE: adding the X causes compile breaks if used. These are unused symbols
167// that can be removed from both here and the unmanaged definition of this structure.
168[StructLayout(LayoutKind.Sequential)]
169public struct ConfigurationParameters
170{
171 public float defaultFriction;
172 public float defaultDensity;
173 public float defaultRestitution;
174 public float collisionMargin;
175 public float gravity;
176
177 public float maxPersistantManifoldPoolSize;
178 public float maxCollisionAlgorithmPoolSize;
179 public float shouldDisableContactPoolDynamicAllocation;
180 public float shouldForceUpdateAllAabbs;
181 public float shouldRandomizeSolverOrder;
182 public float shouldSplitSimulationIslands;
183 public float shouldEnableFrictionCaching;
184 public float numberOfSolverIterations;
185 public float useSingleSidedMeshes;
186 public float globalContactBreakingThreshold;
187
188 public float physicsLoggingFrames;
189
190 public const float numericTrue = 1f;
191 public const float numericFalse = 0f;
192}
193
194
195// The states a bullet collision object can have
196public enum ActivationState : uint
197{
198 ACTIVE_TAG = 1,
199 ISLAND_SLEEPING,
200 WANTS_DEACTIVATION,
201 DISABLE_DEACTIVATION,
202 DISABLE_SIMULATION,
203}
204
205public enum CollisionObjectTypes : int
206{
207 CO_COLLISION_OBJECT = 1 << 0,
208 CO_RIGID_BODY = 1 << 1,
209 CO_GHOST_OBJECT = 1 << 2,
210 CO_SOFT_BODY = 1 << 3,
211 CO_HF_FLUID = 1 << 4,
212 CO_USER_TYPE = 1 << 5,
213}
214
215// Values used by Bullet and BulletSim to control object properties.
216// Bullet's "CollisionFlags" has more to do with operations on the
217// object (if collisions happen, if gravity effects it, ...).
218public enum CollisionFlags : uint
219{
220 CF_STATIC_OBJECT = 1 << 0,
221 CF_KINEMATIC_OBJECT = 1 << 1,
222 CF_NO_CONTACT_RESPONSE = 1 << 2,
223 CF_CUSTOM_MATERIAL_CALLBACK = 1 << 3,
224 CF_CHARACTER_OBJECT = 1 << 4,
225 CF_DISABLE_VISUALIZE_OBJECT = 1 << 5,
226 CF_DISABLE_SPU_COLLISION_PROCESS = 1 << 6,
227 // Following used by BulletSim to control collisions and updates
228 BS_SUBSCRIBE_COLLISION_EVENTS = 1 << 10, // return collision events from unmanaged to managed
229 BS_FLOATS_ON_WATER = 1 << 11, // the object should float at water level
230 BS_VEHICLE_COLLISIONS = 1 << 12, // return collisions for vehicle ground checking
231 BS_RETURN_ROOT_COMPOUND_SHAPE = 1 << 13, // return the pos/rot of the root shape in a compound shape
232 BS_NONE = 0,
233 BS_ALL = 0xFFFFFFFF
234};
235
236// Values f collisions groups and masks
237public enum CollisionFilterGroups : uint
238{
239 // Don't use the bit definitions!! Define the use in a
240 // filter/mask definition below. This way collision interactions
241 // are more easily found and debugged.
242 BNoneGroup = 0,
243 BDefaultGroup = 1 << 0, // 0001
244 BStaticGroup = 1 << 1, // 0002
245 BKinematicGroup = 1 << 2, // 0004
246 BDebrisGroup = 1 << 3, // 0008
247 BSensorTrigger = 1 << 4, // 0010
248 BCharacterGroup = 1 << 5, // 0020
249 BAllGroup = 0x000FFFFF,
250 // Filter groups defined by BulletSim
251 BGroundPlaneGroup = 1 << 10, // 0400
252 BTerrainGroup = 1 << 11, // 0800
253 BRaycastGroup = 1 << 12, // 1000
254 BSolidGroup = 1 << 13, // 2000
255 // BLinksetGroup = xx // a linkset proper is either static or dynamic
256 BLinksetChildGroup = 1 << 14, // 4000
257};
258
259// CFM controls the 'hardness' of the constraint. 0=fixed, 0..1=violatable. Default=0
260// ERP controls amount of correction per tick. Usable range=0.1..0.8. Default=0.2.
261public enum ConstraintParams : int
262{
263 BT_CONSTRAINT_ERP = 1, // this one is not used in Bullet as of 20120730
264 BT_CONSTRAINT_STOP_ERP,
265 BT_CONSTRAINT_CFM,
266 BT_CONSTRAINT_STOP_CFM,
267};
268public enum ConstraintParamAxis : int
269{
270 AXIS_LINEAR_X = 0,
271 AXIS_LINEAR_Y,
272 AXIS_LINEAR_Z,
273 AXIS_ANGULAR_X,
274 AXIS_ANGULAR_Y,
275 AXIS_ANGULAR_Z,
276 AXIS_LINEAR_ALL = 20, // these last three added by BulletSim so we don't have to do zillions of calls
277 AXIS_ANGULAR_ALL,
278 AXIS_ALL
279};
280
281public abstract class BSAPITemplate
282{
283// Returns the name of the underlying Bullet engine
284public abstract string BulletEngineName { get; }
285public abstract string BulletEngineVersion { get; protected set;}
286
287// Initialization and simulation
288public abstract BulletWorld Initialize(Vector3 maxPosition, ConfigurationParameters parms,
289 int maxCollisions, ref CollisionDesc[] collisionArray,
290 int maxUpdates, ref EntityProperties[] updateArray
291 );
292
293public abstract int PhysicsStep(BulletWorld world, float timeStep, int maxSubSteps, float fixedTimeStep,
294 out int updatedEntityCount, out int collidersCount);
295
296public abstract bool UpdateParameter(BulletWorld world, UInt32 localID, String parm, float value);
297
298public abstract void Shutdown(BulletWorld sim);
299
300public abstract bool PushUpdate(BulletBody obj);
301
302// =====================================================================================
303// Mesh, hull, shape and body creation helper routines
304public abstract BulletShape CreateMeshShape(BulletWorld world,
305 int indicesCount, int[] indices,
306 int verticesCount, float[] vertices );
307
308public abstract BulletShape CreateHullShape(BulletWorld world,
309 int hullCount, float[] hulls);
310
311public abstract BulletShape BuildHullShapeFromMesh(BulletWorld world, BulletShape meshShape);
312
313public abstract BulletShape BuildNativeShape(BulletWorld world, ShapeData shapeData);
314
315public abstract bool IsNativeShape(BulletShape shape);
316
317public abstract void SetShapeCollisionMargin(BulletShape shape, float margin);
318
319public abstract BulletShape BuildCapsuleShape(BulletWorld world, float radius, float height, Vector3 scale);
320
321public abstract BulletShape CreateCompoundShape(BulletWorld sim, bool enableDynamicAabbTree);
322
323public abstract int GetNumberOfCompoundChildren(BulletShape cShape);
324
325public abstract void AddChildShapeToCompoundShape(BulletShape cShape, BulletShape addShape, Vector3 pos, Quaternion rot);
326
327public abstract BulletShape GetChildShapeFromCompoundShapeIndex(BulletShape cShape, int indx);
328
329public abstract BulletShape RemoveChildShapeFromCompoundShapeIndex(BulletShape cShape, int indx);
330
331public abstract void RemoveChildShapeFromCompoundShape(BulletShape cShape, BulletShape removeShape);
332
333public abstract void UpdateChildTransform(BulletShape pShape, int childIndex, Vector3 pos, Quaternion rot, bool shouldRecalculateLocalAabb);
334
335public abstract void RecalculateCompoundShapeLocalAabb(BulletShape cShape);
336
337public abstract BulletShape DuplicateCollisionShape(BulletWorld sim, BulletShape srcShape, UInt32 id);
338
339public abstract bool DeleteCollisionShape(BulletWorld world, BulletShape shape);
340
341public abstract CollisionObjectTypes GetBodyType(BulletBody obj);
342
343public abstract BulletBody CreateBodyFromShape(BulletWorld sim, BulletShape shape, UInt32 id, Vector3 pos, Quaternion rot);
344
345public abstract BulletBody CreateBodyWithDefaultMotionState(BulletShape shape, UInt32 id, Vector3 pos, Quaternion rot);
346
347public abstract BulletBody CreateGhostFromShape(BulletWorld sim, BulletShape shape, UInt32 id, Vector3 pos, Quaternion rot);
348
349public abstract void DestroyObject(BulletWorld sim, BulletBody obj);
350
351// =====================================================================================
352public abstract BulletShape CreateGroundPlaneShape(UInt32 id, float height, float collisionMargin);
353
354public abstract BulletShape CreateTerrainShape(UInt32 id, Vector3 size, float minHeight, float maxHeight, float[] heightMap,
355 float scaleFactor, float collisionMargin);
356
357// =====================================================================================
358// Constraint creation and helper routines
359public abstract BulletConstraint Create6DofConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
360 Vector3 frame1loc, Quaternion frame1rot,
361 Vector3 frame2loc, Quaternion frame2rot,
362 bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
363
364public abstract BulletConstraint Create6DofConstraintToPoint(BulletWorld world, BulletBody obj1, BulletBody obj2,
365 Vector3 joinPoint,
366 bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
367
368public abstract BulletConstraint Create6DofConstraintFixed(BulletWorld world, BulletBody obj1,
369 Vector3 frameInBloc, Quaternion frameInBrot,
370 bool useLinearReferenceFrameB, bool disableCollisionsBetweenLinkedBodies);
371
372public abstract BulletConstraint Create6DofSpringConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
373 Vector3 frame1loc, Quaternion frame1rot,
374 Vector3 frame2loc, Quaternion frame2rot,
375 bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
376
377public abstract BulletConstraint CreateHingeConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
378 Vector3 pivotinA, Vector3 pivotinB,
379 Vector3 axisInA, Vector3 axisInB,
380 bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
381
382public abstract BulletConstraint CreateSliderConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
383 Vector3 frameInAloc, Quaternion frameInArot,
384 Vector3 frameInBloc, Quaternion frameInBrot,
385 bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
386
387public abstract BulletConstraint CreateConeTwistConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
388 Vector3 frameInAloc, Quaternion frameInArot,
389 Vector3 frameInBloc, Quaternion frameInBrot,
390 bool disableCollisionsBetweenLinkedBodies);
391
392public abstract BulletConstraint CreateGearConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
393 Vector3 axisInA, Vector3 axisInB,
394 float ratio, bool disableCollisionsBetweenLinkedBodies);
395
396public abstract BulletConstraint CreatePoint2PointConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
397 Vector3 pivotInA, Vector3 pivotInB,
398 bool disableCollisionsBetweenLinkedBodies);
399
400public abstract void SetConstraintEnable(BulletConstraint constrain, float numericTrueFalse);
401
402public abstract void SetConstraintNumSolverIterations(BulletConstraint constrain, float iterations);
403
404public abstract bool SetFrames(BulletConstraint constrain,
405 Vector3 frameA, Quaternion frameArot, Vector3 frameB, Quaternion frameBrot);
406
407public abstract bool SetLinearLimits(BulletConstraint constrain, Vector3 low, Vector3 hi);
408
409public abstract bool SetAngularLimits(BulletConstraint constrain, Vector3 low, Vector3 hi);
410
411public abstract bool UseFrameOffset(BulletConstraint constrain, float enable);
412
413public abstract bool TranslationalLimitMotor(BulletConstraint constrain, float enable, float targetVel, float maxMotorForce);
414
415public abstract bool SetBreakingImpulseThreshold(BulletConstraint constrain, float threshold);
416
417public abstract bool CalculateTransforms(BulletConstraint constrain);
418
419public abstract bool SetConstraintParam(BulletConstraint constrain, ConstraintParams paramIndex, float value, ConstraintParamAxis axis);
420
421public abstract bool DestroyConstraint(BulletWorld world, BulletConstraint constrain);
422
423// =====================================================================================
424// btCollisionWorld entries
425public abstract void UpdateSingleAabb(BulletWorld world, BulletBody obj);
426
427public abstract void UpdateAabbs(BulletWorld world);
428
429public abstract bool GetForceUpdateAllAabbs(BulletWorld world);
430
431public abstract void SetForceUpdateAllAabbs(BulletWorld world, bool force);
432
433// =====================================================================================
434// btDynamicsWorld entries
435// public abstract bool AddObjectToWorld(BulletWorld world, BulletBody obj, Vector3 pos, Quaternion rot);
436public abstract bool AddObjectToWorld(BulletWorld world, BulletBody obj);
437
438public abstract bool RemoveObjectFromWorld(BulletWorld world, BulletBody obj);
439
440public abstract bool AddConstraintToWorld(BulletWorld world, BulletConstraint constrain, bool disableCollisionsBetweenLinkedObjects);
441
442public abstract bool RemoveConstraintFromWorld(BulletWorld world, BulletConstraint constrain);
443// =====================================================================================
444// btCollisionObject entries
445public abstract Vector3 GetAnisotripicFriction(BulletConstraint constrain);
446
447public abstract Vector3 SetAnisotripicFriction(BulletConstraint constrain, Vector3 frict);
448
449public abstract bool HasAnisotripicFriction(BulletConstraint constrain);
450
451public abstract void SetContactProcessingThreshold(BulletBody obj, float val);
452
453public abstract float GetContactProcessingThreshold(BulletBody obj);
454
455public abstract bool IsStaticObject(BulletBody obj);
456
457public abstract bool IsKinematicObject(BulletBody obj);
458
459public abstract bool IsStaticOrKinematicObject(BulletBody obj);
460
461public abstract bool HasContactResponse(BulletBody obj);
462
463public abstract void SetCollisionShape(BulletWorld sim, BulletBody obj, BulletShape shape);
464
465public abstract BulletShape GetCollisionShape(BulletBody obj);
466
467public abstract int GetActivationState(BulletBody obj);
468
469public abstract void SetActivationState(BulletBody obj, int state);
470
471public abstract void SetDeactivationTime(BulletBody obj, float dtime);
472
473public abstract float GetDeactivationTime(BulletBody obj);
474
475public abstract void ForceActivationState(BulletBody obj, ActivationState state);
476
477public abstract void Activate(BulletBody obj, bool forceActivation);
478
479public abstract bool IsActive(BulletBody obj);
480
481public abstract void SetRestitution(BulletBody obj, float val);
482
483public abstract float GetRestitution(BulletBody obj);
484
485public abstract void SetFriction(BulletBody obj, float val);
486
487public abstract float GetFriction(BulletBody obj);
488
489public abstract Vector3 GetPosition(BulletBody obj);
490
491public abstract Quaternion GetOrientation(BulletBody obj);
492
493public abstract void SetTranslation(BulletBody obj, Vector3 position, Quaternion rotation);
494
495// public abstract IntPtr GetBroadphaseHandle(BulletBody obj);
496
497// public abstract void SetBroadphaseHandle(BulletBody obj, IntPtr handle);
498
499public abstract void SetInterpolationLinearVelocity(BulletBody obj, Vector3 vel);
500
501public abstract void SetInterpolationAngularVelocity(BulletBody obj, Vector3 vel);
502
503public abstract void SetInterpolationVelocity(BulletBody obj, Vector3 linearVel, Vector3 angularVel);
504
505public abstract float GetHitFraction(BulletBody obj);
506
507public abstract void SetHitFraction(BulletBody obj, float val);
508
509public abstract CollisionFlags GetCollisionFlags(BulletBody obj);
510
511public abstract CollisionFlags SetCollisionFlags(BulletBody obj, CollisionFlags flags);
512
513public abstract CollisionFlags AddToCollisionFlags(BulletBody obj, CollisionFlags flags);
514
515public abstract CollisionFlags RemoveFromCollisionFlags(BulletBody obj, CollisionFlags flags);
516
517public abstract float GetCcdMotionThreshold(BulletBody obj);
518
519public abstract void SetCcdMotionThreshold(BulletBody obj, float val);
520
521public abstract float GetCcdSweptSphereRadius(BulletBody obj);
522
523public abstract void SetCcdSweptSphereRadius(BulletBody obj, float val);
524
525public abstract IntPtr GetUserPointer(BulletBody obj);
526
527public abstract void SetUserPointer(BulletBody obj, IntPtr val);
528
529// =====================================================================================
530// btRigidBody entries
531public abstract void ApplyGravity(BulletBody obj);
532
533public abstract void SetGravity(BulletBody obj, Vector3 val);
534
535public abstract Vector3 GetGravity(BulletBody obj);
536
537public abstract void SetDamping(BulletBody obj, float lin_damping, float ang_damping);
538
539public abstract void SetLinearDamping(BulletBody obj, float lin_damping);
540
541public abstract void SetAngularDamping(BulletBody obj, float ang_damping);
542
543public abstract float GetLinearDamping(BulletBody obj);
544
545public abstract float GetAngularDamping(BulletBody obj);
546
547public abstract float GetLinearSleepingThreshold(BulletBody obj);
548
549public abstract void ApplyDamping(BulletBody obj, float timeStep);
550
551public abstract void SetMassProps(BulletBody obj, float mass, Vector3 inertia);
552
553public abstract Vector3 GetLinearFactor(BulletBody obj);
554
555public abstract void SetLinearFactor(BulletBody obj, Vector3 factor);
556
557public abstract void SetCenterOfMassByPosRot(BulletBody obj, Vector3 pos, Quaternion rot);
558
559// Add a force to the object as if its mass is one.
560public abstract void ApplyCentralForce(BulletBody obj, Vector3 force);
561
562// Set the force being applied to the object as if its mass is one.
563public abstract void SetObjectForce(BulletBody obj, Vector3 force);
564
565public abstract Vector3 GetTotalForce(BulletBody obj);
566
567public abstract Vector3 GetTotalTorque(BulletBody obj);
568
569public abstract Vector3 GetInvInertiaDiagLocal(BulletBody obj);
570
571public abstract void SetInvInertiaDiagLocal(BulletBody obj, Vector3 inert);
572
573public abstract void SetSleepingThresholds(BulletBody obj, float lin_threshold, float ang_threshold);
574
575public abstract void ApplyTorque(BulletBody obj, Vector3 torque);
576
577// Apply force at the given point. Will add torque to the object.
578public abstract void ApplyForce(BulletBody obj, Vector3 force, Vector3 pos);
579
580// Apply impulse to the object. Same as "ApplycentralForce" but force scaled by object's mass.
581public abstract void ApplyCentralImpulse(BulletBody obj, Vector3 imp);
582
583// Apply impulse to the object's torque. Force is scaled by object's mass.
584public abstract void ApplyTorqueImpulse(BulletBody obj, Vector3 imp);
585
586// Apply impulse at the point given. For is scaled by object's mass and effects both linear and angular forces.
587public abstract void ApplyImpulse(BulletBody obj, Vector3 imp, Vector3 pos);
588
589public abstract void ClearForces(BulletBody obj);
590
591public abstract void ClearAllForces(BulletBody obj);
592
593public abstract void UpdateInertiaTensor(BulletBody obj);
594
595public abstract Vector3 GetLinearVelocity(BulletBody obj);
596
597public abstract Vector3 GetAngularVelocity(BulletBody obj);
598
599public abstract void SetLinearVelocity(BulletBody obj, Vector3 val);
600
601public abstract void SetAngularVelocity(BulletBody obj, Vector3 angularVelocity);
602
603public abstract Vector3 GetVelocityInLocalPoint(BulletBody obj, Vector3 pos);
604
605public abstract void Translate(BulletBody obj, Vector3 trans);
606
607public abstract void UpdateDeactivation(BulletBody obj, float timeStep);
608
609public abstract bool WantsSleeping(BulletBody obj);
610
611public abstract void SetAngularFactor(BulletBody obj, float factor);
612
613public abstract void SetAngularFactorV(BulletBody obj, Vector3 factor);
614
615public abstract Vector3 GetAngularFactor(BulletBody obj);
616
617public abstract bool IsInWorld(BulletWorld world, BulletBody obj);
618
619public abstract void AddConstraintRef(BulletBody obj, BulletConstraint constrain);
620
621public abstract void RemoveConstraintRef(BulletBody obj, BulletConstraint constrain);
622
623public abstract BulletConstraint GetConstraintRef(BulletBody obj, int index);
624
625public abstract int GetNumConstraintRefs(BulletBody obj);
626
627public abstract bool SetCollisionGroupMask(BulletBody body, UInt32 filter, UInt32 mask);
628
629// =====================================================================================
630// btCollisionShape entries
631
632public abstract float GetAngularMotionDisc(BulletShape shape);
633
634public abstract float GetContactBreakingThreshold(BulletShape shape, float defaultFactor);
635
636public abstract bool IsPolyhedral(BulletShape shape);
637
638public abstract bool IsConvex2d(BulletShape shape);
639
640public abstract bool IsConvex(BulletShape shape);
641
642public abstract bool IsNonMoving(BulletShape shape);
643
644public abstract bool IsConcave(BulletShape shape);
645
646public abstract bool IsCompound(BulletShape shape);
647
648public abstract bool IsSoftBody(BulletShape shape);
649
650public abstract bool IsInfinite(BulletShape shape);
651
652public abstract void SetLocalScaling(BulletShape shape, Vector3 scale);
653
654public abstract Vector3 GetLocalScaling(BulletShape shape);
655
656public abstract Vector3 CalculateLocalInertia(BulletShape shape, float mass);
657
658public abstract int GetShapeType(BulletShape shape);
659
660public abstract void SetMargin(BulletShape shape, float val);
661
662public abstract float GetMargin(BulletShape shape);
663
664// =====================================================================================
665// Debugging
666public virtual void DumpRigidBody(BulletWorld sim, BulletBody collisionObject) { }
667
668public virtual void DumpCollisionShape(BulletWorld sim, BulletShape collisionShape) { }
669
670public virtual void DumpConstraint(BulletWorld sim, BulletConstraint constrain) { }
671
672public virtual void DumpActivationInfo(BulletWorld sim) { }
673
674public virtual void DumpAllInfo(BulletWorld sim) { }
675
676public virtual void DumpPhysicsStatistics(BulletWorld sim) { }
677
678public virtual void ResetBroadphasePool(BulletWorld sim) { }
679
680public virtual void ResetConstraintSolver(BulletWorld sim) { }
681
682};
683}