clockwerk-opensim – Blame information for rev 1

Subversion Repositories:
Rev:
Rev Author Line No. Line
1 vero 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 */
27 using System;
28 using System.Collections.Generic;
29 using System.Runtime.InteropServices;
30 using System.Security;
31 using System.Text;
32 using OpenMetaverse;
33  
34 namespace OpenSim.Region.Physics.BulletSPlugin {
35  
36 // Constraint type values as defined by Bullet
37 public 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)]
55 public struct ConvexHull
56 {
57 Vector3 Offset;
58 int VertexCount;
59 Vector3[] Vertices;
60 }
61 public 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
82 public 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)]
94 public 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)]
118 public struct SweepHit
119 {
120 public UInt32 ID;
121 public float Fraction;
122 public Vector3 Normal;
123 public Vector3 Point;
124 }
125 [StructLayout(LayoutKind.Sequential)]
126 public struct RaycastHit
127 {
128 public UInt32 ID;
129 public float Fraction;
130 public Vector3 Normal;
131 }
132 [StructLayout(LayoutKind.Sequential)]
133 public 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)]
142 public 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)]
175 public 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)]
202 public 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 }
215  
216 // The states a bullet collision object can have
217 public enum ActivationState : uint
218 {
219 ACTIVE_TAG = 1,
220 ISLAND_SLEEPING,
221 WANTS_DEACTIVATION,
222 DISABLE_DEACTIVATION,
223 DISABLE_SIMULATION,
224 }
225  
226 public enum CollisionObjectTypes : int
227 {
228 CO_COLLISION_OBJECT = 1 << 0,
229 CO_RIGID_BODY = 1 << 1,
230 CO_GHOST_OBJECT = 1 << 2,
231 CO_SOFT_BODY = 1 << 3,
232 CO_HF_FLUID = 1 << 4,
233 CO_USER_TYPE = 1 << 5,
234 }
235  
236 // Values used by Bullet and BulletSim to control object properties.
237 // Bullet's "CollisionFlags" has more to do with operations on the
238 // object (if collisions happen, if gravity effects it, ...).
239 public enum CollisionFlags : uint
240 {
241 CF_STATIC_OBJECT = 1 << 0,
242 CF_KINEMATIC_OBJECT = 1 << 1,
243 CF_NO_CONTACT_RESPONSE = 1 << 2,
244 CF_CUSTOM_MATERIAL_CALLBACK = 1 << 3,
245 CF_CHARACTER_OBJECT = 1 << 4,
246 CF_DISABLE_VISUALIZE_OBJECT = 1 << 5,
247 CF_DISABLE_SPU_COLLISION_PROCESS = 1 << 6,
248 // Following used by BulletSim to control collisions and updates
249 BS_SUBSCRIBE_COLLISION_EVENTS = 1 << 10, // return collision events from unmanaged to managed
250 BS_FLOATS_ON_WATER = 1 << 11, // the object should float at water level
251 BS_VEHICLE_COLLISIONS = 1 << 12, // return collisions for vehicle ground checking
252 BS_RETURN_ROOT_COMPOUND_SHAPE = 1 << 13, // return the pos/rot of the root shape in a compound shape
253 BS_NONE = 0,
254 BS_ALL = 0x7FFF // collision flags are a signed short
255 };
256  
257 // Values f collisions groups and masks
258 public enum CollisionFilterGroups : uint
259 {
260 // Don't use the bit definitions!! Define the use in a
261 // filter/mask definition below. This way collision interactions
262 // are more easily found and debugged.
263 BNoneGroup = 0,
264 BDefaultGroup = 1 << 0, // 0001
265 BStaticGroup = 1 << 1, // 0002
266 BKinematicGroup = 1 << 2, // 0004
267 BDebrisGroup = 1 << 3, // 0008
268 BSensorTrigger = 1 << 4, // 0010
269 BCharacterGroup = 1 << 5, // 0020
270 BAllGroup = 0x0007FFF, // collision flags are a signed short
271 // Filter groups defined by BulletSim
272 BGroundPlaneGroup = 1 << 8, // 0400
273 BTerrainGroup = 1 << 9, // 0800
274 BRaycastGroup = 1 << 10, // 1000
275 BSolidGroup = 1 << 11, // 2000
276 // BLinksetGroup = xx // a linkset proper is either static or dynamic
277 BLinksetChildGroup = 1 << 12, // 4000
278 };
279  
280 // CFM controls the 'hardness' of the constraint. 0=fixed, 0..1=violatable. Default=0
281 // ERP controls amount of correction per tick. Usable range=0.1..0.8. Default=0.2.
282 public enum ConstraintParams : int
283 {
284 BT_CONSTRAINT_ERP = 1, // this one is not used in Bullet as of 20120730
285 BT_CONSTRAINT_STOP_ERP,
286 BT_CONSTRAINT_CFM,
287 BT_CONSTRAINT_STOP_CFM,
288 };
289 public enum ConstraintParamAxis : int
290 {
291 AXIS_LINEAR_X = 0,
292 AXIS_LINEAR_Y,
293 AXIS_LINEAR_Z,
294 AXIS_ANGULAR_X,
295 AXIS_ANGULAR_Y,
296 AXIS_ANGULAR_Z,
297 AXIS_LINEAR_ALL = 20, // added by BulletSim so we don't have to do zillions of calls
298 AXIS_ANGULAR_ALL,
299 AXIS_ALL
300 };
301  
302 public abstract class BSAPITemplate
303 {
304 // Returns the name of the underlying Bullet engine
305 public abstract string BulletEngineName { get; }
306 public abstract string BulletEngineVersion { get; protected set;}
307  
308 // Initialization and simulation
309 public abstract BulletWorld Initialize(Vector3 maxPosition, ConfigurationParameters parms,
310 int maxCollisions, ref CollisionDesc[] collisionArray,
311 int maxUpdates, ref EntityProperties[] updateArray
312 );
313  
314 public abstract int PhysicsStep(BulletWorld world, float timeStep, int maxSubSteps, float fixedTimeStep,
315 out int updatedEntityCount, out int collidersCount);
316  
317 public abstract bool UpdateParameter(BulletWorld world, UInt32 localID, String parm, float value);
318  
319 public abstract void Shutdown(BulletWorld sim);
320  
321 public abstract bool PushUpdate(BulletBody obj);
322  
323 // =====================================================================================
324 // Mesh, hull, shape and body creation helper routines
325 public abstract BulletShape CreateMeshShape(BulletWorld world,
326 int indicesCount, int[] indices,
327 int verticesCount, float[] vertices );
328  
329 public abstract BulletShape CreateGImpactShape(BulletWorld world,
330 int indicesCount, int[] indices,
331 int verticesCount, float[] vertices );
332  
333 public abstract BulletShape CreateHullShape(BulletWorld world,
334 int hullCount, float[] hulls);
335  
336 public abstract BulletShape BuildHullShapeFromMesh(BulletWorld world, BulletShape meshShape, HACDParams parms);
337  
338 public abstract BulletShape BuildConvexHullShapeFromMesh(BulletWorld world, BulletShape meshShape);
339  
340 public abstract BulletShape CreateConvexHullShape(BulletWorld world,
341 int indicesCount, int[] indices,
342 int verticesCount, float[] vertices );
343  
344 public abstract BulletShape BuildNativeShape(BulletWorld world, ShapeData shapeData);
345  
346 public abstract bool IsNativeShape(BulletShape shape);
347  
348 public abstract void SetShapeCollisionMargin(BulletShape shape, float margin);
349  
350 public abstract BulletShape BuildCapsuleShape(BulletWorld world, float radius, float height, Vector3 scale);
351  
352 public abstract BulletShape CreateCompoundShape(BulletWorld sim, bool enableDynamicAabbTree);
353  
354 public abstract int GetNumberOfCompoundChildren(BulletShape cShape);
355  
356 public abstract void AddChildShapeToCompoundShape(BulletShape cShape, BulletShape addShape, Vector3 pos, Quaternion rot);
357  
358 public abstract BulletShape GetChildShapeFromCompoundShapeIndex(BulletShape cShape, int indx);
359  
360 public abstract BulletShape RemoveChildShapeFromCompoundShapeIndex(BulletShape cShape, int indx);
361  
362 public abstract void RemoveChildShapeFromCompoundShape(BulletShape cShape, BulletShape removeShape);
363  
364 public abstract void UpdateChildTransform(BulletShape pShape, int childIndex, Vector3 pos, Quaternion rot, bool shouldRecalculateLocalAabb);
365  
366 public abstract void RecalculateCompoundShapeLocalAabb(BulletShape cShape);
367  
368 public abstract BulletShape DuplicateCollisionShape(BulletWorld sim, BulletShape srcShape, UInt32 id);
369  
370 public abstract bool DeleteCollisionShape(BulletWorld world, BulletShape shape);
371  
372 public abstract CollisionObjectTypes GetBodyType(BulletBody obj);
373  
374 public abstract BulletBody CreateBodyFromShape(BulletWorld sim, BulletShape shape, UInt32 id, Vector3 pos, Quaternion rot);
375  
376 public abstract BulletBody CreateBodyWithDefaultMotionState(BulletShape shape, UInt32 id, Vector3 pos, Quaternion rot);
377  
378 public abstract BulletBody CreateGhostFromShape(BulletWorld sim, BulletShape shape, UInt32 id, Vector3 pos, Quaternion rot);
379  
380 public abstract void DestroyObject(BulletWorld sim, BulletBody obj);
381  
382 // =====================================================================================
383 public abstract BulletShape CreateGroundPlaneShape(UInt32 id, float height, float collisionMargin);
384  
385 public abstract BulletShape CreateTerrainShape(UInt32 id, Vector3 size, float minHeight, float maxHeight, float[] heightMap,
386 float scaleFactor, float collisionMargin);
387  
388 // =====================================================================================
389 // Constraint creation and helper routines
390 public abstract BulletConstraint Create6DofConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
391 Vector3 frame1loc, Quaternion frame1rot,
392 Vector3 frame2loc, Quaternion frame2rot,
393 bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
394  
395 public abstract BulletConstraint Create6DofConstraintToPoint(BulletWorld world, BulletBody obj1, BulletBody obj2,
396 Vector3 joinPoint,
397 bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
398  
399 public abstract BulletConstraint Create6DofConstraintFixed(BulletWorld world, BulletBody obj1,
400 Vector3 frameInBloc, Quaternion frameInBrot,
401 bool useLinearReferenceFrameB, bool disableCollisionsBetweenLinkedBodies);
402  
403 public abstract BulletConstraint Create6DofSpringConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
404 Vector3 frame1loc, Quaternion frame1rot,
405 Vector3 frame2loc, Quaternion frame2rot,
406 bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
407  
408 public abstract BulletConstraint CreateHingeConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
409 Vector3 pivotinA, Vector3 pivotinB,
410 Vector3 axisInA, Vector3 axisInB,
411 bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
412  
413 public abstract BulletConstraint CreateSliderConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
414 Vector3 frameInAloc, Quaternion frameInArot,
415 Vector3 frameInBloc, Quaternion frameInBrot,
416 bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
417  
418 public abstract BulletConstraint CreateConeTwistConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
419 Vector3 frameInAloc, Quaternion frameInArot,
420 Vector3 frameInBloc, Quaternion frameInBrot,
421 bool disableCollisionsBetweenLinkedBodies);
422  
423 public abstract BulletConstraint CreateGearConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
424 Vector3 axisInA, Vector3 axisInB,
425 float ratio, bool disableCollisionsBetweenLinkedBodies);
426  
427 public abstract BulletConstraint CreatePoint2PointConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
428 Vector3 pivotInA, Vector3 pivotInB,
429 bool disableCollisionsBetweenLinkedBodies);
430  
431 public abstract void SetConstraintEnable(BulletConstraint constrain, float numericTrueFalse);
432  
433 public abstract void SetConstraintNumSolverIterations(BulletConstraint constrain, float iterations);
434  
435 public abstract bool SetFrames(BulletConstraint constrain,
436 Vector3 frameA, Quaternion frameArot, Vector3 frameB, Quaternion frameBrot);
437  
438 public abstract bool SetLinearLimits(BulletConstraint constrain, Vector3 low, Vector3 hi);
439  
440 public abstract bool SetAngularLimits(BulletConstraint constrain, Vector3 low, Vector3 hi);
441  
442 public abstract bool UseFrameOffset(BulletConstraint constrain, float enable);
443  
444 public abstract bool TranslationalLimitMotor(BulletConstraint constrain, float enable, float targetVel, float maxMotorForce);
445  
446 public abstract bool SetBreakingImpulseThreshold(BulletConstraint constrain, float threshold);
447  
448 public const int HINGE_NOT_SPECIFIED = -1;
449 public abstract bool HingeSetLimits(BulletConstraint constrain, float low, float high, float softness, float bias, float relaxation);
450  
451 public abstract bool SpringEnable(BulletConstraint constrain, int index, float numericTrueFalse);
452  
453 public const int SPRING_NOT_SPECIFIED = -1;
454 public abstract bool SpringSetEquilibriumPoint(BulletConstraint constrain, int index, float equilibriumPoint);
455  
456 public abstract bool SpringSetStiffness(BulletConstraint constrain, int index, float stiffnesss);
457  
458 public abstract bool SpringSetDamping(BulletConstraint constrain, int index, float damping);
459  
460 public const int SLIDER_LOWER_LIMIT = 0;
461 public const int SLIDER_UPPER_LIMIT = 1;
462 public const int SLIDER_LINEAR = 2;
463 public const int SLIDER_ANGULAR = 3;
464 public abstract bool SliderSetLimits(BulletConstraint constrain, int lowerUpper, int linAng, float val);
465  
466 public const int SLIDER_SET_SOFTNESS = 4;
467 public const int SLIDER_SET_RESTITUTION = 5;
468 public const int SLIDER_SET_DAMPING = 6;
469 public const int SLIDER_SET_DIRECTION = 7;
470 public const int SLIDER_SET_LIMIT = 8;
471 public const int SLIDER_SET_ORTHO = 9;
472 public abstract bool SliderSet(BulletConstraint constrain, int softRestDamp, int dirLimOrtho, int linAng, float val);
473  
474 public abstract bool SliderMotorEnable(BulletConstraint constrain, int linAng, float numericTrueFalse);
475  
476 public const int SLIDER_MOTOR_VELOCITY = 10;
477 public const int SLIDER_MAX_MOTOR_FORCE = 11;
478 public abstract bool SliderMotor(BulletConstraint constrain, int forceVel, int linAng, float val);
479  
480 public abstract bool CalculateTransforms(BulletConstraint constrain);
481  
482 public abstract bool SetConstraintParam(BulletConstraint constrain, ConstraintParams paramIndex, float value, ConstraintParamAxis axis);
483  
484 public abstract bool DestroyConstraint(BulletWorld world, BulletConstraint constrain);
485  
486 // =====================================================================================
487 // btCollisionWorld entries
488 public abstract void UpdateSingleAabb(BulletWorld world, BulletBody obj);
489  
490 public abstract void UpdateAabbs(BulletWorld world);
491  
492 public abstract bool GetForceUpdateAllAabbs(BulletWorld world);
493  
494 public abstract void SetForceUpdateAllAabbs(BulletWorld world, bool force);
495  
496 // =====================================================================================
497 // btDynamicsWorld entries
498 // public abstract bool AddObjectToWorld(BulletWorld world, BulletBody obj, Vector3 pos, Quaternion rot);
499 public abstract bool AddObjectToWorld(BulletWorld world, BulletBody obj);
500  
501 public abstract bool RemoveObjectFromWorld(BulletWorld world, BulletBody obj);
502  
503 public abstract bool ClearCollisionProxyCache(BulletWorld world, BulletBody obj);
504  
505 public abstract bool AddConstraintToWorld(BulletWorld world, BulletConstraint constrain, bool disableCollisionsBetweenLinkedObjects);
506  
507 public abstract bool RemoveConstraintFromWorld(BulletWorld world, BulletConstraint constrain);
508 // =====================================================================================
509 // btCollisionObject entries
510 public abstract Vector3 GetAnisotripicFriction(BulletConstraint constrain);
511  
512 public abstract Vector3 SetAnisotripicFriction(BulletConstraint constrain, Vector3 frict);
513  
514 public abstract bool HasAnisotripicFriction(BulletConstraint constrain);
515  
516 public abstract void SetContactProcessingThreshold(BulletBody obj, float val);
517  
518 public abstract float GetContactProcessingThreshold(BulletBody obj);
519  
520 public abstract bool IsStaticObject(BulletBody obj);
521  
522 public abstract bool IsKinematicObject(BulletBody obj);
523  
524 public abstract bool IsStaticOrKinematicObject(BulletBody obj);
525  
526 public abstract bool HasContactResponse(BulletBody obj);
527  
528 public abstract void SetCollisionShape(BulletWorld sim, BulletBody obj, BulletShape shape);
529  
530 public abstract BulletShape GetCollisionShape(BulletBody obj);
531  
532 public abstract int GetActivationState(BulletBody obj);
533  
534 public abstract void SetActivationState(BulletBody obj, int state);
535  
536 public abstract void SetDeactivationTime(BulletBody obj, float dtime);
537  
538 public abstract float GetDeactivationTime(BulletBody obj);
539  
540 public abstract void ForceActivationState(BulletBody obj, ActivationState state);
541  
542 public abstract void Activate(BulletBody obj, bool forceActivation);
543  
544 public abstract bool IsActive(BulletBody obj);
545  
546 public abstract void SetRestitution(BulletBody obj, float val);
547  
548 public abstract float GetRestitution(BulletBody obj);
549  
550 public abstract void SetFriction(BulletBody obj, float val);
551  
552 public abstract float GetFriction(BulletBody obj);
553  
554 public abstract Vector3 GetPosition(BulletBody obj);
555  
556 public abstract Quaternion GetOrientation(BulletBody obj);
557  
558 public abstract void SetTranslation(BulletBody obj, Vector3 position, Quaternion rotation);
559  
560 // public abstract IntPtr GetBroadphaseHandle(BulletBody obj);
561  
562 // public abstract void SetBroadphaseHandle(BulletBody obj, IntPtr handle);
563  
564 public abstract void SetInterpolationLinearVelocity(BulletBody obj, Vector3 vel);
565  
566 public abstract void SetInterpolationAngularVelocity(BulletBody obj, Vector3 vel);
567  
568 public abstract void SetInterpolationVelocity(BulletBody obj, Vector3 linearVel, Vector3 angularVel);
569  
570 public abstract float GetHitFraction(BulletBody obj);
571  
572 public abstract void SetHitFraction(BulletBody obj, float val);
573  
574 public abstract CollisionFlags GetCollisionFlags(BulletBody obj);
575  
576 public abstract CollisionFlags SetCollisionFlags(BulletBody obj, CollisionFlags flags);
577  
578 public abstract CollisionFlags AddToCollisionFlags(BulletBody obj, CollisionFlags flags);
579  
580 public abstract CollisionFlags RemoveFromCollisionFlags(BulletBody obj, CollisionFlags flags);
581  
582 public abstract float GetCcdMotionThreshold(BulletBody obj);
583  
584 public abstract void SetCcdMotionThreshold(BulletBody obj, float val);
585  
586 public abstract float GetCcdSweptSphereRadius(BulletBody obj);
587  
588 public abstract void SetCcdSweptSphereRadius(BulletBody obj, float val);
589  
590 public abstract IntPtr GetUserPointer(BulletBody obj);
591  
592 public abstract void SetUserPointer(BulletBody obj, IntPtr val);
593  
594 // =====================================================================================
595 // btRigidBody entries
596 public abstract void ApplyGravity(BulletBody obj);
597  
598 public abstract void SetGravity(BulletBody obj, Vector3 val);
599  
600 public abstract Vector3 GetGravity(BulletBody obj);
601  
602 public abstract void SetDamping(BulletBody obj, float lin_damping, float ang_damping);
603  
604 public abstract void SetLinearDamping(BulletBody obj, float lin_damping);
605  
606 public abstract void SetAngularDamping(BulletBody obj, float ang_damping);
607  
608 public abstract float GetLinearDamping(BulletBody obj);
609  
610 public abstract float GetAngularDamping(BulletBody obj);
611  
612 public abstract float GetLinearSleepingThreshold(BulletBody obj);
613  
614 public abstract void ApplyDamping(BulletBody obj, float timeStep);
615  
616 public abstract void SetMassProps(BulletBody obj, float mass, Vector3 inertia);
617  
618 public abstract Vector3 GetLinearFactor(BulletBody obj);
619  
620 public abstract void SetLinearFactor(BulletBody obj, Vector3 factor);
621  
622 public abstract void SetCenterOfMassByPosRot(BulletBody obj, Vector3 pos, Quaternion rot);
623  
624 // Add a force to the object as if its mass is one.
625 public abstract void ApplyCentralForce(BulletBody obj, Vector3 force);
626  
627 // Set the force being applied to the object as if its mass is one.
628 public abstract void SetObjectForce(BulletBody obj, Vector3 force);
629  
630 public abstract Vector3 GetTotalForce(BulletBody obj);
631  
632 public abstract Vector3 GetTotalTorque(BulletBody obj);
633  
634 public abstract Vector3 GetInvInertiaDiagLocal(BulletBody obj);
635  
636 public abstract void SetInvInertiaDiagLocal(BulletBody obj, Vector3 inert);
637  
638 public abstract void SetSleepingThresholds(BulletBody obj, float lin_threshold, float ang_threshold);
639  
640 public abstract void ApplyTorque(BulletBody obj, Vector3 torque);
641  
642 // Apply force at the given point. Will add torque to the object.
643 public abstract void ApplyForce(BulletBody obj, Vector3 force, Vector3 pos);
644  
645 // Apply impulse to the object. Same as "ApplycentralForce" but force scaled by object's mass.
646 public abstract void ApplyCentralImpulse(BulletBody obj, Vector3 imp);
647  
648 // Apply impulse to the object's torque. Force is scaled by object's mass.
649 public abstract void ApplyTorqueImpulse(BulletBody obj, Vector3 imp);
650  
651 // Apply impulse at the point given. For is scaled by object's mass and effects both linear and angular forces.
652 public abstract void ApplyImpulse(BulletBody obj, Vector3 imp, Vector3 pos);
653  
654 public abstract void ClearForces(BulletBody obj);
655  
656 public abstract void ClearAllForces(BulletBody obj);
657  
658 public abstract void UpdateInertiaTensor(BulletBody obj);
659  
660 public abstract Vector3 GetLinearVelocity(BulletBody obj);
661  
662 public abstract Vector3 GetAngularVelocity(BulletBody obj);
663  
664 public abstract void SetLinearVelocity(BulletBody obj, Vector3 val);
665  
666 public abstract void SetAngularVelocity(BulletBody obj, Vector3 angularVelocity);
667  
668 public abstract Vector3 GetVelocityInLocalPoint(BulletBody obj, Vector3 pos);
669  
670 public abstract void Translate(BulletBody obj, Vector3 trans);
671  
672 public abstract void UpdateDeactivation(BulletBody obj, float timeStep);
673  
674 public abstract bool WantsSleeping(BulletBody obj);
675  
676 public abstract void SetAngularFactor(BulletBody obj, float factor);
677  
678 public abstract void SetAngularFactorV(BulletBody obj, Vector3 factor);
679  
680 public abstract Vector3 GetAngularFactor(BulletBody obj);
681  
682 public abstract bool IsInWorld(BulletWorld world, BulletBody obj);
683  
684 public abstract void AddConstraintRef(BulletBody obj, BulletConstraint constrain);
685  
686 public abstract void RemoveConstraintRef(BulletBody obj, BulletConstraint constrain);
687  
688 public abstract BulletConstraint GetConstraintRef(BulletBody obj, int index);
689  
690 public abstract int GetNumConstraintRefs(BulletBody obj);
691  
692 public abstract bool SetCollisionGroupMask(BulletBody body, UInt32 filter, UInt32 mask);
693  
694 // =====================================================================================
695 // btCollisionShape entries
696  
697 public abstract float GetAngularMotionDisc(BulletShape shape);
698  
699 public abstract float GetContactBreakingThreshold(BulletShape shape, float defaultFactor);
700  
701 public abstract bool IsPolyhedral(BulletShape shape);
702  
703 public abstract bool IsConvex2d(BulletShape shape);
704  
705 public abstract bool IsConvex(BulletShape shape);
706  
707 public abstract bool IsNonMoving(BulletShape shape);
708  
709 public abstract bool IsConcave(BulletShape shape);
710  
711 public abstract bool IsCompound(BulletShape shape);
712  
713 public abstract bool IsSoftBody(BulletShape shape);
714  
715 public abstract bool IsInfinite(BulletShape shape);
716  
717 public abstract void SetLocalScaling(BulletShape shape, Vector3 scale);
718  
719 public abstract Vector3 GetLocalScaling(BulletShape shape);
720  
721 public abstract Vector3 CalculateLocalInertia(BulletShape shape, float mass);
722  
723 public abstract int GetShapeType(BulletShape shape);
724  
725 public abstract void SetMargin(BulletShape shape, float val);
726  
727 public abstract float GetMargin(BulletShape shape);
728  
729 // =====================================================================================
730 // Debugging
731 public virtual void DumpRigidBody(BulletWorld sim, BulletBody collisionObject) { }
732  
733 public virtual void DumpCollisionShape(BulletWorld sim, BulletShape collisionShape) { }
734  
735 public virtual void DumpConstraint(BulletWorld sim, BulletConstraint constrain) { }
736  
737 public virtual void DumpActivationInfo(BulletWorld sim) { }
738  
739 public virtual void DumpAllInfo(BulletWorld sim) { }
740  
741 public virtual void DumpPhysicsStatistics(BulletWorld sim) { }
742  
743 public virtual void ResetBroadphasePool(BulletWorld sim) { }
744  
745 public virtual void ResetConstraintSolver(BulletWorld sim) { }
746  
747 };
748 }