aboutsummaryrefslogtreecommitdiffstatshomepage
path: root/OpenSim/Region/Physics/BulletSPlugin/BSAPIXNA.cs
diff options
context:
space:
mode:
Diffstat (limited to 'OpenSim/Region/Physics/BulletSPlugin/BSAPIXNA.cs')
-rwxr-xr-xOpenSim/Region/Physics/BulletSPlugin/BSAPIXNA.cs1597
1 files changed, 1597 insertions, 0 deletions
diff --git a/OpenSim/Region/Physics/BulletSPlugin/BSAPIXNA.cs b/OpenSim/Region/Physics/BulletSPlugin/BSAPIXNA.cs
new file mode 100755
index 0000000..0c7f315
--- /dev/null
+++ b/OpenSim/Region/Physics/BulletSPlugin/BSAPIXNA.cs
@@ -0,0 +1,1597 @@
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 copyrightD
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.IO;
30using System.Text;
31
32using OpenSim.Framework;
33
34using OpenMetaverse;
35
36using BulletXNA;
37using BulletXNA.LinearMath;
38using BulletXNA.BulletCollision;
39using BulletXNA.BulletDynamics;
40using BulletXNA.BulletCollision.CollisionDispatch;
41
42namespace OpenSim.Region.Physics.BulletSPlugin
43{
44public sealed class BSAPIXNA : BSAPITemplate
45{
46private sealed class BulletWorldXNA : BulletWorld
47{
48 public DiscreteDynamicsWorld world;
49 public BulletWorldXNA(uint id, BSScene physScene, DiscreteDynamicsWorld xx)
50 : base(id, physScene)
51 {
52 world = xx;
53 }
54}
55
56private sealed class BulletBodyXNA : BulletBody
57{
58 public CollisionObject body;
59 public RigidBody rigidBody { get { return RigidBody.Upcast(body); } }
60
61 public BulletBodyXNA(uint id, CollisionObject xx)
62 : base(id)
63 {
64 body = xx;
65 }
66 public override bool HasPhysicalBody
67 {
68 get { return body != null; }
69 }
70 public override void Clear()
71 {
72 body = null;
73 }
74 public override string AddrString
75 {
76 get { return "XNARigidBody"; }
77 }
78}
79
80private sealed class BulletShapeXNA : BulletShape
81{
82 public CollisionShape shape;
83 public BulletShapeXNA(CollisionShape xx, BSPhysicsShapeType typ)
84 : base()
85 {
86 shape = xx;
87 type = typ;
88 }
89 public override bool HasPhysicalShape
90 {
91 get { return shape != null; }
92 }
93 public override void Clear()
94 {
95 shape = null;
96 }
97 public override BulletShape Clone()
98 {
99 return new BulletShapeXNA(shape, type);
100 }
101 public override bool ReferenceSame(BulletShape other)
102 {
103 BulletShapeXNA otheru = other as BulletShapeXNA;
104 return (otheru != null) && (this.shape == otheru.shape);
105
106 }
107 public override string AddrString
108 {
109 get { return "XNACollisionShape"; }
110 }
111}
112private sealed class BulletConstraintXNA : BulletConstraint
113{
114 public TypedConstraint constrain;
115 public BulletConstraintXNA(TypedConstraint xx) : base()
116 {
117 constrain = xx;
118 }
119
120 public override void Clear()
121 {
122 constrain = null;
123 }
124 public override bool HasPhysicalConstraint { get { return constrain != null; } }
125
126 // Used for log messages for a unique display of the memory/object allocated to this instance
127 public override string AddrString
128 {
129 get { return "XNAConstraint"; }
130 }
131}
132
133 private static int m_collisionsThisFrame;
134 private BSScene PhysicsScene { get; set; }
135
136 public override string BulletEngineName { get { return "BulletXNA"; } }
137 public override string BulletEngineVersion { get; protected set; }
138
139 public BSAPIXNA(string paramName, BSScene physScene)
140 {
141 PhysicsScene = physScene;
142 }
143
144 /// <summary>
145 ///
146 /// </summary>
147 /// <param name="p"></param>
148 /// <param name="p_2"></param>
149 public override bool RemoveObjectFromWorld(BulletWorld pWorld, BulletBody pBody)
150 {
151 DiscreteDynamicsWorld world = ((BulletWorldXNA)pWorld).world;
152 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
153 world.RemoveRigidBody(body);
154 return true;
155 }
156
157 public override bool AddConstraintToWorld(BulletWorld world, BulletConstraint constrain, bool disableCollisionsBetweenLinkedObjects)
158 {
159 /* TODO */
160 return false;
161 }
162
163 public override bool RemoveConstraintFromWorld(BulletWorld world, BulletConstraint constrain)
164 {
165 /* TODO */
166 return false;
167 }
168
169 public override void SetRestitution(BulletBody pBody, float pRestitution)
170 {
171 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
172 body.SetRestitution(pRestitution);
173 }
174
175 public override int GetShapeType(BulletShape pShape)
176 {
177 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
178 return (int)shape.GetShapeType();
179 }
180 public override void SetMargin(BulletShape pShape, float pMargin)
181 {
182 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
183 shape.SetMargin(pMargin);
184 }
185
186 public override float GetMargin(BulletShape pShape)
187 {
188 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
189 return shape.GetMargin();
190 }
191
192 public override void SetLocalScaling(BulletShape pShape, Vector3 pScale)
193 {
194 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
195 IndexedVector3 vec = new IndexedVector3(pScale.X, pScale.Y, pScale.Z);
196 shape.SetLocalScaling(ref vec);
197
198 }
199
200 public override void SetContactProcessingThreshold(BulletBody pBody, float contactprocessingthreshold)
201 {
202 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
203 body.SetContactProcessingThreshold(contactprocessingthreshold);
204 }
205
206 public override void SetCcdMotionThreshold(BulletBody pBody, float pccdMotionThreashold)
207 {
208 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
209 body.SetCcdMotionThreshold(pccdMotionThreashold);
210 }
211
212 public override void SetCcdSweptSphereRadius(BulletBody pBody, float pCcdSweptSphereRadius)
213 {
214 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
215 body.SetCcdSweptSphereRadius(pCcdSweptSphereRadius);
216 }
217
218 public override void SetAngularFactorV(BulletBody pBody, Vector3 pAngularFactor)
219 {
220 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
221 body.SetAngularFactor(new IndexedVector3(pAngularFactor.X, pAngularFactor.Y, pAngularFactor.Z));
222 }
223
224 public override CollisionFlags AddToCollisionFlags(BulletBody pBody, CollisionFlags pcollisionFlags)
225 {
226 CollisionObject body = ((BulletBodyXNA)pBody).body;
227 CollisionFlags existingcollisionFlags = (CollisionFlags)(uint)body.GetCollisionFlags();
228 existingcollisionFlags |= pcollisionFlags;
229 body.SetCollisionFlags((BulletXNA.BulletCollision.CollisionFlags)(uint)existingcollisionFlags);
230 return (CollisionFlags) (uint) existingcollisionFlags;
231 }
232
233 public override bool AddObjectToWorld(BulletWorld pWorld, BulletBody pBody)
234 {
235 DiscreteDynamicsWorld world = ((BulletWorldXNA)pWorld).world;
236 CollisionObject cbody = ((BulletBodyXNA)pBody).body;
237 RigidBody rbody = cbody as RigidBody;
238
239 // Bullet resets several variables when an object is added to the world. In particular,
240 // BulletXNA resets position and rotation. Gravity is also reset depending on the static/dynamic
241 // type. Of course, the collision flags in the broadphase proxy are initialized to default.
242 IndexedMatrix origPos = cbody.GetWorldTransform();
243 if (rbody != null)
244 {
245 IndexedVector3 origGrav = rbody.GetGravity();
246 world.AddRigidBody(rbody);
247 rbody.SetGravity(origGrav);
248 }
249 else
250 {
251 world.AddCollisionObject(rbody);
252 }
253 cbody.SetWorldTransform(origPos);
254
255 pBody.ApplyCollisionMask(pWorld.physicsScene);
256
257 //if (body.GetBroadphaseHandle() != null)
258 // world.UpdateSingleAabb(body);
259 return true;
260 }
261
262 public override void ForceActivationState(BulletBody pBody, ActivationState pActivationState)
263 {
264 CollisionObject body = ((BulletBodyXNA)pBody).body;
265 body.ForceActivationState((BulletXNA.BulletCollision.ActivationState)(uint)pActivationState);
266 }
267
268 public override void UpdateSingleAabb(BulletWorld pWorld, BulletBody pBody)
269 {
270 DiscreteDynamicsWorld world = ((BulletWorldXNA)pWorld).world;
271 CollisionObject body = ((BulletBodyXNA)pBody).body;
272 world.UpdateSingleAabb(body);
273 }
274
275 public override void UpdateAabbs(BulletWorld world) { /* TODO */ }
276 public override bool GetForceUpdateAllAabbs(BulletWorld world) { /* TODO */ return false; }
277 public override void SetForceUpdateAllAabbs(BulletWorld world, bool force) { /* TODO */ }
278
279 public override bool SetCollisionGroupMask(BulletBody pBody, uint pGroup, uint pMask)
280 {
281 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
282 body.GetBroadphaseHandle().m_collisionFilterGroup = (BulletXNA.BulletCollision.CollisionFilterGroups) pGroup;
283 body.GetBroadphaseHandle().m_collisionFilterGroup = (BulletXNA.BulletCollision.CollisionFilterGroups) pGroup;
284 if ((uint) body.GetBroadphaseHandle().m_collisionFilterGroup == 0)
285 return false;
286 return true;
287 }
288
289 public override void ClearAllForces(BulletBody pBody)
290 {
291 CollisionObject body = ((BulletBodyXNA)pBody).body;
292 IndexedVector3 zeroVector = new IndexedVector3(0, 0, 0);
293 body.SetInterpolationLinearVelocity(ref zeroVector);
294 body.SetInterpolationAngularVelocity(ref zeroVector);
295 IndexedMatrix bodytransform = body.GetWorldTransform();
296
297 body.SetInterpolationWorldTransform(ref bodytransform);
298
299 if (body is RigidBody)
300 {
301 RigidBody rigidbody = body as RigidBody;
302 rigidbody.SetLinearVelocity(zeroVector);
303 rigidbody.SetAngularVelocity(zeroVector);
304 rigidbody.ClearForces();
305 }
306 }
307
308 public override void SetInterpolationAngularVelocity(BulletBody pBody, Vector3 pVector3)
309 {
310 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
311 IndexedVector3 vec = new IndexedVector3(pVector3.X, pVector3.Y, pVector3.Z);
312 body.SetInterpolationAngularVelocity(ref vec);
313 }
314
315 public override void SetAngularVelocity(BulletBody pBody, Vector3 pVector3)
316 {
317 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
318 IndexedVector3 vec = new IndexedVector3(pVector3.X, pVector3.Y, pVector3.Z);
319 body.SetAngularVelocity(ref vec);
320 }
321 public override Vector3 GetTotalForce(BulletBody pBody)
322 {
323 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
324 IndexedVector3 iv3 = body.GetTotalForce();
325 return new Vector3(iv3.X, iv3.Y, iv3.Z);
326 }
327 public override Vector3 GetTotalTorque(BulletBody pBody)
328 {
329 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
330 IndexedVector3 iv3 = body.GetTotalTorque();
331 return new Vector3(iv3.X, iv3.Y, iv3.Z);
332 }
333 public override Vector3 GetInvInertiaDiagLocal(BulletBody pBody)
334 {
335 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
336 IndexedVector3 iv3 = body.GetInvInertiaDiagLocal();
337 return new Vector3(iv3.X, iv3.Y, iv3.Z);
338 }
339 public override void SetInvInertiaDiagLocal(BulletBody pBody, Vector3 inert)
340 {
341 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
342 IndexedVector3 iv3 = new IndexedVector3(inert.X, inert.Y, inert.Z);
343 body.SetInvInertiaDiagLocal(ref iv3);
344 }
345 public override void ApplyForce(BulletBody pBody, Vector3 force, Vector3 pos)
346 {
347 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
348 IndexedVector3 forceiv3 = new IndexedVector3(force.X, force.Y, force.Z);
349 IndexedVector3 posiv3 = new IndexedVector3(pos.X, pos.Y, pos.Z);
350 body.ApplyForce(ref forceiv3, ref posiv3);
351 }
352 public override void ApplyImpulse(BulletBody pBody, Vector3 imp, Vector3 pos)
353 {
354 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
355 IndexedVector3 impiv3 = new IndexedVector3(imp.X, imp.Y, imp.Z);
356 IndexedVector3 posiv3 = new IndexedVector3(pos.X, pos.Y, pos.Z);
357 body.ApplyImpulse(ref impiv3, ref posiv3);
358 }
359
360 public override void ClearForces(BulletBody pBody)
361 {
362 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
363 body.ClearForces();
364 }
365
366 public override void SetTranslation(BulletBody pBody, Vector3 _position, Quaternion _orientation)
367 {
368 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
369 IndexedVector3 vposition = new IndexedVector3(_position.X, _position.Y, _position.Z);
370 IndexedQuaternion vquaternion = new IndexedQuaternion(_orientation.X, _orientation.Y, _orientation.Z,
371 _orientation.W);
372 IndexedMatrix mat = IndexedMatrix.CreateFromQuaternion(vquaternion);
373 mat._origin = vposition;
374 body.SetWorldTransform(mat);
375
376 }
377
378 public override Vector3 GetPosition(BulletBody pBody)
379 {
380 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
381 IndexedVector3 pos = body.GetInterpolationWorldTransform()._origin;
382 return new Vector3(pos.X, pos.Y, pos.Z);
383 }
384
385 public override Vector3 CalculateLocalInertia(BulletShape pShape, float pphysMass)
386 {
387 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
388 IndexedVector3 inertia = IndexedVector3.Zero;
389 shape.CalculateLocalInertia(pphysMass, out inertia);
390 return new Vector3(inertia.X, inertia.Y, inertia.Z);
391 }
392
393 public override void SetMassProps(BulletBody pBody, float pphysMass, Vector3 plocalInertia)
394 {
395 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
396 IndexedVector3 inertia = new IndexedVector3(plocalInertia.X, plocalInertia.Y, plocalInertia.Z);
397 body.SetMassProps(pphysMass, inertia);
398 }
399
400
401 public override void SetObjectForce(BulletBody pBody, Vector3 _force)
402 {
403 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
404 IndexedVector3 force = new IndexedVector3(_force.X, _force.Y, _force.Z);
405 body.SetTotalForce(ref force);
406 }
407
408 public override void SetFriction(BulletBody pBody, float _currentFriction)
409 {
410 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
411 body.SetFriction(_currentFriction);
412 }
413
414 public override void SetLinearVelocity(BulletBody pBody, Vector3 _velocity)
415 {
416 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
417 IndexedVector3 velocity = new IndexedVector3(_velocity.X, _velocity.Y, _velocity.Z);
418 body.SetLinearVelocity(velocity);
419 }
420
421 public override void Activate(BulletBody pBody, bool pforceactivation)
422 {
423 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
424 body.Activate(pforceactivation);
425
426 }
427
428 public override Quaternion GetOrientation(BulletBody pBody)
429 {
430 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
431 IndexedQuaternion mat = body.GetInterpolationWorldTransform().GetRotation();
432 return new Quaternion(mat.X, mat.Y, mat.Z, mat.W);
433 }
434
435 public override CollisionFlags RemoveFromCollisionFlags(BulletBody pBody, CollisionFlags pcollisionFlags)
436 {
437 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
438 CollisionFlags existingcollisionFlags = (CollisionFlags)(uint)body.GetCollisionFlags();
439 existingcollisionFlags &= ~pcollisionFlags;
440 body.SetCollisionFlags((BulletXNA.BulletCollision.CollisionFlags)(uint)existingcollisionFlags);
441 return (CollisionFlags)(uint)existingcollisionFlags;
442 }
443
444 public override float GetCcdMotionThreshold(BulletBody obj) { /* TODO */ return 0f; }
445
446 public override float GetCcdSweptSphereRadius(BulletBody obj) { /* TODO */ return 0f; }
447
448 public override IntPtr GetUserPointer(BulletBody obj) { /* TODO */ return IntPtr.Zero; }
449
450 public override void SetUserPointer(BulletBody obj, IntPtr val) { /* TODO */ }
451
452 public override void SetGravity(BulletBody pBody, Vector3 pGravity)
453 {
454 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
455 IndexedVector3 gravity = new IndexedVector3(pGravity.X, pGravity.Y, pGravity.Z);
456 body.SetGravity(gravity);
457 }
458
459 public override bool DestroyConstraint(BulletWorld pWorld, BulletConstraint pConstraint)
460 {
461 DiscreteDynamicsWorld world = ((BulletWorldXNA)pWorld).world;
462 TypedConstraint constraint = ((BulletConstraintXNA)pConstraint).constrain;
463 world.RemoveConstraint(constraint);
464 return true;
465 }
466
467 public override bool SetLinearLimits(BulletConstraint pConstraint, Vector3 low, Vector3 high)
468 {
469 Generic6DofConstraint constraint = ((BulletConstraintXNA)pConstraint).constrain as Generic6DofConstraint;
470 IndexedVector3 lowlimit = new IndexedVector3(low.X, low.Y, low.Z);
471 IndexedVector3 highlimit = new IndexedVector3(high.X, high.Y, high.Z);
472 constraint.SetLinearLowerLimit(lowlimit);
473 constraint.SetLinearUpperLimit(highlimit);
474 return true;
475 }
476
477 public override bool SetAngularLimits(BulletConstraint pConstraint, Vector3 low, Vector3 high)
478 {
479 Generic6DofConstraint constraint = ((BulletConstraintXNA)pConstraint).constrain as Generic6DofConstraint;
480 IndexedVector3 lowlimit = new IndexedVector3(low.X, low.Y, low.Z);
481 IndexedVector3 highlimit = new IndexedVector3(high.X, high.Y, high.Z);
482 constraint.SetAngularLowerLimit(lowlimit);
483 constraint.SetAngularUpperLimit(highlimit);
484 return true;
485 }
486
487 public override void SetConstraintNumSolverIterations(BulletConstraint pConstraint, float cnt)
488 {
489 Generic6DofConstraint constraint = ((BulletConstraintXNA)pConstraint).constrain as Generic6DofConstraint;
490 constraint.SetOverrideNumSolverIterations((int)cnt);
491 }
492
493 public override bool CalculateTransforms(BulletConstraint pConstraint)
494 {
495 Generic6DofConstraint constraint = ((BulletConstraintXNA)pConstraint).constrain as Generic6DofConstraint;
496 constraint.CalculateTransforms();
497 return true;
498 }
499
500 public override void SetConstraintEnable(BulletConstraint pConstraint, float p_2)
501 {
502 Generic6DofConstraint constraint = ((BulletConstraintXNA)pConstraint).constrain as Generic6DofConstraint;
503 constraint.SetEnabled((p_2 == 0) ? false : true);
504 }
505
506
507 //BulletSimAPI.Create6DofConstraint(m_world.ptr, m_body1.ptr, m_body2.ptr,frame1, frame1rot,frame2, frame2rot,useLinearReferenceFrameA, disableCollisionsBetweenLinkedBodies));
508 public override BulletConstraint Create6DofConstraint(BulletWorld pWorld, BulletBody pBody1, BulletBody pBody2, Vector3 pframe1, Quaternion pframe1rot, Vector3 pframe2, Quaternion pframe2rot, bool puseLinearReferenceFrameA, bool pdisableCollisionsBetweenLinkedBodies)
509
510 {
511 DiscreteDynamicsWorld world = ((BulletWorldXNA)pWorld).world;
512 RigidBody body1 = ((BulletBodyXNA)pBody1).rigidBody;
513 RigidBody body2 = ((BulletBodyXNA)pBody2).rigidBody;
514 IndexedVector3 frame1v = new IndexedVector3(pframe1.X, pframe1.Y, pframe1.Z);
515 IndexedQuaternion frame1rot = new IndexedQuaternion(pframe1rot.X, pframe1rot.Y, pframe1rot.Z, pframe1rot.W);
516 IndexedMatrix frame1 = IndexedMatrix.CreateFromQuaternion(frame1rot);
517 frame1._origin = frame1v;
518
519 IndexedVector3 frame2v = new IndexedVector3(pframe2.X, pframe2.Y, pframe2.Z);
520 IndexedQuaternion frame2rot = new IndexedQuaternion(pframe2rot.X, pframe2rot.Y, pframe2rot.Z, pframe2rot.W);
521 IndexedMatrix frame2 = IndexedMatrix.CreateFromQuaternion(frame2rot);
522 frame2._origin = frame1v;
523
524 Generic6DofConstraint consttr = new Generic6DofConstraint(body1, body2, ref frame1, ref frame2,
525 puseLinearReferenceFrameA);
526 consttr.CalculateTransforms();
527 world.AddConstraint(consttr,pdisableCollisionsBetweenLinkedBodies);
528
529 return new BulletConstraintXNA(consttr);
530 }
531
532
533 /// <summary>
534 ///
535 /// </summary>
536 /// <param name="pWorld"></param>
537 /// <param name="pBody1"></param>
538 /// <param name="pBody2"></param>
539 /// <param name="pjoinPoint"></param>
540 /// <param name="puseLinearReferenceFrameA"></param>
541 /// <param name="pdisableCollisionsBetweenLinkedBodies"></param>
542 /// <returns></returns>
543 public override BulletConstraint Create6DofConstraintToPoint(BulletWorld pWorld, BulletBody pBody1, BulletBody pBody2, Vector3 pjoinPoint, bool puseLinearReferenceFrameA, bool pdisableCollisionsBetweenLinkedBodies)
544 {
545 DiscreteDynamicsWorld world = ((BulletWorldXNA)pWorld).world;
546 RigidBody body1 = ((BulletBodyXNA)pBody1).rigidBody;
547 RigidBody body2 = ((BulletBodyXNA)pBody2).rigidBody;
548 IndexedMatrix frame1 = new IndexedMatrix(IndexedBasisMatrix.Identity, new IndexedVector3(0, 0, 0));
549 IndexedMatrix frame2 = new IndexedMatrix(IndexedBasisMatrix.Identity, new IndexedVector3(0, 0, 0));
550
551 IndexedVector3 joinPoint = new IndexedVector3(pjoinPoint.X, pjoinPoint.Y, pjoinPoint.Z);
552 IndexedMatrix mat = IndexedMatrix.Identity;
553 mat._origin = new IndexedVector3(pjoinPoint.X, pjoinPoint.Y, pjoinPoint.Z);
554 frame1._origin = body1.GetWorldTransform().Inverse()*joinPoint;
555 frame2._origin = body2.GetWorldTransform().Inverse()*joinPoint;
556
557 Generic6DofConstraint consttr = new Generic6DofConstraint(body1, body2, ref frame1, ref frame2, puseLinearReferenceFrameA);
558 consttr.CalculateTransforms();
559 world.AddConstraint(consttr, pdisableCollisionsBetweenLinkedBodies);
560
561 return new BulletConstraintXNA(consttr);
562 }
563 //SetFrames(m_constraint.ptr, frameA, frameArot, frameB, frameBrot);
564 public override bool SetFrames(BulletConstraint pConstraint, Vector3 pframe1, Quaternion pframe1rot, Vector3 pframe2, Quaternion pframe2rot)
565 {
566 Generic6DofConstraint constraint = ((BulletConstraintXNA)pConstraint).constrain as Generic6DofConstraint;
567 IndexedVector3 frame1v = new IndexedVector3(pframe1.X, pframe1.Y, pframe1.Z);
568 IndexedQuaternion frame1rot = new IndexedQuaternion(pframe1rot.X, pframe1rot.Y, pframe1rot.Z, pframe1rot.W);
569 IndexedMatrix frame1 = IndexedMatrix.CreateFromQuaternion(frame1rot);
570 frame1._origin = frame1v;
571
572 IndexedVector3 frame2v = new IndexedVector3(pframe2.X, pframe2.Y, pframe2.Z);
573 IndexedQuaternion frame2rot = new IndexedQuaternion(pframe2rot.X, pframe2rot.Y, pframe2rot.Z, pframe2rot.W);
574 IndexedMatrix frame2 = IndexedMatrix.CreateFromQuaternion(frame2rot);
575 frame2._origin = frame1v;
576 constraint.SetFrames(ref frame1, ref frame2);
577 return true;
578 }
579
580 public override Vector3 GetLinearVelocity(BulletBody pBody)
581 {
582 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
583 IndexedVector3 iv3 = body.GetLinearVelocity();
584 return new Vector3(iv3.X, iv3.Y, iv3.Z);
585 }
586 public override Vector3 GetAngularVelocity(BulletBody pBody)
587 {
588 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
589 IndexedVector3 iv3 = body.GetAngularVelocity();
590 return new Vector3(iv3.X, iv3.Y, iv3.Z);
591 }
592 public override Vector3 GetVelocityInLocalPoint(BulletBody pBody, Vector3 pos)
593 {
594 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
595 IndexedVector3 posiv3 = new IndexedVector3(pos.X, pos.Y, pos.Z);
596 IndexedVector3 iv3 = body.GetVelocityInLocalPoint(ref posiv3);
597 return new Vector3(iv3.X, iv3.Y, iv3.Z);
598 }
599 public override void Translate(BulletBody pBody, Vector3 trans)
600 {
601 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
602 }
603 public override void UpdateDeactivation(BulletBody pBody, float timeStep)
604 {
605 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
606 body.UpdateDeactivation(timeStep);
607 }
608
609 public override bool WantsSleeping(BulletBody pBody)
610 {
611 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
612 return body.WantsSleeping();
613 }
614
615 public override void SetAngularFactor(BulletBody pBody, float factor)
616 {
617 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
618 body.SetAngularFactor(factor);
619 }
620
621 public override Vector3 GetAngularFactor(BulletBody pBody)
622 {
623 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
624 IndexedVector3 iv3 = body.GetAngularFactor();
625 return new Vector3(iv3.X, iv3.Y, iv3.Z);
626 }
627
628 public override bool IsInWorld(BulletWorld pWorld, BulletBody pBody)
629 {
630 DiscreteDynamicsWorld world = ((BulletWorldXNA)pWorld).world;
631 CollisionObject body = ((BulletBodyXNA)pBody).body;
632 return world.IsInWorld(body);
633 }
634
635 public override void AddConstraintRef(BulletBody pBody, BulletConstraint pConstrain)
636 {
637 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
638 TypedConstraint constrain = ((BulletConstraintXNA)pConstrain).constrain;
639 body.AddConstraintRef(constrain);
640 }
641
642 public override void RemoveConstraintRef(BulletBody pBody, BulletConstraint pConstrain)
643 {
644 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
645 TypedConstraint constrain = ((BulletConstraintXNA)pConstrain).constrain;
646 body.RemoveConstraintRef(constrain);
647 }
648
649 public override BulletConstraint GetConstraintRef(BulletBody pBody, int index)
650 {
651 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
652 return new BulletConstraintXNA(body.GetConstraintRef(index));
653 }
654
655 public override int GetNumConstraintRefs(BulletBody pBody)
656 {
657 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
658 return body.GetNumConstraintRefs();
659 }
660
661 public override void SetInterpolationLinearVelocity(BulletBody pBody, Vector3 VehicleVelocity)
662 {
663 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
664 IndexedVector3 velocity = new IndexedVector3(VehicleVelocity.X, VehicleVelocity.Y, VehicleVelocity.Z);
665 body.SetInterpolationLinearVelocity(ref velocity);
666 }
667
668 public override bool UseFrameOffset(BulletConstraint pConstraint, float onOff)
669 {
670 Generic6DofConstraint constraint = ((BulletConstraintXNA)pConstraint).constrain as Generic6DofConstraint;
671 constraint.SetUseFrameOffset((onOff == 0) ? false : true);
672 return true;
673 }
674 //SetBreakingImpulseThreshold(m_constraint.ptr, threshold);
675 public override bool SetBreakingImpulseThreshold(BulletConstraint pConstraint, float threshold)
676 {
677 Generic6DofConstraint constraint = ((BulletConstraintXNA)pConstraint).constrain as Generic6DofConstraint;
678 constraint.SetBreakingImpulseThreshold(threshold);
679 return true;
680 }
681 //BulletSimAPI.SetAngularDamping(Prim.PhysBody.ptr, angularDamping);
682 public override void SetAngularDamping(BulletBody pBody, float angularDamping)
683 {
684 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
685 float lineardamping = body.GetLinearDamping();
686 body.SetDamping(lineardamping, angularDamping);
687
688 }
689
690 public override void UpdateInertiaTensor(BulletBody pBody)
691 {
692 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
693 body.UpdateInertiaTensor();
694 }
695
696 public override void RecalculateCompoundShapeLocalAabb(BulletShape pCompoundShape)
697 {
698 CompoundShape shape = ((BulletShapeXNA)pCompoundShape).shape as CompoundShape;
699 shape.RecalculateLocalAabb();
700 }
701
702 //BulletSimAPI.GetCollisionFlags(PhysBody.ptr)
703 public override CollisionFlags GetCollisionFlags(BulletBody pBody)
704 {
705 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
706 uint flags = (uint)body.GetCollisionFlags();
707 return (CollisionFlags) flags;
708 }
709
710 public override void SetDamping(BulletBody pBody, float pLinear, float pAngular)
711 {
712 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
713 body.SetDamping(pLinear, pAngular);
714 }
715 //PhysBody.ptr, PhysicsScene.Params.deactivationTime);
716 public override void SetDeactivationTime(BulletBody pBody, float pDeactivationTime)
717 {
718 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
719 body.SetDeactivationTime(pDeactivationTime);
720 }
721 //SetSleepingThresholds(PhysBody.ptr, PhysicsScene.Params.linearSleepingThreshold, PhysicsScene.Params.angularSleepingThreshold);
722 public override void SetSleepingThresholds(BulletBody pBody, float plinearSleepingThreshold, float pangularSleepingThreshold)
723 {
724 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
725 body.SetSleepingThresholds(plinearSleepingThreshold, pangularSleepingThreshold);
726 }
727
728 public override CollisionObjectTypes GetBodyType(BulletBody pBody)
729 {
730 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
731 return (CollisionObjectTypes)(int) body.GetInternalType();
732 }
733
734 public override void ApplyGravity(BulletBody obj) { /* TODO */ }
735
736 public override Vector3 GetGravity(BulletBody obj) { /* TODO */ return Vector3.Zero; }
737
738 public override void SetLinearDamping(BulletBody obj, float lin_damping) { /* TODO */ }
739
740 public override float GetLinearDamping(BulletBody obj) { /* TODO */ return 0f; }
741
742 public override float GetAngularDamping(BulletBody obj) { /* TODO */ return 0f; }
743
744 public override float GetLinearSleepingThreshold(BulletBody obj) { /* TODO */ return 0f; }
745
746 public override void ApplyDamping(BulletBody obj, float timeStep) { /* TODO */ }
747
748 public override Vector3 GetLinearFactor(BulletBody obj) { /* TODO */ return Vector3.Zero; }
749
750 public override void SetLinearFactor(BulletBody obj, Vector3 factor) { /* TODO */ }
751
752 public override void SetCenterOfMassByPosRot(BulletBody obj, Vector3 pos, Quaternion rot) { /* TODO */ }
753
754 //BulletSimAPI.ApplyCentralForce(PhysBody.ptr, fSum);
755 public override void ApplyCentralForce(BulletBody pBody, Vector3 pfSum)
756 {
757 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
758 IndexedVector3 fSum = new IndexedVector3(pfSum.X, pfSum.Y, pfSum.Z);
759 body.ApplyCentralForce(ref fSum);
760 }
761 public override void ApplyCentralImpulse(BulletBody pBody, Vector3 pfSum)
762 {
763 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
764 IndexedVector3 fSum = new IndexedVector3(pfSum.X, pfSum.Y, pfSum.Z);
765 body.ApplyCentralImpulse(ref fSum);
766 }
767 public override void ApplyTorque(BulletBody pBody, Vector3 pfSum)
768 {
769 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
770 IndexedVector3 fSum = new IndexedVector3(pfSum.X, pfSum.Y, pfSum.Z);
771 body.ApplyTorque(ref fSum);
772 }
773 public override void ApplyTorqueImpulse(BulletBody pBody, Vector3 pfSum)
774 {
775 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
776 IndexedVector3 fSum = new IndexedVector3(pfSum.X, pfSum.Y, pfSum.Z);
777 body.ApplyTorqueImpulse(ref fSum);
778 }
779
780 public override void DestroyObject(BulletWorld p, BulletBody p_2)
781 {
782 //TODO:
783 }
784
785 public override void Shutdown(BulletWorld pWorld)
786 {
787 DiscreteDynamicsWorld world = ((BulletWorldXNA)pWorld).world;
788 world.Cleanup();
789 }
790
791 public override BulletShape DuplicateCollisionShape(BulletWorld sim, BulletShape srcShape, uint id)
792 {
793 return null;
794 }
795
796 public override bool DeleteCollisionShape(BulletWorld p, BulletShape p_2)
797 {
798 //TODO:
799 return false;
800 }
801 //(sim.ptr, shape.ptr, prim.LocalID, prim.RawPosition, prim.RawOrientation);
802
803 public override BulletBody CreateBodyFromShape(BulletWorld pWorld, BulletShape pShape, uint pLocalID, Vector3 pRawPosition, Quaternion pRawOrientation)
804 {
805 CollisionWorld world = ((BulletWorldXNA)pWorld).world;
806 IndexedMatrix mat =
807 IndexedMatrix.CreateFromQuaternion(new IndexedQuaternion(pRawOrientation.X, pRawOrientation.Y,
808 pRawOrientation.Z, pRawOrientation.W));
809 mat._origin = new IndexedVector3(pRawPosition.X, pRawPosition.Y, pRawPosition.Z);
810 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
811 //UpdateSingleAabb(world, shape);
812 // TODO: Feed Update array into null
813 RigidBody body = new RigidBody(0,new SimMotionState(world,pLocalID,mat,null),shape,IndexedVector3.Zero);
814
815 body.SetUserPointer(pLocalID);
816 return new BulletBodyXNA(pLocalID, body);
817 }
818
819
820 public override BulletBody CreateBodyWithDefaultMotionState( BulletShape pShape, uint pLocalID, Vector3 pRawPosition, Quaternion pRawOrientation)
821 {
822
823 IndexedMatrix mat =
824 IndexedMatrix.CreateFromQuaternion(new IndexedQuaternion(pRawOrientation.X, pRawOrientation.Y,
825 pRawOrientation.Z, pRawOrientation.W));
826 mat._origin = new IndexedVector3(pRawPosition.X, pRawPosition.Y, pRawPosition.Z);
827
828 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
829
830 // TODO: Feed Update array into null
831 RigidBody body = new RigidBody(0, new DefaultMotionState( mat, IndexedMatrix.Identity), shape, IndexedVector3.Zero);
832 body.SetWorldTransform(mat);
833 body.SetUserPointer(pLocalID);
834 return new BulletBodyXNA(pLocalID, body);
835 }
836 //(m_mapInfo.terrainBody.ptr, CollisionFlags.CF_STATIC_OBJECT);
837 public override CollisionFlags SetCollisionFlags(BulletBody pBody, CollisionFlags collisionFlags)
838 {
839 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
840 body.SetCollisionFlags((BulletXNA.BulletCollision.CollisionFlags) (uint) collisionFlags);
841 return (CollisionFlags)body.GetCollisionFlags();
842 }
843
844 public override Vector3 GetAnisotripicFriction(BulletConstraint pconstrain) { /* TODO */ return Vector3.Zero; }
845 public override Vector3 SetAnisotripicFriction(BulletConstraint pconstrain, Vector3 frict) { /* TODO */ return Vector3.Zero; }
846 public override bool HasAnisotripicFriction(BulletConstraint pconstrain) { /* TODO */ return false; }
847 public override float GetContactProcessingThreshold(BulletBody pBody) { /* TODO */ return 0f; }
848 public override bool IsStaticObject(BulletBody pBody) { /* TODO */ return false; }
849 public override bool IsKinematicObject(BulletBody pBody) { /* TODO */ return false; }
850 public override bool IsStaticOrKinematicObject(BulletBody pBody) { /* TODO */ return false; }
851 public override bool HasContactResponse(BulletBody pBody) { /* TODO */ return false; }
852 public override int GetActivationState(BulletBody pBody) { /* TODO */ return 0; }
853 public override void SetActivationState(BulletBody pBody, int state) { /* TODO */ }
854 public override float GetDeactivationTime(BulletBody pBody) { /* TODO */ return 0f; }
855 public override bool IsActive(BulletBody pBody) { /* TODO */ return false; }
856 public override float GetRestitution(BulletBody pBody) { /* TODO */ return 0f; }
857 public override float GetFriction(BulletBody pBody) { /* TODO */ return 0f; }
858 public override void SetInterpolationVelocity(BulletBody pBody, Vector3 linearVel, Vector3 angularVel) { /* TODO */ }
859 public override float GetHitFraction(BulletBody pBody) { /* TODO */ return 0f; }
860
861 //(m_mapInfo.terrainBody.ptr, PhysicsScene.Params.terrainHitFraction);
862 public override void SetHitFraction(BulletBody pBody, float pHitFraction)
863 {
864 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
865 body.SetHitFraction(pHitFraction);
866 }
867 //BuildCapsuleShape(physicsScene.World.ptr, 1f, 1f, prim.Scale);
868 public override BulletShape BuildCapsuleShape(BulletWorld pWorld, float pRadius, float pHeight, Vector3 pScale)
869 {
870 DiscreteDynamicsWorld world = ((BulletWorldXNA)pWorld).world;
871 IndexedVector3 scale = new IndexedVector3(pScale.X, pScale.Y, pScale.Z);
872 CapsuleShapeZ capsuleShapeZ = new CapsuleShapeZ(pRadius, pHeight);
873 capsuleShapeZ.SetMargin(world.WorldSettings.Params.collisionMargin);
874 capsuleShapeZ.SetLocalScaling(ref scale);
875
876 return new BulletShapeXNA(capsuleShapeZ, BSPhysicsShapeType.SHAPE_CAPSULE); ;
877 }
878
879 public override BulletWorld Initialize(Vector3 maxPosition, ConfigurationParameters parms,
880 int maxCollisions, ref CollisionDesc[] collisionArray,
881 int maxUpdates, ref EntityProperties[] updateArray
882 )
883 {
884 /* TODO */
885 return new BulletWorldXNA(1, null, null);
886 }
887
888 private static object Initialize2(Vector3 worldExtent,
889 ConfigurationParameters[] o,
890 int mMaxCollisionsPerFrame, ref List<BulletXNA.CollisionDesc> collisionArray,
891 int mMaxUpdatesPerFrame, ref List<BulletXNA.EntityProperties> updateArray,
892 object mDebugLogCallbackHandle)
893 {
894 CollisionWorld.WorldData.ParamData p = new CollisionWorld.WorldData.ParamData();
895
896 p.angularDamping = o[0].XangularDamping;
897 p.defaultFriction = o[0].defaultFriction;
898 p.defaultFriction = o[0].defaultFriction;
899 p.defaultDensity = o[0].defaultDensity;
900 p.defaultRestitution = o[0].defaultRestitution;
901 p.collisionMargin = o[0].collisionMargin;
902 p.gravity = o[0].gravity;
903
904 p.linearDamping = o[0].XlinearDamping;
905 p.angularDamping = o[0].XangularDamping;
906 p.deactivationTime = o[0].XdeactivationTime;
907 p.linearSleepingThreshold = o[0].XlinearSleepingThreshold;
908 p.angularSleepingThreshold = o[0].XangularSleepingThreshold;
909 p.ccdMotionThreshold = o[0].XccdMotionThreshold;
910 p.ccdSweptSphereRadius = o[0].XccdSweptSphereRadius;
911 p.contactProcessingThreshold = o[0].XcontactProcessingThreshold;
912
913 p.terrainImplementation = o[0].XterrainImplementation;
914 p.terrainFriction = o[0].XterrainFriction;
915
916 p.terrainHitFraction = o[0].XterrainHitFraction;
917 p.terrainRestitution = o[0].XterrainRestitution;
918 p.terrainCollisionMargin = o[0].XterrainCollisionMargin;
919
920 p.avatarFriction = o[0].XavatarFriction;
921 p.avatarStandingFriction = o[0].XavatarStandingFriction;
922 p.avatarDensity = o[0].XavatarDensity;
923 p.avatarRestitution = o[0].XavatarRestitution;
924 p.avatarCapsuleWidth = o[0].XavatarCapsuleWidth;
925 p.avatarCapsuleDepth = o[0].XavatarCapsuleDepth;
926 p.avatarCapsuleHeight = o[0].XavatarCapsuleHeight;
927 p.avatarContactProcessingThreshold = o[0].XavatarContactProcessingThreshold;
928
929 p.vehicleAngularDamping = o[0].XvehicleAngularDamping;
930
931 p.maxPersistantManifoldPoolSize = o[0].maxPersistantManifoldPoolSize;
932 p.maxCollisionAlgorithmPoolSize = o[0].maxCollisionAlgorithmPoolSize;
933 p.shouldDisableContactPoolDynamicAllocation = o[0].shouldDisableContactPoolDynamicAllocation;
934 p.shouldForceUpdateAllAabbs = o[0].shouldForceUpdateAllAabbs;
935 p.shouldRandomizeSolverOrder = o[0].shouldRandomizeSolverOrder;
936 p.shouldSplitSimulationIslands = o[0].shouldSplitSimulationIslands;
937 p.shouldEnableFrictionCaching = o[0].shouldEnableFrictionCaching;
938 p.numberOfSolverIterations = o[0].numberOfSolverIterations;
939
940 p.linksetImplementation = o[0].XlinksetImplementation;
941 p.linkConstraintUseFrameOffset = o[0].XlinkConstraintUseFrameOffset;
942 p.linkConstraintEnableTransMotor = o[0].XlinkConstraintEnableTransMotor;
943 p.linkConstraintTransMotorMaxVel = o[0].XlinkConstraintTransMotorMaxVel;
944 p.linkConstraintTransMotorMaxForce = o[0].XlinkConstraintTransMotorMaxForce;
945 p.linkConstraintERP = o[0].XlinkConstraintERP;
946 p.linkConstraintCFM = o[0].XlinkConstraintCFM;
947 p.linkConstraintSolverIterations = o[0].XlinkConstraintSolverIterations;
948 p.physicsLoggingFrames = o[0].XphysicsLoggingFrames;
949 DefaultCollisionConstructionInfo ccci = new DefaultCollisionConstructionInfo();
950
951 DefaultCollisionConfiguration cci = new DefaultCollisionConfiguration();
952 CollisionDispatcher m_dispatcher = new CollisionDispatcher(cci);
953
954
955 if (p.maxPersistantManifoldPoolSize > 0)
956 cci.m_persistentManifoldPoolSize = (int)p.maxPersistantManifoldPoolSize;
957 if (p.shouldDisableContactPoolDynamicAllocation !=0)
958 m_dispatcher.SetDispatcherFlags(DispatcherFlags.CD_DISABLE_CONTACTPOOL_DYNAMIC_ALLOCATION);
959 //if (p.maxCollisionAlgorithmPoolSize >0 )
960
961 DbvtBroadphase m_broadphase = new DbvtBroadphase();
962 //IndexedVector3 aabbMin = new IndexedVector3(0, 0, 0);
963 //IndexedVector3 aabbMax = new IndexedVector3(256, 256, 256);
964
965 //AxisSweep3Internal m_broadphase2 = new AxisSweep3Internal(ref aabbMin, ref aabbMax, Convert.ToInt32(0xfffe), 0xffff, ushort.MaxValue/2, null, true);
966 m_broadphase.GetOverlappingPairCache().SetInternalGhostPairCallback(new GhostPairCallback());
967
968 SequentialImpulseConstraintSolver m_solver = new SequentialImpulseConstraintSolver();
969
970 DiscreteDynamicsWorld world = new DiscreteDynamicsWorld(m_dispatcher, m_broadphase, m_solver, cci);
971 world.UpdatedObjects = updateArray;
972 world.UpdatedCollisions = collisionArray;
973 world.WorldSettings.Params = p;
974 world.SetForceUpdateAllAabbs(p.shouldForceUpdateAllAabbs != 0);
975 world.GetSolverInfo().m_solverMode = SolverMode.SOLVER_USE_WARMSTARTING | SolverMode.SOLVER_SIMD;
976 if (p.shouldRandomizeSolverOrder != 0)
977 world.GetSolverInfo().m_solverMode |= SolverMode.SOLVER_RANDMIZE_ORDER;
978
979 world.GetSimulationIslandManager().SetSplitIslands(p.shouldSplitSimulationIslands != 0);
980 //world.GetDispatchInfo().m_enableSatConvex Not implemented in C# port
981
982 if (p.shouldEnableFrictionCaching != 0)
983 world.GetSolverInfo().m_solverMode |= SolverMode.SOLVER_ENABLE_FRICTION_DIRECTION_CACHING;
984
985 if (p.numberOfSolverIterations > 0)
986 world.GetSolverInfo().m_numIterations = (int) p.numberOfSolverIterations;
987
988
989 world.GetSolverInfo().m_damping = world.WorldSettings.Params.linearDamping;
990 world.GetSolverInfo().m_restitution = world.WorldSettings.Params.defaultRestitution;
991 world.GetSolverInfo().m_globalCfm = 0.0f;
992 world.GetSolverInfo().m_tau = 0.6f;
993 world.GetSolverInfo().m_friction = 0.3f;
994 world.GetSolverInfo().m_maxErrorReduction = 20f;
995 world.GetSolverInfo().m_numIterations = 10;
996 world.GetSolverInfo().m_erp = 0.2f;
997 world.GetSolverInfo().m_erp2 = 0.1f;
998 world.GetSolverInfo().m_sor = 1.0f;
999 world.GetSolverInfo().m_splitImpulse = false;
1000 world.GetSolverInfo().m_splitImpulsePenetrationThreshold = -0.02f;
1001 world.GetSolverInfo().m_linearSlop = 0.0f;
1002 world.GetSolverInfo().m_warmstartingFactor = 0.85f;
1003 world.GetSolverInfo().m_restingContactRestitutionThreshold = 2;
1004 world.SetForceUpdateAllAabbs(true);
1005
1006
1007 world.SetGravity(new IndexedVector3(0,0,p.gravity));
1008
1009 return world;
1010 }
1011 //m_constraint.ptr, ConstraintParams.BT_CONSTRAINT_STOP_CFM, cfm, ConstraintParamAxis.AXIS_ALL
1012 public override bool SetConstraintParam(BulletConstraint pConstraint, ConstraintParams paramIndex, float paramvalue, ConstraintParamAxis axis)
1013 {
1014 Generic6DofConstraint constrain = ((BulletConstraintXNA)pConstraint).constrain as Generic6DofConstraint;
1015 if (axis == ConstraintParamAxis.AXIS_LINEAR_ALL || axis == ConstraintParamAxis.AXIS_ALL)
1016 {
1017 constrain.SetParam((BulletXNA.BulletDynamics.ConstraintParams) (int) paramIndex, paramvalue, 0);
1018 constrain.SetParam((BulletXNA.BulletDynamics.ConstraintParams) (int) paramIndex, paramvalue, 1);
1019 constrain.SetParam((BulletXNA.BulletDynamics.ConstraintParams) (int) paramIndex, paramvalue, 2);
1020 }
1021 if (axis == ConstraintParamAxis.AXIS_ANGULAR_ALL || axis == ConstraintParamAxis.AXIS_ALL)
1022 {
1023 constrain.SetParam((BulletXNA.BulletDynamics.ConstraintParams)(int)paramIndex, paramvalue, 3);
1024 constrain.SetParam((BulletXNA.BulletDynamics.ConstraintParams)(int)paramIndex, paramvalue, 4);
1025 constrain.SetParam((BulletXNA.BulletDynamics.ConstraintParams)(int)paramIndex, paramvalue, 5);
1026 }
1027 if (axis == ConstraintParamAxis.AXIS_LINEAR_ALL)
1028 {
1029 constrain.SetParam((BulletXNA.BulletDynamics.ConstraintParams)(int)paramIndex, paramvalue, (int)axis);
1030 }
1031 return true;
1032 }
1033
1034 public override bool PushUpdate(BulletBody pCollisionObject)
1035 {
1036 bool ret = false;
1037 RigidBody rb = ((BulletBodyXNA)pCollisionObject).rigidBody;
1038 if (rb != null)
1039 {
1040 SimMotionState sms = rb.GetMotionState() as SimMotionState;
1041 if (sms != null)
1042 {
1043 IndexedMatrix wt = IndexedMatrix.Identity;
1044 sms.GetWorldTransform(out wt);
1045 sms.SetWorldTransform(ref wt, true);
1046 ret = true;
1047 }
1048 }
1049 return ret;
1050
1051 }
1052
1053 public override float GetAngularMotionDisc(BulletShape pShape)
1054 {
1055 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
1056 return shape.GetAngularMotionDisc();
1057 }
1058 public override float GetContactBreakingThreshold(BulletShape pShape, float defaultFactor)
1059 {
1060 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
1061 return shape.GetContactBreakingThreshold(defaultFactor);
1062 }
1063 public override bool IsCompound(BulletShape pShape)
1064 {
1065 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
1066 return shape.IsCompound();
1067 }
1068 public override bool IsSoftBody(BulletShape pShape)
1069 {
1070 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
1071 return shape.IsSoftBody();
1072 }
1073 public override bool IsPolyhedral(BulletShape pShape)
1074 {
1075 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
1076 return shape.IsPolyhedral();
1077 }
1078 public override bool IsConvex2d(BulletShape pShape)
1079 {
1080 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
1081 return shape.IsConvex2d();
1082 }
1083 public override bool IsConvex(BulletShape pShape)
1084 {
1085 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
1086 return shape.IsConvex();
1087 }
1088 public override bool IsNonMoving(BulletShape pShape)
1089 {
1090 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
1091 return shape.IsNonMoving();
1092 }
1093 public override bool IsConcave(BulletShape pShape)
1094 {
1095 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
1096 return shape.IsConcave();
1097 }
1098 public override bool IsInfinite(BulletShape pShape)
1099 {
1100 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
1101 return shape.IsInfinite();
1102 }
1103 public override bool IsNativeShape(BulletShape pShape)
1104 {
1105 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
1106 bool ret;
1107 switch (shape.GetShapeType())
1108 {
1109 case BroadphaseNativeTypes.BOX_SHAPE_PROXYTYPE:
1110 case BroadphaseNativeTypes.CONE_SHAPE_PROXYTYPE:
1111 case BroadphaseNativeTypes.SPHERE_SHAPE_PROXYTYPE:
1112 case BroadphaseNativeTypes.CYLINDER_SHAPE_PROXYTYPE:
1113 ret = true;
1114 break;
1115 default:
1116 ret = false;
1117 break;
1118 }
1119 return ret;
1120 }
1121
1122 public override void SetShapeCollisionMargin(BulletShape shape, float margin) { /* TODO */ }
1123
1124 //sim.ptr, shape.ptr,prim.LocalID, prim.RawPosition, prim.RawOrientation
1125 public override BulletBody CreateGhostFromShape(BulletWorld pWorld, BulletShape pShape, uint pLocalID, Vector3 pRawPosition, Quaternion pRawOrientation)
1126 {
1127 DiscreteDynamicsWorld world = ((BulletWorldXNA)pWorld).world;
1128 IndexedMatrix bodyTransform = new IndexedMatrix();
1129 bodyTransform._origin = new IndexedVector3(pRawPosition.X, pRawPosition.Y, pRawPosition.Z);
1130 bodyTransform.SetRotation(new IndexedQuaternion(pRawOrientation.X,pRawOrientation.Y,pRawOrientation.Z,pRawOrientation.W));
1131 GhostObject gObj = new PairCachingGhostObject();
1132 gObj.SetWorldTransform(bodyTransform);
1133 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
1134 gObj.SetCollisionShape(shape);
1135 gObj.SetUserPointer(pLocalID);
1136 // TODO: Add to Special CollisionObjects!
1137 return new BulletBodyXNA(pLocalID, gObj);
1138 }
1139
1140 public override void SetCollisionShape(BulletWorld pWorld, BulletBody pObj, BulletShape pShape)
1141 {
1142 DiscreteDynamicsWorld world = ((BulletWorldXNA)pWorld).world;
1143 CollisionObject obj = ((BulletBodyXNA)pObj).body;
1144 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
1145 obj.SetCollisionShape(shape);
1146
1147 }
1148 public override BulletShape GetCollisionShape(BulletBody obj) { /* TODO */ return null; }
1149
1150 //(PhysicsScene.World.ptr, nativeShapeData)
1151 public override BulletShape BuildNativeShape(BulletWorld pWorld, ShapeData pShapeData)
1152 {
1153 DiscreteDynamicsWorld world = ((BulletWorldXNA)pWorld).world;
1154 CollisionShape shape = null;
1155 switch (pShapeData.Type)
1156 {
1157 case BSPhysicsShapeType.SHAPE_BOX:
1158 shape = new BoxShape(new IndexedVector3(0.5f,0.5f,0.5f));
1159 break;
1160 case BSPhysicsShapeType.SHAPE_CONE:
1161 shape = new ConeShapeZ(0.5f, 1.0f);
1162 break;
1163 case BSPhysicsShapeType.SHAPE_CYLINDER:
1164 shape = new CylinderShapeZ(new IndexedVector3(0.5f, 0.5f, 0.5f));
1165 break;
1166 case BSPhysicsShapeType.SHAPE_SPHERE:
1167 shape = new SphereShape(0.5f);
1168 break;
1169
1170 }
1171 if (shape != null)
1172 {
1173 IndexedVector3 scaling = new IndexedVector3(pShapeData.Scale.X, pShapeData.Scale.Y, pShapeData.Scale.Z);
1174 shape.SetMargin(world.WorldSettings.Params.collisionMargin);
1175 shape.SetLocalScaling(ref scaling);
1176
1177 }
1178 return new BulletShapeXNA(shape, pShapeData.Type);
1179 }
1180 //PhysicsScene.World.ptr, false
1181 public override BulletShape CreateCompoundShape(BulletWorld pWorld, bool enableDynamicAabbTree)
1182 {
1183 return new BulletShapeXNA(new CompoundShape(enableDynamicAabbTree), BSPhysicsShapeType.SHAPE_COMPOUND);
1184 }
1185
1186 public override int GetNumberOfCompoundChildren(BulletShape pCompoundShape)
1187 {
1188 CompoundShape compoundshape = ((BulletShapeXNA)pCompoundShape).shape as CompoundShape;
1189 return compoundshape.GetNumChildShapes();
1190 }
1191 //LinksetRoot.PhysShape.ptr, newShape.ptr, displacementPos, displacementRot
1192 public override void AddChildShapeToCompoundShape(BulletShape pCShape, BulletShape paddShape, Vector3 displacementPos, Quaternion displacementRot)
1193 {
1194 IndexedMatrix relativeTransform = new IndexedMatrix();
1195 CompoundShape compoundshape = ((BulletShapeXNA)pCShape).shape as CompoundShape;
1196 CollisionShape addshape = ((BulletShapeXNA)paddShape).shape;
1197
1198 relativeTransform._origin = new IndexedVector3(displacementPos.X, displacementPos.Y, displacementPos.Z);
1199 relativeTransform.SetRotation(new IndexedQuaternion(displacementRot.X,displacementRot.Y,displacementRot.Z,displacementRot.W));
1200 compoundshape.AddChildShape(ref relativeTransform, addshape);
1201
1202 }
1203
1204 public override BulletShape RemoveChildShapeFromCompoundShapeIndex(BulletShape pCShape, int pii)
1205 {
1206 CompoundShape compoundshape = ((BulletShapeXNA)pCShape).shape as CompoundShape;
1207 CollisionShape ret = null;
1208 ret = compoundshape.GetChildShape(pii);
1209 compoundshape.RemoveChildShapeByIndex(pii);
1210 return new BulletShapeXNA(ret, BSPhysicsShapeType.SHAPE_UNKNOWN);
1211 }
1212
1213 public override BulletShape GetChildShapeFromCompoundShapeIndex(BulletShape cShape, int indx) { /* TODO */ return null; }
1214 public override void RemoveChildShapeFromCompoundShape(BulletShape cShape, BulletShape removeShape) { /* TODO */ }
1215
1216 public override BulletShape CreateGroundPlaneShape(uint pLocalId, float pheight, float pcollisionMargin)
1217 {
1218 StaticPlaneShape m_planeshape = new StaticPlaneShape(new IndexedVector3(0,0,1),(int)pheight );
1219 m_planeshape.SetMargin(pcollisionMargin);
1220 m_planeshape.SetUserPointer(pLocalId);
1221 return new BulletShapeXNA(m_planeshape, BSPhysicsShapeType.SHAPE_GROUNDPLANE);
1222 }
1223
1224 public override BulletConstraint CreateHingeConstraint(BulletWorld pWorld, BulletBody pBody1, BulletBody ppBody2, Vector3 ppivotInA, Vector3 ppivotInB, Vector3 paxisInA, Vector3 paxisInB, bool puseLinearReferenceFrameA, bool pdisableCollisionsBetweenLinkedBodies)
1225 {
1226 HingeConstraint constrain = null;
1227 DiscreteDynamicsWorld world = ((BulletWorldXNA)pWorld).world;
1228 RigidBody rb1 = ((BulletBodyXNA)pBody1).rigidBody;
1229 RigidBody rb2 = ((BulletBodyXNA)ppBody2).rigidBody;
1230 if (rb1 != null && rb2 != null)
1231 {
1232 IndexedVector3 pivotInA = new IndexedVector3(ppivotInA.X, ppivotInA.Y, ppivotInA.Z);
1233 IndexedVector3 pivotInB = new IndexedVector3(ppivotInB.X, ppivotInB.Y, ppivotInB.Z);
1234 IndexedVector3 axisInA = new IndexedVector3(paxisInA.X, paxisInA.Y, paxisInA.Z);
1235 IndexedVector3 axisInB = new IndexedVector3(paxisInB.X, paxisInB.Y, paxisInB.Z);
1236 world.AddConstraint(constrain, pdisableCollisionsBetweenLinkedBodies);
1237 }
1238 return new BulletConstraintXNA(constrain);
1239 }
1240
1241 public override BulletShape CreateHullShape(BulletWorld pWorld, int pHullCount, float[] pConvHulls)
1242 {
1243 DiscreteDynamicsWorld world = ((BulletWorldXNA)pWorld).world;
1244 CompoundShape compoundshape = new CompoundShape(false);
1245
1246 compoundshape.SetMargin(world.WorldSettings.Params.collisionMargin);
1247 int ii = 1;
1248
1249 for (int i = 0; i < pHullCount; i++)
1250 {
1251 int vertexCount = (int) pConvHulls[ii];
1252
1253 IndexedVector3 centroid = new IndexedVector3(pConvHulls[ii + 1], pConvHulls[ii + 2], pConvHulls[ii + 3]);
1254 IndexedMatrix childTrans = IndexedMatrix.Identity;
1255 childTrans._origin = centroid;
1256
1257 List<IndexedVector3> virts = new List<IndexedVector3>();
1258 int ender = ((ii + 4) + (vertexCount*3));
1259 for (int iii = ii + 4; iii < ender; iii+=3)
1260 {
1261
1262 virts.Add(new IndexedVector3(pConvHulls[iii], pConvHulls[iii + 1], pConvHulls[iii +2]));
1263 }
1264 ConvexHullShape convexShape = new ConvexHullShape(virts, vertexCount);
1265 convexShape.SetMargin(world.WorldSettings.Params.collisionMargin);
1266 compoundshape.AddChildShape(ref childTrans, convexShape);
1267 ii += (vertexCount*3 + 4);
1268 }
1269
1270 return new BulletShapeXNA(compoundshape, BSPhysicsShapeType.SHAPE_HULL);
1271 }
1272
1273 public override BulletShape BuildHullShapeFromMesh(BulletWorld world, BulletShape meshShape) { /* TODO */ return null; }
1274
1275 public override BulletShape CreateMeshShape(BulletWorld pWorld, int pIndicesCount, int[] indices, int pVerticesCount, float[] verticesAsFloats)
1276 {
1277 //DumpRaw(indices,verticesAsFloats,pIndicesCount,pVerticesCount);
1278
1279 for (int iter = 0; iter < pVerticesCount; iter++)
1280 {
1281 if (verticesAsFloats[iter] > 0 && verticesAsFloats[iter] < 0.0001) verticesAsFloats[iter] = 0;
1282 if (verticesAsFloats[iter] < 0 && verticesAsFloats[iter] > -0.0001) verticesAsFloats[iter] = 0;
1283 }
1284
1285 ObjectArray<int> indicesarr = new ObjectArray<int>(indices);
1286 ObjectArray<float> vertices = new ObjectArray<float>(verticesAsFloats);
1287 DumpRaw(indicesarr,vertices,pIndicesCount,pVerticesCount);
1288 DiscreteDynamicsWorld world = ((BulletWorldXNA)pWorld).world;
1289 IndexedMesh mesh = new IndexedMesh();
1290 mesh.m_indexType = PHY_ScalarType.PHY_INTEGER;
1291 mesh.m_numTriangles = pIndicesCount/3;
1292 mesh.m_numVertices = pVerticesCount;
1293 mesh.m_triangleIndexBase = indicesarr;
1294 mesh.m_vertexBase = vertices;
1295 mesh.m_vertexStride = 3;
1296 mesh.m_vertexType = PHY_ScalarType.PHY_FLOAT;
1297 mesh.m_triangleIndexStride = 3;
1298
1299 TriangleIndexVertexArray tribuilder = new TriangleIndexVertexArray();
1300 tribuilder.AddIndexedMesh(mesh, PHY_ScalarType.PHY_INTEGER);
1301 BvhTriangleMeshShape meshShape = new BvhTriangleMeshShape(tribuilder, true,true);
1302 meshShape.SetMargin(world.WorldSettings.Params.collisionMargin);
1303 // world.UpdateSingleAabb(meshShape);
1304 return new BulletShapeXNA(meshShape, BSPhysicsShapeType.SHAPE_MESH);
1305
1306 }
1307 public static void DumpRaw(ObjectArray<int>indices, ObjectArray<float> vertices, int pIndicesCount,int pVerticesCount )
1308 {
1309
1310 String fileName = "objTest3.raw";
1311 String completePath = System.IO.Path.Combine(Util.configDir(), fileName);
1312 StreamWriter sw = new StreamWriter(completePath);
1313 IndexedMesh mesh = new IndexedMesh();
1314
1315 mesh.m_indexType = PHY_ScalarType.PHY_INTEGER;
1316 mesh.m_numTriangles = pIndicesCount / 3;
1317 mesh.m_numVertices = pVerticesCount;
1318 mesh.m_triangleIndexBase = indices;
1319 mesh.m_vertexBase = vertices;
1320 mesh.m_vertexStride = 3;
1321 mesh.m_vertexType = PHY_ScalarType.PHY_FLOAT;
1322 mesh.m_triangleIndexStride = 3;
1323
1324 TriangleIndexVertexArray tribuilder = new TriangleIndexVertexArray();
1325 tribuilder.AddIndexedMesh(mesh, PHY_ScalarType.PHY_INTEGER);
1326
1327
1328
1329 for (int i = 0; i < pVerticesCount; i++)
1330 {
1331
1332 string s = vertices[indices[i * 3]].ToString("0.0000");
1333 s += " " + vertices[indices[i * 3 + 1]].ToString("0.0000");
1334 s += " " + vertices[indices[i * 3 + 2]].ToString("0.0000");
1335
1336 sw.Write(s + "\n");
1337 }
1338
1339 sw.Close();
1340 }
1341 public static void DumpRaw(int[] indices, float[] vertices, int pIndicesCount, int pVerticesCount)
1342 {
1343
1344 String fileName = "objTest6.raw";
1345 String completePath = System.IO.Path.Combine(Util.configDir(), fileName);
1346 StreamWriter sw = new StreamWriter(completePath);
1347 IndexedMesh mesh = new IndexedMesh();
1348
1349 mesh.m_indexType = PHY_ScalarType.PHY_INTEGER;
1350 mesh.m_numTriangles = pIndicesCount / 3;
1351 mesh.m_numVertices = pVerticesCount;
1352 mesh.m_triangleIndexBase = indices;
1353 mesh.m_vertexBase = vertices;
1354 mesh.m_vertexStride = 3;
1355 mesh.m_vertexType = PHY_ScalarType.PHY_FLOAT;
1356 mesh.m_triangleIndexStride = 3;
1357
1358 TriangleIndexVertexArray tribuilder = new TriangleIndexVertexArray();
1359 tribuilder.AddIndexedMesh(mesh, PHY_ScalarType.PHY_INTEGER);
1360
1361
1362 sw.WriteLine("Indices");
1363 sw.WriteLine(string.Format("int[] indices = new int[{0}];",pIndicesCount));
1364 for (int iter = 0; iter < indices.Length; iter++)
1365 {
1366 sw.WriteLine(string.Format("indices[{0}]={1};",iter,indices[iter]));
1367 }
1368 sw.WriteLine("VerticesFloats");
1369 sw.WriteLine(string.Format("float[] vertices = new float[{0}];", pVerticesCount));
1370 for (int iter = 0; iter < vertices.Length; iter++)
1371 {
1372 sw.WriteLine(string.Format("Vertices[{0}]={1};", iter, vertices[iter].ToString("0.0000")));
1373 }
1374
1375 // for (int i = 0; i < pVerticesCount; i++)
1376 // {
1377 //
1378 // string s = vertices[indices[i * 3]].ToString("0.0000");
1379 // s += " " + vertices[indices[i * 3 + 1]].ToString("0.0000");
1380 // s += " " + vertices[indices[i * 3 + 2]].ToString("0.0000");
1381 //
1382 // sw.Write(s + "\n");
1383 //}
1384
1385 sw.Close();
1386 }
1387
1388 public override BulletShape CreateTerrainShape(uint id, Vector3 size, float minHeight, float maxHeight, float[] heightMap,
1389 float scaleFactor, float collisionMargin)
1390 {
1391 const int upAxis = 2;
1392 HeightfieldTerrainShape terrainShape = new HeightfieldTerrainShape((int)size.X, (int)size.Y,
1393 heightMap, scaleFactor,
1394 minHeight, maxHeight, upAxis,
1395 false);
1396 terrainShape.SetMargin(collisionMargin + 0.5f);
1397 terrainShape.SetUseDiamondSubdivision(true);
1398 terrainShape.SetUserPointer(id);
1399 return new BulletShapeXNA(terrainShape, BSPhysicsShapeType.SHAPE_TERRAIN);
1400 }
1401
1402 public override bool TranslationalLimitMotor(BulletConstraint pConstraint, float ponOff, float targetVelocity, float maxMotorForce)
1403 {
1404 TypedConstraint tconstrain = ((BulletConstraintXNA)pConstraint).constrain;
1405 bool onOff = ponOff != 0;
1406 bool ret = false;
1407
1408 switch (tconstrain.GetConstraintType())
1409 {
1410 case TypedConstraintType.D6_CONSTRAINT_TYPE:
1411 Generic6DofConstraint constrain = tconstrain as Generic6DofConstraint;
1412 constrain.GetTranslationalLimitMotor().m_enableMotor[0] = onOff;
1413 constrain.GetTranslationalLimitMotor().m_targetVelocity[0] = targetVelocity;
1414 constrain.GetTranslationalLimitMotor().m_maxMotorForce[0] = maxMotorForce;
1415 ret = true;
1416 break;
1417 }
1418
1419
1420 return ret;
1421
1422 }
1423
1424 public override int PhysicsStep(BulletWorld world, float timeStep, int maxSubSteps, float fixedTimeStep,
1425 out int updatedEntityCount, out int collidersCount)
1426 {
1427 /* TODO */
1428 updatedEntityCount = 0;
1429 collidersCount = 0;
1430 return 1;
1431 }
1432
1433 private int PhysicsStep2(BulletWorld pWorld, float timeStep, int m_maxSubSteps, float m_fixedTimeStep,
1434 out int updatedEntityCount, out List<BulletXNA.EntityProperties> updatedEntities,
1435 out int collidersCount, out List<BulletXNA.CollisionDesc>colliders)
1436 {
1437 int epic = PhysicsStepint(pWorld, timeStep, m_maxSubSteps, m_fixedTimeStep, out updatedEntityCount, out updatedEntities,
1438 out collidersCount, out colliders);
1439 return epic;
1440 }
1441
1442 private static int PhysicsStepint(BulletWorld pWorld,float timeStep, int m_maxSubSteps, float m_fixedTimeStep, out int updatedEntityCount, out List<BulletXNA.EntityProperties> updatedEntities, out int collidersCount, out List<BulletXNA.CollisionDesc> colliders)
1443 {
1444 int numSimSteps = 0;
1445
1446
1447 //if (updatedEntities is null)
1448 // updatedEntities = new List<BulletXNA.EntityProperties>();
1449
1450 //if (colliders is null)
1451 // colliders = new List<BulletXNA.CollisionDesc>();
1452
1453
1454 if (pWorld is BulletWorldXNA)
1455 {
1456 DiscreteDynamicsWorld world = ((BulletWorldXNA)pWorld).world;
1457
1458 numSimSteps = world.StepSimulation(timeStep, m_maxSubSteps, m_fixedTimeStep);
1459 int updates = 0;
1460
1461 updatedEntityCount = world.UpdatedObjects.Count;
1462 updatedEntities = new List<BulletXNA.EntityProperties>(world.UpdatedObjects);
1463 updatedEntityCount = updatedEntities.Count;
1464 world.UpdatedObjects.Clear();
1465
1466
1467 collidersCount = world.UpdatedCollisions.Count;
1468 colliders = new List<BulletXNA.CollisionDesc>(world.UpdatedCollisions);
1469
1470 world.UpdatedCollisions.Clear();
1471 m_collisionsThisFrame = 0;
1472 int numManifolds = world.GetDispatcher().GetNumManifolds();
1473 for (int j = 0; j < numManifolds; j++)
1474 {
1475 PersistentManifold contactManifold = world.GetDispatcher().GetManifoldByIndexInternal(j);
1476 int numContacts = contactManifold.GetNumContacts();
1477 if (numContacts == 0)
1478 continue;
1479
1480 CollisionObject objA = contactManifold.GetBody0() as CollisionObject;
1481 CollisionObject objB = contactManifold.GetBody1() as CollisionObject;
1482
1483 ManifoldPoint manifoldPoint = contactManifold.GetContactPoint(0);
1484 IndexedVector3 contactPoint = manifoldPoint.GetPositionWorldOnB();
1485 IndexedVector3 contactNormal = -manifoldPoint.m_normalWorldOnB; // make relative to A
1486
1487 RecordCollision(world, objA, objB, contactPoint, contactNormal);
1488 m_collisionsThisFrame ++;
1489 if (m_collisionsThisFrame >= 9999999)
1490 break;
1491
1492
1493 }
1494
1495
1496 }
1497 else
1498 {
1499 //if (updatedEntities is null)
1500 updatedEntities = new List<BulletXNA.EntityProperties>();
1501 updatedEntityCount = 0;
1502 //if (colliders is null)
1503 colliders = new List<BulletXNA.CollisionDesc>();
1504 collidersCount = 0;
1505 }
1506 return numSimSteps;
1507 }
1508
1509 private static void RecordCollision(CollisionWorld world, CollisionObject objA, CollisionObject objB, IndexedVector3 contact, IndexedVector3 norm)
1510 {
1511
1512 IndexedVector3 contactNormal = norm;
1513 if ((objA.GetCollisionFlags() & BulletXNA.BulletCollision.CollisionFlags.BS_WANTS_COLLISIONS) == 0 &&
1514 (objB.GetCollisionFlags() & BulletXNA.BulletCollision.CollisionFlags.BS_WANTS_COLLISIONS) == 0)
1515 {
1516 return;
1517 }
1518 uint idA = (uint)objA.GetUserPointer();
1519 uint idB = (uint)objB.GetUserPointer();
1520 if (idA > idB)
1521 {
1522 uint temp = idA;
1523 idA = idB;
1524 idB = temp;
1525 contactNormal = -contactNormal;
1526 }
1527
1528 ulong collisionID = ((ulong) idA << 32) | idB;
1529
1530 BulletXNA.CollisionDesc cDesc = new BulletXNA.CollisionDesc()
1531 {
1532 aID = idA,
1533 bID = idB,
1534 point = contact,
1535 normal = contactNormal
1536 };
1537 world.UpdatedCollisions.Add(cDesc);
1538 m_collisionsThisFrame++;
1539
1540
1541 }
1542 private static EntityProperties GetDebugProperties(BulletWorld pWorld, BulletBody pBody)
1543 {
1544 EntityProperties ent = new EntityProperties();
1545 DiscreteDynamicsWorld world = ((BulletWorldXNA)pWorld).world;
1546 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
1547 IndexedMatrix transform = body.GetWorldTransform();
1548 IndexedVector3 LinearVelocity = body.GetInterpolationLinearVelocity();
1549 IndexedVector3 AngularVelocity = body.GetInterpolationAngularVelocity();
1550 IndexedQuaternion rotation = transform.GetRotation();
1551 ent.Acceleration = Vector3.Zero;
1552 ent.ID = (uint)body.GetUserPointer();
1553 ent.Position = new Vector3(transform._origin.X,transform._origin.Y,transform._origin.Z);
1554 ent.Rotation = new Quaternion(rotation.X,rotation.Y,rotation.Z,rotation.W);
1555 ent.Velocity = new Vector3(LinearVelocity.X, LinearVelocity.Y, LinearVelocity.Z);
1556 ent.RotationalVelocity = new Vector3(AngularVelocity.X, AngularVelocity.Y, AngularVelocity.Z);
1557 return ent;
1558 }
1559
1560 public override bool UpdateParameter(BulletWorld world, uint localID, String parm, float value) { /* TODO */ return false; }
1561
1562 public override Vector3 GetLocalScaling(BulletShape pShape)
1563 {
1564 CollisionShape shape = ((BulletShapeXNA)pShape).shape;
1565 IndexedVector3 scale = shape.GetLocalScaling();
1566 return new Vector3(scale.X,scale.Y,scale.Z);
1567 }
1568
1569 public bool RayCastGround(BulletWorld pWorld, Vector3 _RayOrigin, float pRayHeight, BulletBody NotMe)
1570 {
1571 DiscreteDynamicsWorld world = ((BulletWorldXNA)pWorld).world;
1572 if (world != null)
1573 {
1574 if (NotMe is BulletBodyXNA && NotMe.HasPhysicalBody)
1575 {
1576 CollisionObject AvoidBody = ((BulletBodyXNA)NotMe).body;
1577
1578 IndexedVector3 rOrigin = new IndexedVector3(_RayOrigin.X, _RayOrigin.Y, _RayOrigin.Z);
1579 IndexedVector3 rEnd = new IndexedVector3(_RayOrigin.X, _RayOrigin.Y, _RayOrigin.Z - pRayHeight);
1580 using (
1581 ClosestNotMeRayResultCallback rayCallback =
1582 new ClosestNotMeRayResultCallback(rOrigin, rEnd, AvoidBody)
1583 )
1584 {
1585 world.RayTest(ref rOrigin, ref rEnd, rayCallback);
1586 if (rayCallback.HasHit())
1587 {
1588 IndexedVector3 hitLocation = rayCallback.m_hitPointWorld;
1589 }
1590 return rayCallback.HasHit();
1591 }
1592 }
1593 }
1594 return false;
1595 }
1596}
1597}