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