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.cs1959
1 files changed, 1959 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..49b1730
--- /dev/null
+++ b/OpenSim/Region/Physics/BulletSPlugin/BSAPIXNA.cs
@@ -0,0 +1,1959 @@
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 internal int m_maxCollisions;
133 internal CollisionDesc[] m_collisionArray;
134
135 internal int m_maxUpdatesPerFrame;
136 internal EntityProperties[] m_updateArray;
137
138 private static int m_collisionsThisFrame;
139 private BSScene PhysicsScene { get; set; }
140
141 public override string BulletEngineName { get { return "BulletXNA"; } }
142 public override string BulletEngineVersion { get; protected set; }
143
144 public BSAPIXNA(string paramName, BSScene physScene)
145 {
146 PhysicsScene = physScene;
147 }
148
149 /// <summary>
150 ///
151 /// </summary>
152 /// <param name="p"></param>
153 /// <param name="p_2"></param>
154 public override bool RemoveObjectFromWorld(BulletWorld pWorld, BulletBody pBody)
155 {
156 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
157 RigidBody body = ((BulletBodyXNA)pBody).rigidBody;
158 world.RemoveRigidBody(body);
159 return true;
160 }
161
162 public override bool AddConstraintToWorld(BulletWorld pWorld, BulletConstraint pConstraint, bool pDisableCollisionsBetweenLinkedObjects)
163 {
164 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
165 TypedConstraint constraint = (pConstraint as BulletConstraintXNA).constrain;
166 world.AddConstraint(constraint, pDisableCollisionsBetweenLinkedObjects);
167
168 return true;
169
170 }
171
172 public override bool RemoveConstraintFromWorld(BulletWorld pWorld, BulletConstraint pConstraint)
173 {
174 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
175 TypedConstraint constraint = (pConstraint as BulletConstraintXNA).constrain;
176 world.RemoveConstraint(constraint);
177 return true;
178 }
179
180 public override void SetRestitution(BulletBody pCollisionObject, float pRestitution)
181 {
182 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
183 collisionObject.SetRestitution(pRestitution);
184 }
185
186 public override int GetShapeType(BulletShape pShape)
187 {
188 CollisionShape shape = (pShape as BulletShapeXNA).shape;
189 return (int)shape.GetShapeType();
190 }
191 public override void SetMargin(BulletShape pShape, float pMargin)
192 {
193 CollisionShape shape = (pShape as BulletShapeXNA).shape;
194 shape.SetMargin(pMargin);
195 }
196
197 public override float GetMargin(BulletShape pShape)
198 {
199 CollisionShape shape = (pShape as BulletShapeXNA).shape;
200 return shape.GetMargin();
201 }
202
203 public override void SetLocalScaling(BulletShape pShape, Vector3 pScale)
204 {
205 CollisionShape shape = (pShape as BulletShapeXNA).shape;
206 IndexedVector3 vec = new IndexedVector3(pScale.X, pScale.Y, pScale.Z);
207 shape.SetLocalScaling(ref vec);
208
209 }
210
211 public override void SetContactProcessingThreshold(BulletBody pCollisionObject, float contactprocessingthreshold)
212 {
213 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
214 collisionObject.SetContactProcessingThreshold(contactprocessingthreshold);
215 }
216
217 public override void SetCcdMotionThreshold(BulletBody pCollisionObject, float pccdMotionThreashold)
218 {
219 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
220 collisionObject.SetCcdMotionThreshold(pccdMotionThreashold);
221 }
222
223 public override void SetCcdSweptSphereRadius(BulletBody pCollisionObject, float pCcdSweptSphereRadius)
224 {
225 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
226 collisionObject.SetCcdSweptSphereRadius(pCcdSweptSphereRadius);
227 }
228
229 public override void SetAngularFactorV(BulletBody pBody, Vector3 pAngularFactor)
230 {
231 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
232 body.SetAngularFactor(new IndexedVector3(pAngularFactor.X, pAngularFactor.Y, pAngularFactor.Z));
233 }
234
235 public override CollisionFlags AddToCollisionFlags(BulletBody pCollisionObject, CollisionFlags pcollisionFlags)
236 {
237 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).body;
238 CollisionFlags existingcollisionFlags = (CollisionFlags)(uint)collisionObject.GetCollisionFlags();
239 existingcollisionFlags |= pcollisionFlags;
240 collisionObject.SetCollisionFlags((BulletXNA.BulletCollision.CollisionFlags)(uint)existingcollisionFlags);
241 return (CollisionFlags) (uint) existingcollisionFlags;
242 }
243
244 public override bool AddObjectToWorld(BulletWorld pWorld, BulletBody pBody)
245 {
246 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
247 CollisionObject cbody = (pBody as BulletBodyXNA).body;
248 RigidBody rbody = cbody as RigidBody;
249
250 // Bullet resets several variables when an object is added to the world. In particular,
251 // BulletXNA resets position and rotation. Gravity is also reset depending on the static/dynamic
252 // type. Of course, the collision flags in the broadphase proxy are initialized to default.
253 IndexedMatrix origPos = cbody.GetWorldTransform();
254 if (rbody != null)
255 {
256 IndexedVector3 origGrav = rbody.GetGravity();
257 world.AddRigidBody(rbody);
258 rbody.SetGravity(origGrav);
259 }
260 else
261 {
262 world.AddCollisionObject(rbody);
263 }
264 cbody.SetWorldTransform(origPos);
265
266 pBody.ApplyCollisionMask(pWorld.physicsScene);
267
268 //if (body.GetBroadphaseHandle() != null)
269 // world.UpdateSingleAabb(body);
270 return true;
271 }
272
273 public override void ForceActivationState(BulletBody pCollisionObject, ActivationState pActivationState)
274 {
275 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).body;
276 collisionObject.ForceActivationState((BulletXNA.BulletCollision.ActivationState)(uint)pActivationState);
277 }
278
279 public override void UpdateSingleAabb(BulletWorld pWorld, BulletBody pCollisionObject)
280 {
281 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
282 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).body;
283 world.UpdateSingleAabb(collisionObject);
284 }
285
286 public override void UpdateAabbs(BulletWorld pWorld) {
287 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
288 world.UpdateAabbs();
289 }
290 public override bool GetForceUpdateAllAabbs(BulletWorld pWorld) {
291 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
292 return world.GetForceUpdateAllAabbs();
293
294 }
295 public override void SetForceUpdateAllAabbs(BulletWorld pWorld, bool pForce)
296 {
297 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
298 world.SetForceUpdateAllAabbs(pForce);
299 }
300
301 public override bool SetCollisionGroupMask(BulletBody pCollisionObject, uint pGroup, uint pMask)
302 {
303 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
304 collisionObject.GetBroadphaseHandle().m_collisionFilterGroup = (BulletXNA.BulletCollision.CollisionFilterGroups) pGroup;
305 collisionObject.GetBroadphaseHandle().m_collisionFilterGroup = (BulletXNA.BulletCollision.CollisionFilterGroups) pGroup;
306 if ((uint) collisionObject.GetBroadphaseHandle().m_collisionFilterGroup == 0)
307 return false;
308 return true;
309 }
310
311 public override void ClearAllForces(BulletBody pCollisionObject)
312 {
313 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).body;
314 IndexedVector3 zeroVector = new IndexedVector3(0, 0, 0);
315 collisionObject.SetInterpolationLinearVelocity(ref zeroVector);
316 collisionObject.SetInterpolationAngularVelocity(ref zeroVector);
317 IndexedMatrix bodytransform = collisionObject.GetWorldTransform();
318
319 collisionObject.SetInterpolationWorldTransform(ref bodytransform);
320
321 if (collisionObject is RigidBody)
322 {
323 RigidBody rigidbody = collisionObject as RigidBody;
324 rigidbody.SetLinearVelocity(zeroVector);
325 rigidbody.SetAngularVelocity(zeroVector);
326 rigidbody.ClearForces();
327 }
328 }
329
330 public override void SetInterpolationAngularVelocity(BulletBody pCollisionObject, Vector3 pVector3)
331 {
332 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
333 IndexedVector3 vec = new IndexedVector3(pVector3.X, pVector3.Y, pVector3.Z);
334 collisionObject.SetInterpolationAngularVelocity(ref vec);
335 }
336
337 public override void SetAngularVelocity(BulletBody pBody, Vector3 pVector3)
338 {
339 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
340 IndexedVector3 vec = new IndexedVector3(pVector3.X, pVector3.Y, pVector3.Z);
341 body.SetAngularVelocity(ref vec);
342 }
343 public override Vector3 GetTotalForce(BulletBody pBody)
344 {
345 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
346 IndexedVector3 iv3 = body.GetTotalForce();
347 return new Vector3(iv3.X, iv3.Y, iv3.Z);
348 }
349 public override Vector3 GetTotalTorque(BulletBody pBody)
350 {
351 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
352 IndexedVector3 iv3 = body.GetTotalTorque();
353 return new Vector3(iv3.X, iv3.Y, iv3.Z);
354 }
355 public override Vector3 GetInvInertiaDiagLocal(BulletBody pBody)
356 {
357 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
358 IndexedVector3 iv3 = body.GetInvInertiaDiagLocal();
359 return new Vector3(iv3.X, iv3.Y, iv3.Z);
360 }
361 public override void SetInvInertiaDiagLocal(BulletBody pBody, Vector3 inert)
362 {
363 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
364 IndexedVector3 iv3 = new IndexedVector3(inert.X, inert.Y, inert.Z);
365 body.SetInvInertiaDiagLocal(ref iv3);
366 }
367 public override void ApplyForce(BulletBody pBody, Vector3 force, Vector3 pos)
368 {
369 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
370 IndexedVector3 forceiv3 = new IndexedVector3(force.X, force.Y, force.Z);
371 IndexedVector3 posiv3 = new IndexedVector3(pos.X, pos.Y, pos.Z);
372 body.ApplyForce(ref forceiv3, ref posiv3);
373 }
374 public override void ApplyImpulse(BulletBody pBody, Vector3 imp, Vector3 pos)
375 {
376 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
377 IndexedVector3 impiv3 = new IndexedVector3(imp.X, imp.Y, imp.Z);
378 IndexedVector3 posiv3 = new IndexedVector3(pos.X, pos.Y, pos.Z);
379 body.ApplyImpulse(ref impiv3, ref posiv3);
380 }
381
382 public override void ClearForces(BulletBody pBody)
383 {
384 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
385 body.ClearForces();
386 }
387
388 public override void SetTranslation(BulletBody pCollisionObject, Vector3 _position, Quaternion _orientation)
389 {
390 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
391 IndexedVector3 vposition = new IndexedVector3(_position.X, _position.Y, _position.Z);
392 IndexedQuaternion vquaternion = new IndexedQuaternion(_orientation.X, _orientation.Y, _orientation.Z,
393 _orientation.W);
394 IndexedMatrix mat = IndexedMatrix.CreateFromQuaternion(vquaternion);
395 mat._origin = vposition;
396 collisionObject.SetWorldTransform(mat);
397
398 }
399
400 public override Vector3 GetPosition(BulletBody pCollisionObject)
401 {
402 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
403 IndexedVector3 pos = collisionObject.GetInterpolationWorldTransform()._origin;
404 return new Vector3(pos.X, pos.Y, pos.Z);
405 }
406
407 public override Vector3 CalculateLocalInertia(BulletShape pShape, float pphysMass)
408 {
409 CollisionShape shape = (pShape as BulletShapeXNA).shape;
410 IndexedVector3 inertia = IndexedVector3.Zero;
411 shape.CalculateLocalInertia(pphysMass, out inertia);
412 return new Vector3(inertia.X, inertia.Y, inertia.Z);
413 }
414
415 public override void SetMassProps(BulletBody pBody, float pphysMass, Vector3 plocalInertia)
416 {
417 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
418 IndexedVector3 inertia = new IndexedVector3(plocalInertia.X, plocalInertia.Y, plocalInertia.Z);
419 body.SetMassProps(pphysMass, inertia);
420 }
421
422
423 public override void SetObjectForce(BulletBody pBody, Vector3 _force)
424 {
425 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
426 IndexedVector3 force = new IndexedVector3(_force.X, _force.Y, _force.Z);
427 body.SetTotalForce(ref force);
428 }
429
430 public override void SetFriction(BulletBody pCollisionObject, float _currentFriction)
431 {
432 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
433 collisionObject.SetFriction(_currentFriction);
434 }
435
436 public override void SetLinearVelocity(BulletBody pBody, Vector3 _velocity)
437 {
438 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
439 IndexedVector3 velocity = new IndexedVector3(_velocity.X, _velocity.Y, _velocity.Z);
440 body.SetLinearVelocity(velocity);
441 }
442
443 public override void Activate(BulletBody pCollisionObject, bool pforceactivation)
444 {
445 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
446 collisionObject.Activate(pforceactivation);
447
448 }
449
450 public override Quaternion GetOrientation(BulletBody pCollisionObject)
451 {
452 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
453 IndexedQuaternion mat = collisionObject.GetInterpolationWorldTransform().GetRotation();
454 return new Quaternion(mat.X, mat.Y, mat.Z, mat.W);
455 }
456
457 public override CollisionFlags RemoveFromCollisionFlags(BulletBody pCollisionObject, CollisionFlags pcollisionFlags)
458 {
459 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
460 CollisionFlags existingcollisionFlags = (CollisionFlags)(uint)collisionObject.GetCollisionFlags();
461 existingcollisionFlags &= ~pcollisionFlags;
462 collisionObject.SetCollisionFlags((BulletXNA.BulletCollision.CollisionFlags)(uint)existingcollisionFlags);
463 return (CollisionFlags)(uint)existingcollisionFlags;
464 }
465
466 public override float GetCcdMotionThreshold(BulletBody pCollisionObject)
467 {
468 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
469 return collisionObject.GetCcdSquareMotionThreshold();
470 }
471
472 public override float GetCcdSweptSphereRadius(BulletBody pCollisionObject)
473 {
474 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
475 return collisionObject.GetCcdSweptSphereRadius();
476
477 }
478
479 public override IntPtr GetUserPointer(BulletBody pCollisionObject)
480 {
481 CollisionObject shape = (pCollisionObject as BulletBodyXNA).body;
482 return (IntPtr)shape.GetUserPointer();
483 }
484
485 public override void SetUserPointer(BulletBody pCollisionObject, IntPtr val)
486 {
487 CollisionObject shape = (pCollisionObject as BulletBodyXNA).body;
488 shape.SetUserPointer(val);
489 }
490
491 public override void SetGravity(BulletBody pBody, Vector3 pGravity)
492 {
493 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
494 IndexedVector3 gravity = new IndexedVector3(pGravity.X, pGravity.Y, pGravity.Z);
495 body.SetGravity(gravity);
496 }
497
498 public override bool DestroyConstraint(BulletWorld pWorld, BulletConstraint pConstraint)
499 {
500 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
501 TypedConstraint constraint = (pConstraint as BulletConstraintXNA).constrain;
502 world.RemoveConstraint(constraint);
503 return true;
504 }
505
506 public override bool SetLinearLimits(BulletConstraint pConstraint, Vector3 low, Vector3 high)
507 {
508 Generic6DofConstraint constraint = (pConstraint as BulletConstraintXNA).constrain as Generic6DofConstraint;
509 IndexedVector3 lowlimit = new IndexedVector3(low.X, low.Y, low.Z);
510 IndexedVector3 highlimit = new IndexedVector3(high.X, high.Y, high.Z);
511 constraint.SetLinearLowerLimit(lowlimit);
512 constraint.SetLinearUpperLimit(highlimit);
513 return true;
514 }
515
516 public override bool SetAngularLimits(BulletConstraint pConstraint, Vector3 low, Vector3 high)
517 {
518 Generic6DofConstraint constraint = (pConstraint as BulletConstraintXNA).constrain as Generic6DofConstraint;
519 IndexedVector3 lowlimit = new IndexedVector3(low.X, low.Y, low.Z);
520 IndexedVector3 highlimit = new IndexedVector3(high.X, high.Y, high.Z);
521 constraint.SetAngularLowerLimit(lowlimit);
522 constraint.SetAngularUpperLimit(highlimit);
523 return true;
524 }
525
526 public override void SetConstraintNumSolverIterations(BulletConstraint pConstraint, float cnt)
527 {
528 Generic6DofConstraint constraint = (pConstraint as BulletConstraintXNA).constrain as Generic6DofConstraint;
529 constraint.SetOverrideNumSolverIterations((int)cnt);
530 }
531
532 public override bool CalculateTransforms(BulletConstraint pConstraint)
533 {
534 Generic6DofConstraint constraint = (pConstraint as BulletConstraintXNA).constrain as Generic6DofConstraint;
535 constraint.CalculateTransforms();
536 return true;
537 }
538
539 public override void SetConstraintEnable(BulletConstraint pConstraint, float p_2)
540 {
541 Generic6DofConstraint constraint = (pConstraint as BulletConstraintXNA).constrain as Generic6DofConstraint;
542 constraint.SetEnabled((p_2 == 0) ? false : true);
543 }
544
545
546 //BulletSimAPI.Create6DofConstraint(m_world.ptr, m_body1.ptr, m_body2.ptr,frame1, frame1rot,frame2, frame2rot,useLinearReferenceFrameA, disableCollisionsBetweenLinkedBodies));
547 public override BulletConstraint Create6DofConstraint(BulletWorld pWorld, BulletBody pBody1, BulletBody pBody2, Vector3 pframe1, Quaternion pframe1rot, Vector3 pframe2, Quaternion pframe2rot, bool puseLinearReferenceFrameA, bool pdisableCollisionsBetweenLinkedBodies)
548
549 {
550 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
551 RigidBody body1 = (pBody1 as BulletBodyXNA).rigidBody;
552 RigidBody body2 = (pBody2 as BulletBodyXNA).rigidBody;
553 IndexedVector3 frame1v = new IndexedVector3(pframe1.X, pframe1.Y, pframe1.Z);
554 IndexedQuaternion frame1rot = new IndexedQuaternion(pframe1rot.X, pframe1rot.Y, pframe1rot.Z, pframe1rot.W);
555 IndexedMatrix frame1 = IndexedMatrix.CreateFromQuaternion(frame1rot);
556 frame1._origin = frame1v;
557
558 IndexedVector3 frame2v = new IndexedVector3(pframe2.X, pframe2.Y, pframe2.Z);
559 IndexedQuaternion frame2rot = new IndexedQuaternion(pframe2rot.X, pframe2rot.Y, pframe2rot.Z, pframe2rot.W);
560 IndexedMatrix frame2 = IndexedMatrix.CreateFromQuaternion(frame2rot);
561 frame2._origin = frame1v;
562
563 Generic6DofConstraint consttr = new Generic6DofConstraint(body1, body2, ref frame1, ref frame2,
564 puseLinearReferenceFrameA);
565 consttr.CalculateTransforms();
566 world.AddConstraint(consttr,pdisableCollisionsBetweenLinkedBodies);
567
568 return new BulletConstraintXNA(consttr);
569 }
570
571
572 /// <summary>
573 ///
574 /// </summary>
575 /// <param name="pWorld"></param>
576 /// <param name="pBody1"></param>
577 /// <param name="pBody2"></param>
578 /// <param name="pjoinPoint"></param>
579 /// <param name="puseLinearReferenceFrameA"></param>
580 /// <param name="pdisableCollisionsBetweenLinkedBodies"></param>
581 /// <returns></returns>
582 public override BulletConstraint Create6DofConstraintToPoint(BulletWorld pWorld, BulletBody pBody1, BulletBody pBody2, Vector3 pjoinPoint, bool puseLinearReferenceFrameA, bool pdisableCollisionsBetweenLinkedBodies)
583 {
584 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
585 RigidBody body1 = (pBody1 as BulletBodyXNA).rigidBody;
586 RigidBody body2 = (pBody2 as BulletBodyXNA).rigidBody;
587 IndexedMatrix frame1 = new IndexedMatrix(IndexedBasisMatrix.Identity, new IndexedVector3(0, 0, 0));
588 IndexedMatrix frame2 = new IndexedMatrix(IndexedBasisMatrix.Identity, new IndexedVector3(0, 0, 0));
589
590 IndexedVector3 joinPoint = new IndexedVector3(pjoinPoint.X, pjoinPoint.Y, pjoinPoint.Z);
591 IndexedMatrix mat = IndexedMatrix.Identity;
592 mat._origin = new IndexedVector3(pjoinPoint.X, pjoinPoint.Y, pjoinPoint.Z);
593 frame1._origin = body1.GetWorldTransform().Inverse()*joinPoint;
594 frame2._origin = body2.GetWorldTransform().Inverse()*joinPoint;
595
596 Generic6DofConstraint consttr = new Generic6DofConstraint(body1, body2, ref frame1, ref frame2, puseLinearReferenceFrameA);
597 consttr.CalculateTransforms();
598 world.AddConstraint(consttr, pdisableCollisionsBetweenLinkedBodies);
599
600 return new BulletConstraintXNA(consttr);
601 }
602 //SetFrames(m_constraint.ptr, frameA, frameArot, frameB, frameBrot);
603 public override bool SetFrames(BulletConstraint pConstraint, Vector3 pframe1, Quaternion pframe1rot, Vector3 pframe2, Quaternion pframe2rot)
604 {
605 Generic6DofConstraint constraint = (pConstraint as BulletConstraintXNA).constrain as Generic6DofConstraint;
606 IndexedVector3 frame1v = new IndexedVector3(pframe1.X, pframe1.Y, pframe1.Z);
607 IndexedQuaternion frame1rot = new IndexedQuaternion(pframe1rot.X, pframe1rot.Y, pframe1rot.Z, pframe1rot.W);
608 IndexedMatrix frame1 = IndexedMatrix.CreateFromQuaternion(frame1rot);
609 frame1._origin = frame1v;
610
611 IndexedVector3 frame2v = new IndexedVector3(pframe2.X, pframe2.Y, pframe2.Z);
612 IndexedQuaternion frame2rot = new IndexedQuaternion(pframe2rot.X, pframe2rot.Y, pframe2rot.Z, pframe2rot.W);
613 IndexedMatrix frame2 = IndexedMatrix.CreateFromQuaternion(frame2rot);
614 frame2._origin = frame1v;
615 constraint.SetFrames(ref frame1, ref frame2);
616 return true;
617 }
618
619 public override Vector3 GetLinearVelocity(BulletBody pBody)
620 {
621 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
622 IndexedVector3 iv3 = body.GetLinearVelocity();
623 return new Vector3(iv3.X, iv3.Y, iv3.Z);
624 }
625 public override Vector3 GetAngularVelocity(BulletBody pBody)
626 {
627 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
628 IndexedVector3 iv3 = body.GetAngularVelocity();
629 return new Vector3(iv3.X, iv3.Y, iv3.Z);
630 }
631 public override Vector3 GetVelocityInLocalPoint(BulletBody pBody, Vector3 pos)
632 {
633 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
634 IndexedVector3 posiv3 = new IndexedVector3(pos.X, pos.Y, pos.Z);
635 IndexedVector3 iv3 = body.GetVelocityInLocalPoint(ref posiv3);
636 return new Vector3(iv3.X, iv3.Y, iv3.Z);
637 }
638 public override void Translate(BulletBody pCollisionObject, Vector3 trans)
639 {
640 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
641 collisionObject.Translate(new IndexedVector3(trans.X,trans.Y,trans.Z));
642 }
643 public override void UpdateDeactivation(BulletBody pBody, float timeStep)
644 {
645 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
646 body.UpdateDeactivation(timeStep);
647 }
648
649 public override bool WantsSleeping(BulletBody pBody)
650 {
651 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
652 return body.WantsSleeping();
653 }
654
655 public override void SetAngularFactor(BulletBody pBody, float factor)
656 {
657 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
658 body.SetAngularFactor(factor);
659 }
660
661 public override Vector3 GetAngularFactor(BulletBody pBody)
662 {
663 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
664 IndexedVector3 iv3 = body.GetAngularFactor();
665 return new Vector3(iv3.X, iv3.Y, iv3.Z);
666 }
667
668 public override bool IsInWorld(BulletWorld pWorld, BulletBody pCollisionObject)
669 {
670 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
671 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).body;
672 return world.IsInWorld(collisionObject);
673 }
674
675 public override void AddConstraintRef(BulletBody pBody, BulletConstraint pConstraint)
676 {
677 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
678 TypedConstraint constrain = (pConstraint as BulletConstraintXNA).constrain;
679 body.AddConstraintRef(constrain);
680 }
681
682 public override void RemoveConstraintRef(BulletBody pBody, BulletConstraint pConstraint)
683 {
684 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
685 TypedConstraint constrain = (pConstraint as BulletConstraintXNA).constrain;
686 body.RemoveConstraintRef(constrain);
687 }
688
689 public override BulletConstraint GetConstraintRef(BulletBody pBody, int index)
690 {
691 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
692 return new BulletConstraintXNA(body.GetConstraintRef(index));
693 }
694
695 public override int GetNumConstraintRefs(BulletBody pBody)
696 {
697 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
698 return body.GetNumConstraintRefs();
699 }
700
701 public override void SetInterpolationLinearVelocity(BulletBody pCollisionObject, Vector3 VehicleVelocity)
702 {
703 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
704 IndexedVector3 velocity = new IndexedVector3(VehicleVelocity.X, VehicleVelocity.Y, VehicleVelocity.Z);
705 collisionObject.SetInterpolationLinearVelocity(ref velocity);
706 }
707
708 public override bool UseFrameOffset(BulletConstraint pConstraint, float onOff)
709 {
710 Generic6DofConstraint constraint = (pConstraint as BulletConstraintXNA).constrain as Generic6DofConstraint;
711 constraint.SetUseFrameOffset((onOff == 0) ? false : true);
712 return true;
713 }
714 //SetBreakingImpulseThreshold(m_constraint.ptr, threshold);
715 public override bool SetBreakingImpulseThreshold(BulletConstraint pConstraint, float threshold)
716 {
717 Generic6DofConstraint constraint = (pConstraint as BulletConstraintXNA).constrain as Generic6DofConstraint;
718 constraint.SetBreakingImpulseThreshold(threshold);
719 return true;
720 }
721 //BulletSimAPI.SetAngularDamping(Prim.PhysBody.ptr, angularDamping);
722 public override void SetAngularDamping(BulletBody pBody, float angularDamping)
723 {
724 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
725 float lineardamping = body.GetLinearDamping();
726 body.SetDamping(lineardamping, angularDamping);
727
728 }
729
730 public override void UpdateInertiaTensor(BulletBody pBody)
731 {
732 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
733 body.UpdateInertiaTensor();
734 }
735
736 public override void RecalculateCompoundShapeLocalAabb(BulletShape pCompoundShape)
737 {
738 CompoundShape shape = (pCompoundShape as BulletShapeXNA).shape as CompoundShape;
739 shape.RecalculateLocalAabb();
740 }
741
742 //BulletSimAPI.GetCollisionFlags(PhysBody.ptr)
743 public override CollisionFlags GetCollisionFlags(BulletBody pCollisionObject)
744 {
745 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
746 uint flags = (uint)collisionObject.GetCollisionFlags();
747 return (CollisionFlags) flags;
748 }
749
750 public override void SetDamping(BulletBody pBody, float pLinear, float pAngular)
751 {
752 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
753 body.SetDamping(pLinear, pAngular);
754 }
755 //PhysBody.ptr, PhysicsScene.Params.deactivationTime);
756 public override void SetDeactivationTime(BulletBody pCollisionObject, float pDeactivationTime)
757 {
758 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
759 collisionObject.SetDeactivationTime(pDeactivationTime);
760 }
761 //SetSleepingThresholds(PhysBody.ptr, PhysicsScene.Params.linearSleepingThreshold, PhysicsScene.Params.angularSleepingThreshold);
762 public override void SetSleepingThresholds(BulletBody pBody, float plinearSleepingThreshold, float pangularSleepingThreshold)
763 {
764 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
765 body.SetSleepingThresholds(plinearSleepingThreshold, pangularSleepingThreshold);
766 }
767
768 public override CollisionObjectTypes GetBodyType(BulletBody pCollisionObject)
769 {
770 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
771 return (CollisionObjectTypes)(int) collisionObject.GetInternalType();
772 }
773
774 public override void ApplyGravity(BulletBody pBody)
775 {
776
777 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
778 body.ApplyGravity();
779 }
780
781 public override Vector3 GetGravity(BulletBody pBody)
782 {
783 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
784 IndexedVector3 gravity = body.GetGravity();
785 return new Vector3(gravity.X, gravity.Y, gravity.Z);
786 }
787
788 public override void SetLinearDamping(BulletBody pBody, float lin_damping)
789 {
790 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
791 float angularDamping = body.GetAngularDamping();
792 body.SetDamping(lin_damping, angularDamping);
793 }
794
795 public override float GetLinearDamping(BulletBody pBody)
796 {
797 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
798 return body.GetLinearDamping();
799 }
800
801 public override float GetAngularDamping(BulletBody pBody)
802 {
803 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
804 return body.GetAngularDamping();
805 }
806
807 public override float GetLinearSleepingThreshold(BulletBody pBody)
808 {
809 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
810 return body.GetLinearSleepingThreshold();
811 }
812
813 public override void ApplyDamping(BulletBody pBody, float timeStep)
814 {
815 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
816 body.ApplyDamping(timeStep);
817 }
818
819 public override Vector3 GetLinearFactor(BulletBody pBody)
820 {
821 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
822 IndexedVector3 linearFactor = body.GetLinearFactor();
823 return new Vector3(linearFactor.X, linearFactor.Y, linearFactor.Z);
824 }
825
826 public override void SetLinearFactor(BulletBody pBody, Vector3 factor)
827 {
828 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
829 body.SetLinearFactor(new IndexedVector3(factor.X, factor.Y, factor.Z));
830 }
831
832 public override void SetCenterOfMassByPosRot(BulletBody pBody, Vector3 pos, Quaternion rot)
833 {
834 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
835 IndexedQuaternion quat = new IndexedQuaternion(rot.X, rot.Y, rot.Z,rot.W);
836 IndexedMatrix mat = IndexedMatrix.CreateFromQuaternion(quat);
837 mat._origin = new IndexedVector3(pos.X, pos.Y, pos.Z);
838 body.SetCenterOfMassTransform( ref mat);
839 /* TODO: double check this */
840 }
841
842 //BulletSimAPI.ApplyCentralForce(PhysBody.ptr, fSum);
843 public override void ApplyCentralForce(BulletBody pBody, Vector3 pfSum)
844 {
845 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
846 IndexedVector3 fSum = new IndexedVector3(pfSum.X, pfSum.Y, pfSum.Z);
847 body.ApplyCentralForce(ref fSum);
848 }
849 public override void ApplyCentralImpulse(BulletBody pBody, Vector3 pfSum)
850 {
851 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
852 IndexedVector3 fSum = new IndexedVector3(pfSum.X, pfSum.Y, pfSum.Z);
853 body.ApplyCentralImpulse(ref fSum);
854 }
855 public override void ApplyTorque(BulletBody pBody, Vector3 pfSum)
856 {
857 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
858 IndexedVector3 fSum = new IndexedVector3(pfSum.X, pfSum.Y, pfSum.Z);
859 body.ApplyTorque(ref fSum);
860 }
861 public override void ApplyTorqueImpulse(BulletBody pBody, Vector3 pfSum)
862 {
863 RigidBody body = (pBody as BulletBodyXNA).rigidBody;
864 IndexedVector3 fSum = new IndexedVector3(pfSum.X, pfSum.Y, pfSum.Z);
865 body.ApplyTorqueImpulse(ref fSum);
866 }
867
868 public override void DestroyObject(BulletWorld pWorld, BulletBody pBody)
869 {
870 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
871 CollisionObject co = (pBody as BulletBodyXNA).rigidBody;
872 RigidBody bo = co as RigidBody;
873 if (bo == null)
874 {
875
876 if (world.IsInWorld(co))
877 {
878 world.RemoveCollisionObject(co);
879 }
880 }
881 else
882 {
883
884 if (world.IsInWorld(bo))
885 {
886 world.RemoveRigidBody(bo);
887 }
888 }
889
890 }
891
892 public override void Shutdown(BulletWorld pWorld)
893 {
894 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
895 world.Cleanup();
896 }
897
898 public override BulletShape DuplicateCollisionShape(BulletWorld pWorld, BulletShape pShape, uint id)
899 {
900 CollisionShape shape1 = (pShape as BulletShapeXNA).shape;
901
902 // TODO: Turn this from a reference copy to a Value Copy.
903 BulletShapeXNA shape2 = new BulletShapeXNA(shape1, BSPhysicsShapeType.SHAPE_UNKNOWN);
904
905 return shape2;
906 }
907
908 public override bool DeleteCollisionShape(BulletWorld pWorld, BulletShape pShape)
909 {
910 //TODO:
911 return false;
912 }
913 //(sim.ptr, shape.ptr, prim.LocalID, prim.RawPosition, prim.RawOrientation);
914
915 public override BulletBody CreateBodyFromShape(BulletWorld pWorld, BulletShape pShape, uint pLocalID, Vector3 pRawPosition, Quaternion pRawOrientation)
916 {
917 CollisionWorld world = (pWorld as BulletWorldXNA).world;
918 IndexedMatrix mat =
919 IndexedMatrix.CreateFromQuaternion(new IndexedQuaternion(pRawOrientation.X, pRawOrientation.Y,
920 pRawOrientation.Z, pRawOrientation.W));
921 mat._origin = new IndexedVector3(pRawPosition.X, pRawPosition.Y, pRawPosition.Z);
922 CollisionShape shape = (pShape as BulletShapeXNA).shape;
923 //UpdateSingleAabb(world, shape);
924 // TODO: Feed Update array into null
925 SimMotionState motionState = new SimMotionState(world, pLocalID, mat, null);
926 RigidBody body = new RigidBody(0,motionState,shape,IndexedVector3.Zero);
927 RigidBodyConstructionInfo constructionInfo = new RigidBodyConstructionInfo(0, new SimMotionState(world, pLocalID, mat, null),shape,IndexedVector3.Zero)
928 {
929 m_mass = 0
930 };
931 /*
932 m_mass = mass;
933 m_motionState =motionState;
934 m_collisionShape = collisionShape;
935 m_localInertia = localInertia;
936 m_linearDamping = 0f;
937 m_angularDamping = 0f;
938 m_friction = 0.5f;
939 m_restitution = 0f;
940 m_linearSleepingThreshold = 0.8f;
941 m_angularSleepingThreshold = 1f;
942 m_additionalDamping = false;
943 m_additionalDampingFactor = 0.005f;
944 m_additionalLinearDampingThresholdSqr = 0.01f;
945 m_additionalAngularDampingThresholdSqr = 0.01f;
946 m_additionalAngularDampingFactor = 0.01f;
947 m_startWorldTransform = IndexedMatrix.Identity;
948 */
949 body.SetUserPointer(pLocalID);
950
951 return new BulletBodyXNA(pLocalID, body);
952 }
953
954
955 public override BulletBody CreateBodyWithDefaultMotionState( BulletShape pShape, uint pLocalID, Vector3 pRawPosition, Quaternion pRawOrientation)
956 {
957
958 IndexedMatrix mat =
959 IndexedMatrix.CreateFromQuaternion(new IndexedQuaternion(pRawOrientation.X, pRawOrientation.Y,
960 pRawOrientation.Z, pRawOrientation.W));
961 mat._origin = new IndexedVector3(pRawPosition.X, pRawPosition.Y, pRawPosition.Z);
962
963 CollisionShape shape = (pShape as BulletShapeXNA).shape;
964
965 // TODO: Feed Update array into null
966 RigidBody body = new RigidBody(0, new DefaultMotionState( mat, IndexedMatrix.Identity), shape, IndexedVector3.Zero);
967 body.SetWorldTransform(mat);
968 body.SetUserPointer(pLocalID);
969 return new BulletBodyXNA(pLocalID, body);
970 }
971 //(m_mapInfo.terrainBody.ptr, CollisionFlags.CF_STATIC_OBJECT);
972 public override CollisionFlags SetCollisionFlags(BulletBody pCollisionObject, CollisionFlags collisionFlags)
973 {
974 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
975 collisionObject.SetCollisionFlags((BulletXNA.BulletCollision.CollisionFlags) (uint) collisionFlags);
976 return (CollisionFlags)collisionObject.GetCollisionFlags();
977 }
978
979 public override Vector3 GetAnisotripicFriction(BulletConstraint pconstrain)
980 {
981
982 /* TODO */
983 return Vector3.Zero;
984 }
985 public override Vector3 SetAnisotripicFriction(BulletConstraint pconstrain, Vector3 frict) { /* TODO */ return Vector3.Zero; }
986 public override bool HasAnisotripicFriction(BulletConstraint pconstrain) { /* TODO */ return false; }
987 public override float GetContactProcessingThreshold(BulletBody pBody) { /* TODO */ return 0f; }
988 public override bool IsStaticObject(BulletBody pCollisionObject)
989 {
990 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
991 return collisionObject.IsStaticObject();
992
993 }
994 public override bool IsKinematicObject(BulletBody pCollisionObject)
995 {
996 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
997 return collisionObject.IsKinematicObject();
998 }
999 public override bool IsStaticOrKinematicObject(BulletBody pCollisionObject)
1000 {
1001 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
1002 return collisionObject.IsStaticOrKinematicObject();
1003 }
1004 public override bool HasContactResponse(BulletBody pCollisionObject)
1005 {
1006 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
1007 return collisionObject.HasContactResponse();
1008 }
1009 public override int GetActivationState(BulletBody pBody) { /* TODO */ return 0; }
1010 public override void SetActivationState(BulletBody pBody, int state) { /* TODO */ }
1011 public override float GetDeactivationTime(BulletBody pBody) { /* TODO */ return 0f; }
1012 public override bool IsActive(BulletBody pBody) { /* TODO */ return false; }
1013 public override float GetRestitution(BulletBody pBody) { /* TODO */ return 0f; }
1014 public override float GetFriction(BulletBody pBody) { /* TODO */ return 0f; }
1015 public override void SetInterpolationVelocity(BulletBody pBody, Vector3 linearVel, Vector3 angularVel) { /* TODO */ }
1016 public override float GetHitFraction(BulletBody pBody) { /* TODO */ return 0f; }
1017
1018 //(m_mapInfo.terrainBody.ptr, PhysicsScene.Params.terrainHitFraction);
1019 public override void SetHitFraction(BulletBody pCollisionObject, float pHitFraction)
1020 {
1021 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
1022 collisionObject.SetHitFraction(pHitFraction);
1023 }
1024 //BuildCapsuleShape(physicsScene.World.ptr, 1f, 1f, prim.Scale);
1025 public override BulletShape BuildCapsuleShape(BulletWorld pWorld, float pRadius, float pHeight, Vector3 pScale)
1026 {
1027 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
1028 IndexedVector3 scale = new IndexedVector3(pScale.X, pScale.Y, pScale.Z);
1029 CapsuleShapeZ capsuleShapeZ = new CapsuleShapeZ(pRadius, pHeight);
1030 capsuleShapeZ.SetMargin(world.WorldSettings.Params.collisionMargin);
1031 capsuleShapeZ.SetLocalScaling(ref scale);
1032
1033 return new BulletShapeXNA(capsuleShapeZ, BSPhysicsShapeType.SHAPE_CAPSULE); ;
1034 }
1035
1036 public override BulletWorld Initialize(Vector3 maxPosition, ConfigurationParameters parms,
1037 int maxCollisions, ref CollisionDesc[] collisionArray,
1038 int maxUpdates, ref EntityProperties[] updateArray
1039 )
1040 {
1041
1042 m_updateArray = updateArray;
1043 m_collisionArray = collisionArray;
1044 /* TODO */
1045 ConfigurationParameters[] configparms = new ConfigurationParameters[1];
1046 configparms[0] = parms;
1047 Vector3 worldExtent = new Vector3(Constants.RegionSize, Constants.RegionSize, Constants.RegionHeight);
1048 m_maxCollisions = maxCollisions;
1049 m_maxUpdatesPerFrame = maxUpdates;
1050
1051
1052 return new BulletWorldXNA(1, PhysicsScene, BSAPIXNA.Initialize2(worldExtent, configparms, maxCollisions, ref collisionArray, maxUpdates, ref updateArray, null));
1053 }
1054
1055 private static DiscreteDynamicsWorld Initialize2(Vector3 worldExtent,
1056 ConfigurationParameters[] o,
1057 int mMaxCollisionsPerFrame, ref CollisionDesc[] collisionArray,
1058 int mMaxUpdatesPerFrame, ref EntityProperties[] updateArray,
1059 object mDebugLogCallbackHandle)
1060 {
1061 CollisionWorld.WorldData.ParamData p = new CollisionWorld.WorldData.ParamData();
1062
1063 p.angularDamping = o[0].XangularDamping;
1064 p.defaultFriction = o[0].defaultFriction;
1065 p.defaultFriction = o[0].defaultFriction;
1066 p.defaultDensity = o[0].defaultDensity;
1067 p.defaultRestitution = o[0].defaultRestitution;
1068 p.collisionMargin = o[0].collisionMargin;
1069 p.gravity = o[0].gravity;
1070
1071 p.linearDamping = o[0].XlinearDamping;
1072 p.angularDamping = o[0].XangularDamping;
1073 p.deactivationTime = o[0].XdeactivationTime;
1074 p.linearSleepingThreshold = o[0].XlinearSleepingThreshold;
1075 p.angularSleepingThreshold = o[0].XangularSleepingThreshold;
1076 p.ccdMotionThreshold = o[0].XccdMotionThreshold;
1077 p.ccdSweptSphereRadius = o[0].XccdSweptSphereRadius;
1078 p.contactProcessingThreshold = o[0].XcontactProcessingThreshold;
1079
1080 p.terrainImplementation = o[0].XterrainImplementation;
1081 p.terrainFriction = o[0].XterrainFriction;
1082
1083 p.terrainHitFraction = o[0].XterrainHitFraction;
1084 p.terrainRestitution = o[0].XterrainRestitution;
1085 p.terrainCollisionMargin = o[0].XterrainCollisionMargin;
1086
1087 p.avatarFriction = o[0].XavatarFriction;
1088 p.avatarStandingFriction = o[0].XavatarStandingFriction;
1089 p.avatarDensity = o[0].XavatarDensity;
1090 p.avatarRestitution = o[0].XavatarRestitution;
1091 p.avatarCapsuleWidth = o[0].XavatarCapsuleWidth;
1092 p.avatarCapsuleDepth = o[0].XavatarCapsuleDepth;
1093 p.avatarCapsuleHeight = o[0].XavatarCapsuleHeight;
1094 p.avatarContactProcessingThreshold = o[0].XavatarContactProcessingThreshold;
1095
1096 p.vehicleAngularDamping = o[0].XvehicleAngularDamping;
1097
1098 p.maxPersistantManifoldPoolSize = o[0].maxPersistantManifoldPoolSize;
1099 p.maxCollisionAlgorithmPoolSize = o[0].maxCollisionAlgorithmPoolSize;
1100 p.shouldDisableContactPoolDynamicAllocation = o[0].shouldDisableContactPoolDynamicAllocation;
1101 p.shouldForceUpdateAllAabbs = o[0].shouldForceUpdateAllAabbs;
1102 p.shouldRandomizeSolverOrder = o[0].shouldRandomizeSolverOrder;
1103 p.shouldSplitSimulationIslands = o[0].shouldSplitSimulationIslands;
1104 p.shouldEnableFrictionCaching = o[0].shouldEnableFrictionCaching;
1105 p.numberOfSolverIterations = o[0].numberOfSolverIterations;
1106
1107 p.linksetImplementation = o[0].XlinksetImplementation;
1108 p.linkConstraintUseFrameOffset = o[0].XlinkConstraintUseFrameOffset;
1109 p.linkConstraintEnableTransMotor = o[0].XlinkConstraintEnableTransMotor;
1110 p.linkConstraintTransMotorMaxVel = o[0].XlinkConstraintTransMotorMaxVel;
1111 p.linkConstraintTransMotorMaxForce = o[0].XlinkConstraintTransMotorMaxForce;
1112 p.linkConstraintERP = o[0].XlinkConstraintERP;
1113 p.linkConstraintCFM = o[0].XlinkConstraintCFM;
1114 p.linkConstraintSolverIterations = o[0].XlinkConstraintSolverIterations;
1115 p.physicsLoggingFrames = o[0].XphysicsLoggingFrames;
1116 DefaultCollisionConstructionInfo ccci = new DefaultCollisionConstructionInfo();
1117
1118 DefaultCollisionConfiguration cci = new DefaultCollisionConfiguration();
1119 CollisionDispatcher m_dispatcher = new CollisionDispatcher(cci);
1120
1121
1122 if (p.maxPersistantManifoldPoolSize > 0)
1123 cci.m_persistentManifoldPoolSize = (int)p.maxPersistantManifoldPoolSize;
1124 if (p.shouldDisableContactPoolDynamicAllocation !=0)
1125 m_dispatcher.SetDispatcherFlags(DispatcherFlags.CD_DISABLE_CONTACTPOOL_DYNAMIC_ALLOCATION);
1126 //if (p.maxCollisionAlgorithmPoolSize >0 )
1127
1128 DbvtBroadphase m_broadphase = new DbvtBroadphase();
1129 //IndexedVector3 aabbMin = new IndexedVector3(0, 0, 0);
1130 //IndexedVector3 aabbMax = new IndexedVector3(256, 256, 256);
1131
1132 //AxisSweep3Internal m_broadphase2 = new AxisSweep3Internal(ref aabbMin, ref aabbMax, Convert.ToInt32(0xfffe), 0xffff, ushort.MaxValue/2, null, true);
1133 m_broadphase.GetOverlappingPairCache().SetInternalGhostPairCallback(new GhostPairCallback());
1134
1135 SequentialImpulseConstraintSolver m_solver = new SequentialImpulseConstraintSolver();
1136
1137 DiscreteDynamicsWorld world = new DiscreteDynamicsWorld(m_dispatcher, m_broadphase, m_solver, cci);
1138
1139
1140 world.UpdatedObjects = BSAPIXNA.GetBulletXNAEntityStruct(BSAPIXNA.BulletSimEntityStructToByteArray(updateArray, updateArray.Length));
1141 world.UpdatedCollisions = BSAPIXNA.GetBulletXNACollisionStruct(BSAPIXNA.BulletSimCollisionStructToByteArray(collisionArray, collisionArray.Length));
1142 world.LastCollisionDesc = 0;
1143 world.LastEntityProperty = 0;
1144
1145 world.WorldSettings.Params = p;
1146 world.SetForceUpdateAllAabbs(p.shouldForceUpdateAllAabbs != 0);
1147 world.GetSolverInfo().m_solverMode = SolverMode.SOLVER_USE_WARMSTARTING | SolverMode.SOLVER_SIMD;
1148 if (p.shouldRandomizeSolverOrder != 0)
1149 world.GetSolverInfo().m_solverMode |= SolverMode.SOLVER_RANDMIZE_ORDER;
1150
1151 world.GetSimulationIslandManager().SetSplitIslands(p.shouldSplitSimulationIslands != 0);
1152 //world.GetDispatchInfo().m_enableSatConvex Not implemented in C# port
1153
1154 if (p.shouldEnableFrictionCaching != 0)
1155 world.GetSolverInfo().m_solverMode |= SolverMode.SOLVER_ENABLE_FRICTION_DIRECTION_CACHING;
1156
1157 if (p.numberOfSolverIterations > 0)
1158 world.GetSolverInfo().m_numIterations = (int) p.numberOfSolverIterations;
1159
1160
1161 world.GetSolverInfo().m_damping = world.WorldSettings.Params.linearDamping;
1162 world.GetSolverInfo().m_restitution = world.WorldSettings.Params.defaultRestitution;
1163 world.GetSolverInfo().m_globalCfm = 0.0f;
1164 world.GetSolverInfo().m_tau = 0.6f;
1165 world.GetSolverInfo().m_friction = 0.3f;
1166 world.GetSolverInfo().m_maxErrorReduction = 20f;
1167 world.GetSolverInfo().m_numIterations = 10;
1168 world.GetSolverInfo().m_erp = 0.2f;
1169 world.GetSolverInfo().m_erp2 = 0.1f;
1170 world.GetSolverInfo().m_sor = 1.0f;
1171 world.GetSolverInfo().m_splitImpulse = false;
1172 world.GetSolverInfo().m_splitImpulsePenetrationThreshold = -0.02f;
1173 world.GetSolverInfo().m_linearSlop = 0.0f;
1174 world.GetSolverInfo().m_warmstartingFactor = 0.85f;
1175 world.GetSolverInfo().m_restingContactRestitutionThreshold = 2;
1176 world.SetForceUpdateAllAabbs(true);
1177
1178 //BSParam.TerrainImplementation = 0;
1179 world.SetGravity(new IndexedVector3(0,0,p.gravity));
1180
1181 return world;
1182 }
1183 //m_constraint.ptr, ConstraintParams.BT_CONSTRAINT_STOP_CFM, cfm, ConstraintParamAxis.AXIS_ALL
1184 public override bool SetConstraintParam(BulletConstraint pConstraint, ConstraintParams paramIndex, float paramvalue, ConstraintParamAxis axis)
1185 {
1186 Generic6DofConstraint constrain = (pConstraint as BulletConstraintXNA).constrain as Generic6DofConstraint;
1187 if (axis == ConstraintParamAxis.AXIS_LINEAR_ALL || axis == ConstraintParamAxis.AXIS_ALL)
1188 {
1189 constrain.SetParam((BulletXNA.BulletDynamics.ConstraintParams) (int) paramIndex, paramvalue, 0);
1190 constrain.SetParam((BulletXNA.BulletDynamics.ConstraintParams) (int) paramIndex, paramvalue, 1);
1191 constrain.SetParam((BulletXNA.BulletDynamics.ConstraintParams) (int) paramIndex, paramvalue, 2);
1192 }
1193 if (axis == ConstraintParamAxis.AXIS_ANGULAR_ALL || axis == ConstraintParamAxis.AXIS_ALL)
1194 {
1195 constrain.SetParam((BulletXNA.BulletDynamics.ConstraintParams)(int)paramIndex, paramvalue, 3);
1196 constrain.SetParam((BulletXNA.BulletDynamics.ConstraintParams)(int)paramIndex, paramvalue, 4);
1197 constrain.SetParam((BulletXNA.BulletDynamics.ConstraintParams)(int)paramIndex, paramvalue, 5);
1198 }
1199 if (axis == ConstraintParamAxis.AXIS_LINEAR_ALL)
1200 {
1201 constrain.SetParam((BulletXNA.BulletDynamics.ConstraintParams)(int)paramIndex, paramvalue, (int)axis);
1202 }
1203 return true;
1204 }
1205
1206 public override bool PushUpdate(BulletBody pCollisionObject)
1207 {
1208 bool ret = false;
1209 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
1210 RigidBody rb = collisionObject as RigidBody;
1211 if (rb != null)
1212 {
1213 SimMotionState sms = rb.GetMotionState() as SimMotionState;
1214 if (sms != null)
1215 {
1216 IndexedMatrix wt = IndexedMatrix.Identity;
1217 sms.GetWorldTransform(out wt);
1218 sms.SetWorldTransform(ref wt, true);
1219 ret = true;
1220 }
1221 }
1222 return ret;
1223
1224 }
1225
1226 public override float GetAngularMotionDisc(BulletShape pShape)
1227 {
1228 CollisionShape shape = (pShape as BulletShapeXNA).shape;
1229 return shape.GetAngularMotionDisc();
1230 }
1231 public override float GetContactBreakingThreshold(BulletShape pShape, float defaultFactor)
1232 {
1233 CollisionShape shape = (pShape as BulletShapeXNA).shape;
1234 return shape.GetContactBreakingThreshold(defaultFactor);
1235 }
1236 public override bool IsCompound(BulletShape pShape)
1237 {
1238 CollisionShape shape = (pShape as BulletShapeXNA).shape;
1239 return shape.IsCompound();
1240 }
1241 public override bool IsSoftBody(BulletShape pShape)
1242 {
1243 CollisionShape shape = (pShape as BulletShapeXNA).shape;
1244 return shape.IsSoftBody();
1245 }
1246 public override bool IsPolyhedral(BulletShape pShape)
1247 {
1248 CollisionShape shape = (pShape as BulletShapeXNA).shape;
1249 return shape.IsPolyhedral();
1250 }
1251 public override bool IsConvex2d(BulletShape pShape)
1252 {
1253 CollisionShape shape = (pShape as BulletShapeXNA).shape;
1254 return shape.IsConvex2d();
1255 }
1256 public override bool IsConvex(BulletShape pShape)
1257 {
1258 CollisionShape shape = (pShape as BulletShapeXNA).shape;
1259 return shape.IsConvex();
1260 }
1261 public override bool IsNonMoving(BulletShape pShape)
1262 {
1263 CollisionShape shape = (pShape as BulletShapeXNA).shape;
1264 return shape.IsNonMoving();
1265 }
1266 public override bool IsConcave(BulletShape pShape)
1267 {
1268 CollisionShape shape = (pShape as BulletShapeXNA).shape;
1269 return shape.IsConcave();
1270 }
1271 public override bool IsInfinite(BulletShape pShape)
1272 {
1273 CollisionShape shape = (pShape as BulletShapeXNA).shape;
1274 return shape.IsInfinite();
1275 }
1276 public override bool IsNativeShape(BulletShape pShape)
1277 {
1278 CollisionShape shape = (pShape as BulletShapeXNA).shape;
1279 bool ret;
1280 switch (shape.GetShapeType())
1281 {
1282 case BroadphaseNativeTypes.BOX_SHAPE_PROXYTYPE:
1283 case BroadphaseNativeTypes.CONE_SHAPE_PROXYTYPE:
1284 case BroadphaseNativeTypes.SPHERE_SHAPE_PROXYTYPE:
1285 case BroadphaseNativeTypes.CYLINDER_SHAPE_PROXYTYPE:
1286 ret = true;
1287 break;
1288 default:
1289 ret = false;
1290 break;
1291 }
1292 return ret;
1293 }
1294
1295 public override void SetShapeCollisionMargin(BulletShape pShape, float pMargin)
1296 {
1297 CollisionShape shape = (pShape as BulletShapeXNA).shape;
1298 shape.SetMargin(pMargin);
1299 }
1300
1301 //sim.ptr, shape.ptr,prim.LocalID, prim.RawPosition, prim.RawOrientation
1302 public override BulletBody CreateGhostFromShape(BulletWorld pWorld, BulletShape pShape, uint pLocalID, Vector3 pRawPosition, Quaternion pRawOrientation)
1303 {
1304 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
1305 IndexedMatrix bodyTransform = new IndexedMatrix();
1306 bodyTransform._origin = new IndexedVector3(pRawPosition.X, pRawPosition.Y, pRawPosition.Z);
1307 bodyTransform.SetRotation(new IndexedQuaternion(pRawOrientation.X,pRawOrientation.Y,pRawOrientation.Z,pRawOrientation.W));
1308 GhostObject gObj = new PairCachingGhostObject();
1309 gObj.SetWorldTransform(bodyTransform);
1310 CollisionShape shape = (pShape as BulletShapeXNA).shape;
1311 gObj.SetCollisionShape(shape);
1312 gObj.SetUserPointer(pLocalID);
1313 // TODO: Add to Special CollisionObjects!
1314 return new BulletBodyXNA(pLocalID, gObj);
1315 }
1316
1317 public override void SetCollisionShape(BulletWorld pWorld, BulletBody pCollisionObject, BulletShape pShape)
1318 {
1319 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
1320 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).body;
1321 if (pShape == null)
1322 {
1323 collisionObject.SetCollisionShape(new EmptyShape());
1324 }
1325 else
1326 {
1327 CollisionShape shape = (pShape as BulletShapeXNA).shape;
1328 collisionObject.SetCollisionShape(shape);
1329 }
1330 }
1331 public override BulletShape GetCollisionShape(BulletBody pCollisionObject)
1332 {
1333 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
1334 CollisionShape shape = collisionObject.GetCollisionShape();
1335 return new BulletShapeXNA(shape,BSPhysicsShapeType.SHAPE_UNKNOWN);
1336 }
1337
1338 //(PhysicsScene.World.ptr, nativeShapeData)
1339 public override BulletShape BuildNativeShape(BulletWorld pWorld, ShapeData pShapeData)
1340 {
1341 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
1342 CollisionShape shape = null;
1343 switch (pShapeData.Type)
1344 {
1345 case BSPhysicsShapeType.SHAPE_BOX:
1346 shape = new BoxShape(new IndexedVector3(0.5f,0.5f,0.5f));
1347 break;
1348 case BSPhysicsShapeType.SHAPE_CONE:
1349 shape = new ConeShapeZ(0.5f, 1.0f);
1350 break;
1351 case BSPhysicsShapeType.SHAPE_CYLINDER:
1352 shape = new CylinderShapeZ(new IndexedVector3(0.5f, 0.5f, 0.5f));
1353 break;
1354 case BSPhysicsShapeType.SHAPE_SPHERE:
1355 shape = new SphereShape(0.5f);
1356 break;
1357
1358 }
1359 if (shape != null)
1360 {
1361 IndexedVector3 scaling = new IndexedVector3(pShapeData.Scale.X, pShapeData.Scale.Y, pShapeData.Scale.Z);
1362 shape.SetMargin(world.WorldSettings.Params.collisionMargin);
1363 shape.SetLocalScaling(ref scaling);
1364
1365 }
1366 return new BulletShapeXNA(shape, pShapeData.Type);
1367 }
1368 //PhysicsScene.World.ptr, false
1369 public override BulletShape CreateCompoundShape(BulletWorld pWorld, bool enableDynamicAabbTree)
1370 {
1371 return new BulletShapeXNA(new CompoundShape(enableDynamicAabbTree), BSPhysicsShapeType.SHAPE_COMPOUND);
1372 }
1373
1374 public override int GetNumberOfCompoundChildren(BulletShape pCompoundShape)
1375 {
1376 CompoundShape compoundshape = (pCompoundShape as BulletShapeXNA).shape as CompoundShape;
1377 return compoundshape.GetNumChildShapes();
1378 }
1379 //LinksetRoot.PhysShape.ptr, newShape.ptr, displacementPos, displacementRot
1380 public override void AddChildShapeToCompoundShape(BulletShape pCShape, BulletShape paddShape, Vector3 displacementPos, Quaternion displacementRot)
1381 {
1382 IndexedMatrix relativeTransform = new IndexedMatrix();
1383 CompoundShape compoundshape = (pCShape as BulletShapeXNA).shape as CompoundShape;
1384 CollisionShape addshape = (paddShape as BulletShapeXNA).shape;
1385
1386 relativeTransform._origin = new IndexedVector3(displacementPos.X, displacementPos.Y, displacementPos.Z);
1387 relativeTransform.SetRotation(new IndexedQuaternion(displacementRot.X,displacementRot.Y,displacementRot.Z,displacementRot.W));
1388 compoundshape.AddChildShape(ref relativeTransform, addshape);
1389
1390 }
1391
1392 public override BulletShape RemoveChildShapeFromCompoundShapeIndex(BulletShape pCShape, int pii)
1393 {
1394 CompoundShape compoundshape = (pCShape as BulletShapeXNA).shape as CompoundShape;
1395 CollisionShape ret = null;
1396 ret = compoundshape.GetChildShape(pii);
1397 compoundshape.RemoveChildShapeByIndex(pii);
1398 return new BulletShapeXNA(ret, BSPhysicsShapeType.SHAPE_UNKNOWN);
1399 }
1400
1401 public override BulletShape GetChildShapeFromCompoundShapeIndex(BulletShape cShape, int indx) { /* TODO */ return null; }
1402 public override void RemoveChildShapeFromCompoundShape(BulletShape cShape, BulletShape removeShape) { /* TODO */ }
1403 public override void UpdateChildTransform(BulletShape pShape, int childIndex, Vector3 pos, Quaternion rot, bool shouldRecalculateLocalAabb) { /* TODO */ }
1404
1405 public override BulletShape CreateGroundPlaneShape(uint pLocalId, float pheight, float pcollisionMargin)
1406 {
1407 StaticPlaneShape m_planeshape = new StaticPlaneShape(new IndexedVector3(0,0,1),(int)pheight );
1408 m_planeshape.SetMargin(pcollisionMargin);
1409 m_planeshape.SetUserPointer(pLocalId);
1410 return new BulletShapeXNA(m_planeshape, BSPhysicsShapeType.SHAPE_GROUNDPLANE);
1411 }
1412
1413 public override BulletConstraint CreateHingeConstraint(BulletWorld pWorld, BulletBody pBody1, BulletBody pBody2, Vector3 ppivotInA, Vector3 ppivotInB, Vector3 paxisInA, Vector3 paxisInB, bool puseLinearReferenceFrameA, bool pdisableCollisionsBetweenLinkedBodies)
1414 {
1415 HingeConstraint constrain = null;
1416 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
1417 RigidBody rb1 = (pBody1 as BulletBodyXNA).rigidBody;
1418 RigidBody rb2 = (pBody2 as BulletBodyXNA).rigidBody;
1419 if (rb1 != null && rb2 != null)
1420 {
1421 IndexedVector3 pivotInA = new IndexedVector3(ppivotInA.X, ppivotInA.Y, ppivotInA.Z);
1422 IndexedVector3 pivotInB = new IndexedVector3(ppivotInB.X, ppivotInB.Y, ppivotInB.Z);
1423 IndexedVector3 axisInA = new IndexedVector3(paxisInA.X, paxisInA.Y, paxisInA.Z);
1424 IndexedVector3 axisInB = new IndexedVector3(paxisInB.X, paxisInB.Y, paxisInB.Z);
1425 world.AddConstraint(constrain, pdisableCollisionsBetweenLinkedBodies);
1426 }
1427 return new BulletConstraintXNA(constrain);
1428 }
1429
1430 public override BulletShape CreateHullShape(BulletWorld pWorld, int pHullCount, float[] pConvHulls)
1431 {
1432 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
1433 CompoundShape compoundshape = new CompoundShape(false);
1434
1435 compoundshape.SetMargin(world.WorldSettings.Params.collisionMargin);
1436 int ii = 1;
1437
1438 for (int i = 0; i < pHullCount; i++)
1439 {
1440 int vertexCount = (int) pConvHulls[ii];
1441
1442 IndexedVector3 centroid = new IndexedVector3(pConvHulls[ii + 1], pConvHulls[ii + 2], pConvHulls[ii + 3]);
1443 IndexedMatrix childTrans = IndexedMatrix.Identity;
1444 childTrans._origin = centroid;
1445
1446 List<IndexedVector3> virts = new List<IndexedVector3>();
1447 int ender = ((ii + 4) + (vertexCount*3));
1448 for (int iii = ii + 4; iii < ender; iii+=3)
1449 {
1450
1451 virts.Add(new IndexedVector3(pConvHulls[iii], pConvHulls[iii + 1], pConvHulls[iii +2]));
1452 }
1453 ConvexHullShape convexShape = new ConvexHullShape(virts, vertexCount);
1454 convexShape.SetMargin(world.WorldSettings.Params.collisionMargin);
1455 compoundshape.AddChildShape(ref childTrans, convexShape);
1456 ii += (vertexCount*3 + 4);
1457 }
1458
1459 return new BulletShapeXNA(compoundshape, BSPhysicsShapeType.SHAPE_HULL);
1460 }
1461
1462 public override BulletShape BuildHullShapeFromMesh(BulletWorld world, BulletShape meshShape)
1463 {
1464 /* TODO */ return null;
1465
1466 }
1467
1468 public override BulletShape CreateMeshShape(BulletWorld pWorld, int pIndicesCount, int[] indices, int pVerticesCount, float[] verticesAsFloats)
1469 {
1470 //DumpRaw(indices,verticesAsFloats,pIndicesCount,pVerticesCount);
1471
1472 for (int iter = 0; iter < pVerticesCount; iter++)
1473 {
1474 if (verticesAsFloats[iter] > 0 && verticesAsFloats[iter] < 0.0001) verticesAsFloats[iter] = 0;
1475 if (verticesAsFloats[iter] < 0 && verticesAsFloats[iter] > -0.0001) verticesAsFloats[iter] = 0;
1476 }
1477
1478 ObjectArray<int> indicesarr = new ObjectArray<int>(indices);
1479 ObjectArray<float> vertices = new ObjectArray<float>(verticesAsFloats);
1480 DumpRaw(indicesarr,vertices,pIndicesCount,pVerticesCount);
1481 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
1482 IndexedMesh mesh = new IndexedMesh();
1483 mesh.m_indexType = PHY_ScalarType.PHY_INTEGER;
1484 mesh.m_numTriangles = pIndicesCount/3;
1485 mesh.m_numVertices = pVerticesCount;
1486 mesh.m_triangleIndexBase = indicesarr;
1487 mesh.m_vertexBase = vertices;
1488 mesh.m_vertexStride = 3;
1489 mesh.m_vertexType = PHY_ScalarType.PHY_FLOAT;
1490 mesh.m_triangleIndexStride = 3;
1491
1492 TriangleIndexVertexArray tribuilder = new TriangleIndexVertexArray();
1493 tribuilder.AddIndexedMesh(mesh, PHY_ScalarType.PHY_INTEGER);
1494 BvhTriangleMeshShape meshShape = new BvhTriangleMeshShape(tribuilder, true,true);
1495 meshShape.SetMargin(world.WorldSettings.Params.collisionMargin);
1496 // world.UpdateSingleAabb(meshShape);
1497 return new BulletShapeXNA(meshShape, BSPhysicsShapeType.SHAPE_MESH);
1498
1499 }
1500 public static void DumpRaw(ObjectArray<int>indices, ObjectArray<float> vertices, int pIndicesCount,int pVerticesCount )
1501 {
1502
1503 String fileName = "objTest3.raw";
1504 String completePath = System.IO.Path.Combine(Util.configDir(), fileName);
1505 StreamWriter sw = new StreamWriter(completePath);
1506 IndexedMesh mesh = new IndexedMesh();
1507
1508 mesh.m_indexType = PHY_ScalarType.PHY_INTEGER;
1509 mesh.m_numTriangles = pIndicesCount / 3;
1510 mesh.m_numVertices = pVerticesCount;
1511 mesh.m_triangleIndexBase = indices;
1512 mesh.m_vertexBase = vertices;
1513 mesh.m_vertexStride = 3;
1514 mesh.m_vertexType = PHY_ScalarType.PHY_FLOAT;
1515 mesh.m_triangleIndexStride = 3;
1516
1517 TriangleIndexVertexArray tribuilder = new TriangleIndexVertexArray();
1518 tribuilder.AddIndexedMesh(mesh, PHY_ScalarType.PHY_INTEGER);
1519
1520
1521
1522 for (int i = 0; i < pVerticesCount; i++)
1523 {
1524
1525 string s = vertices[indices[i * 3]].ToString("0.0000");
1526 s += " " + vertices[indices[i * 3 + 1]].ToString("0.0000");
1527 s += " " + vertices[indices[i * 3 + 2]].ToString("0.0000");
1528
1529 sw.Write(s + "\n");
1530 }
1531
1532 sw.Close();
1533 }
1534 public static void DumpRaw(int[] indices, float[] vertices, int pIndicesCount, int pVerticesCount)
1535 {
1536
1537 String fileName = "objTest6.raw";
1538 String completePath = System.IO.Path.Combine(Util.configDir(), fileName);
1539 StreamWriter sw = new StreamWriter(completePath);
1540 IndexedMesh mesh = new IndexedMesh();
1541
1542 mesh.m_indexType = PHY_ScalarType.PHY_INTEGER;
1543 mesh.m_numTriangles = pIndicesCount / 3;
1544 mesh.m_numVertices = pVerticesCount;
1545 mesh.m_triangleIndexBase = indices;
1546 mesh.m_vertexBase = vertices;
1547 mesh.m_vertexStride = 3;
1548 mesh.m_vertexType = PHY_ScalarType.PHY_FLOAT;
1549 mesh.m_triangleIndexStride = 3;
1550
1551 TriangleIndexVertexArray tribuilder = new TriangleIndexVertexArray();
1552 tribuilder.AddIndexedMesh(mesh, PHY_ScalarType.PHY_INTEGER);
1553
1554
1555 sw.WriteLine("Indices");
1556 sw.WriteLine(string.Format("int[] indices = new int[{0}];",pIndicesCount));
1557 for (int iter = 0; iter < indices.Length; iter++)
1558 {
1559 sw.WriteLine(string.Format("indices[{0}]={1};",iter,indices[iter]));
1560 }
1561 sw.WriteLine("VerticesFloats");
1562 sw.WriteLine(string.Format("float[] vertices = new float[{0}];", pVerticesCount));
1563 for (int iter = 0; iter < vertices.Length; iter++)
1564 {
1565 sw.WriteLine(string.Format("Vertices[{0}]={1};", iter, vertices[iter].ToString("0.0000")));
1566 }
1567
1568 // for (int i = 0; i < pVerticesCount; i++)
1569 // {
1570 //
1571 // string s = vertices[indices[i * 3]].ToString("0.0000");
1572 // s += " " + vertices[indices[i * 3 + 1]].ToString("0.0000");
1573 // s += " " + vertices[indices[i * 3 + 2]].ToString("0.0000");
1574 //
1575 // sw.Write(s + "\n");
1576 //}
1577
1578 sw.Close();
1579 }
1580
1581 public override BulletShape CreateTerrainShape(uint id, Vector3 size, float minHeight, float maxHeight, float[] heightMap,
1582 float scaleFactor, float collisionMargin)
1583 {
1584 const int upAxis = 2;
1585 HeightfieldTerrainShape terrainShape = new HeightfieldTerrainShape((int)size.X, (int)size.Y,
1586 heightMap, scaleFactor,
1587 minHeight, maxHeight, upAxis,
1588 false);
1589 terrainShape.SetMargin(collisionMargin + 0.5f);
1590 terrainShape.SetUseDiamondSubdivision(true);
1591 terrainShape.SetUserPointer(id);
1592 return new BulletShapeXNA(terrainShape, BSPhysicsShapeType.SHAPE_TERRAIN);
1593 }
1594
1595 public override bool TranslationalLimitMotor(BulletConstraint pConstraint, float ponOff, float targetVelocity, float maxMotorForce)
1596 {
1597 TypedConstraint tconstrain = (pConstraint as BulletConstraintXNA).constrain;
1598 bool onOff = ponOff != 0;
1599 bool ret = false;
1600
1601 switch (tconstrain.GetConstraintType())
1602 {
1603 case TypedConstraintType.D6_CONSTRAINT_TYPE:
1604 Generic6DofConstraint constrain = tconstrain as Generic6DofConstraint;
1605 constrain.GetTranslationalLimitMotor().m_enableMotor[0] = onOff;
1606 constrain.GetTranslationalLimitMotor().m_targetVelocity[0] = targetVelocity;
1607 constrain.GetTranslationalLimitMotor().m_maxMotorForce[0] = maxMotorForce;
1608 ret = true;
1609 break;
1610 }
1611
1612
1613 return ret;
1614
1615 }
1616
1617 public override int PhysicsStep(BulletWorld world, float timeStep, int maxSubSteps, float fixedTimeStep,
1618 out int updatedEntityCount, out int collidersCount)
1619 {
1620 /* TODO */
1621 updatedEntityCount = 0;
1622 collidersCount = 0;
1623
1624
1625 int ret = PhysicsStep2(world,timeStep,maxSubSteps,fixedTimeStep,out updatedEntityCount,out world.physicsScene.m_updateArray, out collidersCount, out world.physicsScene.m_collisionArray);
1626
1627 return ret;
1628 }
1629
1630 private int PhysicsStep2(BulletWorld pWorld, float timeStep, int m_maxSubSteps, float m_fixedTimeStep,
1631 out int updatedEntityCount, out EntityProperties[] updatedEntities,
1632 out int collidersCount, out CollisionDesc[] colliders)
1633 {
1634 int epic = PhysicsStepint(pWorld, timeStep, m_maxSubSteps, m_fixedTimeStep, out updatedEntityCount, out updatedEntities,
1635 out collidersCount, out colliders, m_maxCollisions, m_maxUpdatesPerFrame);
1636 return epic;
1637 }
1638
1639 private static int PhysicsStepint(BulletWorld pWorld,float timeStep, int m_maxSubSteps, float m_fixedTimeStep, out int updatedEntityCount,
1640 out EntityProperties[] updatedEntities, out int collidersCount, out CollisionDesc[] colliders, int maxCollisions, int maxUpdates)
1641 {
1642 int numSimSteps = 0;
1643
1644 updatedEntityCount = 0;
1645 collidersCount = 0;
1646
1647
1648 if (pWorld is BulletWorldXNA)
1649 {
1650 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
1651
1652 world.LastCollisionDesc = 0;
1653 world.LastEntityProperty = 0;
1654 world.UpdatedObjects = new BulletXNA.EntityProperties[maxUpdates];
1655 world.UpdatedCollisions = new BulletXNA.CollisionDesc[maxCollisions];
1656 numSimSteps = world.StepSimulation(timeStep, m_maxSubSteps, m_fixedTimeStep);
1657 int updates = 0;
1658
1659
1660
1661
1662 m_collisionsThisFrame = 0;
1663 int numManifolds = world.GetDispatcher().GetNumManifolds();
1664 for (int j = 0; j < numManifolds; j++)
1665 {
1666 PersistentManifold contactManifold = world.GetDispatcher().GetManifoldByIndexInternal(j);
1667 int numContacts = contactManifold.GetNumContacts();
1668 if (numContacts == 0)
1669 continue;
1670
1671 CollisionObject objA = contactManifold.GetBody0() as CollisionObject;
1672 CollisionObject objB = contactManifold.GetBody1() as CollisionObject;
1673
1674 ManifoldPoint manifoldPoint = contactManifold.GetContactPoint(0);
1675 IndexedVector3 contactPoint = manifoldPoint.GetPositionWorldOnB();
1676 IndexedVector3 contactNormal = -manifoldPoint.m_normalWorldOnB; // make relative to A
1677
1678 RecordCollision(world, objA, objB, contactPoint, contactNormal);
1679 m_collisionsThisFrame ++;
1680 if (m_collisionsThisFrame >= 9999999)
1681 break;
1682
1683
1684 }
1685
1686 updatedEntityCount = world.LastEntityProperty;
1687 updatedEntities = GetBulletSimEntityStruct(BulletXNAEntityStructToByteArray(world.UpdatedObjects, world.LastEntityProperty));
1688
1689
1690
1691
1692 collidersCount = world.LastCollisionDesc;
1693 colliders =
1694 GetBulletSimCollisionStruct(BulletXNACollisionStructToByteArray(world.UpdatedCollisions, world.LastCollisionDesc));//new List<BulletXNA.CollisionDesc>(world.UpdatedCollisions);
1695
1696 }
1697 else
1698 {
1699 //if (updatedEntities is null)
1700 //updatedEntities = new List<BulletXNA.EntityProperties>();
1701 //updatedEntityCount = 0;
1702 //if (colliders is null)
1703 //colliders = new List<BulletXNA.CollisionDesc>();
1704 //collidersCount = 0;
1705
1706 updatedEntities = new EntityProperties[0];
1707
1708
1709 colliders = new CollisionDesc[0];
1710
1711 }
1712 return numSimSteps;
1713 }
1714
1715 private static void RecordCollision(CollisionWorld world, CollisionObject objA, CollisionObject objB, IndexedVector3 contact, IndexedVector3 norm)
1716 {
1717
1718 IndexedVector3 contactNormal = norm;
1719 if ((objA.GetCollisionFlags() & BulletXNA.BulletCollision.CollisionFlags.BS_WANTS_COLLISIONS) == 0 &&
1720 (objB.GetCollisionFlags() & BulletXNA.BulletCollision.CollisionFlags.BS_WANTS_COLLISIONS) == 0)
1721 {
1722 return;
1723 }
1724 uint idA = (uint)objA.GetUserPointer();
1725 uint idB = (uint)objB.GetUserPointer();
1726 if (idA > idB)
1727 {
1728 uint temp = idA;
1729 idA = idB;
1730 idB = temp;
1731 contactNormal = -contactNormal;
1732 }
1733
1734 ulong collisionID = ((ulong) idA << 32) | idB;
1735
1736 BulletXNA.CollisionDesc cDesc = new BulletXNA.CollisionDesc()
1737 {
1738 aID = idA,
1739 bID = idB,
1740 point = contact,
1741 normal = contactNormal
1742 };
1743 if (world.LastCollisionDesc < world.UpdatedCollisions.Length)
1744 world.UpdatedCollisions[world.LastCollisionDesc++] = (cDesc);
1745 m_collisionsThisFrame++;
1746
1747
1748 }
1749 private static EntityProperties GetDebugProperties(BulletWorld pWorld, BulletBody pCollisionObject)
1750 {
1751 EntityProperties ent = new EntityProperties();
1752 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
1753 CollisionObject collisionObject = (pCollisionObject as BulletBodyXNA).rigidBody;
1754 IndexedMatrix transform = collisionObject.GetWorldTransform();
1755 IndexedVector3 LinearVelocity = collisionObject.GetInterpolationLinearVelocity();
1756 IndexedVector3 AngularVelocity = collisionObject.GetInterpolationAngularVelocity();
1757 IndexedQuaternion rotation = transform.GetRotation();
1758 ent.Acceleration = Vector3.Zero;
1759 ent.ID = (uint)collisionObject.GetUserPointer();
1760 ent.Position = new Vector3(transform._origin.X,transform._origin.Y,transform._origin.Z);
1761 ent.Rotation = new Quaternion(rotation.X,rotation.Y,rotation.Z,rotation.W);
1762 ent.Velocity = new Vector3(LinearVelocity.X, LinearVelocity.Y, LinearVelocity.Z);
1763 ent.RotationalVelocity = new Vector3(AngularVelocity.X, AngularVelocity.Y, AngularVelocity.Z);
1764 return ent;
1765 }
1766
1767 public override bool UpdateParameter(BulletWorld world, uint localID, String parm, float value) { /* TODO */ return false; }
1768
1769 public override Vector3 GetLocalScaling(BulletShape pShape)
1770 {
1771 CollisionShape shape = (pShape as BulletShapeXNA).shape;
1772 IndexedVector3 scale = shape.GetLocalScaling();
1773 return new Vector3(scale.X,scale.Y,scale.Z);
1774 }
1775
1776 public bool RayCastGround(BulletWorld pWorld, Vector3 _RayOrigin, float pRayHeight, BulletBody NotMe)
1777 {
1778 DiscreteDynamicsWorld world = (pWorld as BulletWorldXNA).world;
1779 if (world != null)
1780 {
1781 if (NotMe is BulletBodyXNA && NotMe.HasPhysicalBody)
1782 {
1783 CollisionObject AvoidBody = (NotMe as BulletBodyXNA).body;
1784
1785 IndexedVector3 rOrigin = new IndexedVector3(_RayOrigin.X, _RayOrigin.Y, _RayOrigin.Z);
1786 IndexedVector3 rEnd = new IndexedVector3(_RayOrigin.X, _RayOrigin.Y, _RayOrigin.Z - pRayHeight);
1787 using (
1788 ClosestNotMeRayResultCallback rayCallback =
1789 new ClosestNotMeRayResultCallback(rOrigin, rEnd, AvoidBody)
1790 )
1791 {
1792 world.RayTest(ref rOrigin, ref rEnd, rayCallback);
1793 if (rayCallback.HasHit())
1794 {
1795 IndexedVector3 hitLocation = rayCallback.m_hitPointWorld;
1796 }
1797 return rayCallback.HasHit();
1798 }
1799 }
1800 }
1801 return false;
1802 }
1803
1804 public static unsafe BulletXNA.CollisionDesc[] GetBulletXNACollisionStruct(byte[] buffer)
1805 {
1806 int count = buffer.Length/sizeof (BulletXNA.CollisionDesc);
1807 BulletXNA.CollisionDesc[] result = new BulletXNA.CollisionDesc[count];
1808 BulletXNA.CollisionDesc* ptr;
1809 fixed (byte* localBytes = new byte[buffer.Length])
1810 {
1811 for (int i = 0; i < buffer.Length; i++)
1812 {
1813 localBytes[i] = buffer[i];
1814 }
1815 for (int i=0;i<count;i++)
1816 {
1817 ptr = (BulletXNA.CollisionDesc*) (localBytes + sizeof (BulletXNA.CollisionDesc)*i);
1818 result[i] = new BulletXNA.CollisionDesc();
1819 result[i] = *ptr;
1820 }
1821 }
1822 return result;
1823 }
1824
1825 public static unsafe CollisionDesc[] GetBulletSimCollisionStruct(byte[] buffer)
1826 {
1827 int count = buffer.Length / sizeof(CollisionDesc);
1828 CollisionDesc[] result = new CollisionDesc[count];
1829 CollisionDesc* ptr;
1830 fixed (byte* localBytes = new byte[buffer.Length])
1831 {
1832 for (int i = 0; i < buffer.Length; i++)
1833 {
1834 localBytes[i] = buffer[i];
1835 }
1836 for (int i = 0; i < count; i++)
1837 {
1838 ptr = (CollisionDesc*)(localBytes + sizeof(CollisionDesc) * i);
1839 result[i] = new CollisionDesc();
1840 result[i] = *ptr;
1841 }
1842 }
1843 return result;
1844 }
1845 public static unsafe byte[] BulletSimCollisionStructToByteArray(CollisionDesc[] CollisionDescArray, int count)
1846 {
1847 int arrayLength = CollisionDescArray.Length > count ? count : CollisionDescArray.Length;
1848 byte[] byteArray = new byte[sizeof(CollisionDesc) * arrayLength];
1849 fixed (CollisionDesc* floatPointer = CollisionDescArray)
1850 {
1851 fixed (byte* bytePointer = byteArray)
1852 {
1853 CollisionDesc* read = floatPointer;
1854 CollisionDesc* write = (CollisionDesc*)bytePointer;
1855 for (int i = 0; i < arrayLength; i++)
1856 {
1857 *write++ = *read++;
1858 }
1859 }
1860 }
1861 return byteArray;
1862 }
1863 public static unsafe byte[] BulletXNACollisionStructToByteArray(BulletXNA.CollisionDesc[] CollisionDescArray, int count)
1864 {
1865 int arrayLength = CollisionDescArray.Length > count ? count : CollisionDescArray.Length;
1866 byte[] byteArray = new byte[sizeof(BulletXNA.CollisionDesc) * arrayLength];
1867 fixed (BulletXNA.CollisionDesc* floatPointer = CollisionDescArray)
1868 {
1869 fixed (byte* bytePointer = byteArray)
1870 {
1871 BulletXNA.CollisionDesc* read = floatPointer;
1872 BulletXNA.CollisionDesc* write = (BulletXNA.CollisionDesc*)bytePointer;
1873 for (int i = 0; i < arrayLength; i++)
1874 {
1875 *write++ = *read++;
1876 }
1877 }
1878 }
1879 return byteArray;
1880 }
1881 public static unsafe BulletXNA.EntityProperties[] GetBulletXNAEntityStruct(byte[] buffer)
1882 {
1883 int count = buffer.Length / sizeof(BulletXNA.EntityProperties);
1884 BulletXNA.EntityProperties[] result = new BulletXNA.EntityProperties[count];
1885 BulletXNA.EntityProperties* ptr;
1886 fixed (byte* localBytes = new byte[buffer.Length])
1887 {
1888 for (int i = 0; i < buffer.Length; i++)
1889 {
1890 localBytes[i] = buffer[i];
1891 }
1892 for (int i = 0; i < count; i++)
1893 {
1894 ptr = (BulletXNA.EntityProperties*)(localBytes + sizeof(BulletXNA.EntityProperties) * i);
1895 result[i] = new BulletXNA.EntityProperties();
1896 result[i] = *ptr;
1897 }
1898 }
1899 return result;
1900 }
1901
1902 public static unsafe EntityProperties[] GetBulletSimEntityStruct(byte[] buffer)
1903 {
1904 int count = buffer.Length / sizeof(EntityProperties);
1905 EntityProperties[] result = new EntityProperties[count];
1906 EntityProperties* ptr;
1907 fixed (byte* localBytes = new byte[buffer.Length])
1908 {
1909 for (int i = 0; i < buffer.Length; i++)
1910 {
1911 localBytes[i] = buffer[i];
1912 }
1913 for (int i = 0; i < count; i++)
1914 {
1915 ptr = (EntityProperties*)(localBytes + sizeof(EntityProperties) * i);
1916 result[i] = new EntityProperties();
1917 result[i] = *ptr;
1918 }
1919 }
1920 return result;
1921 }
1922 public static unsafe byte[] BulletSimEntityStructToByteArray(EntityProperties[] CollisionDescArray, int count)
1923 {
1924 int arrayLength = CollisionDescArray.Length > count ? count : CollisionDescArray.Length;
1925 byte[] byteArray = new byte[sizeof(EntityProperties) * arrayLength];
1926 fixed (EntityProperties* floatPointer = CollisionDescArray)
1927 {
1928 fixed (byte* bytePointer = byteArray)
1929 {
1930 EntityProperties* read = floatPointer;
1931 EntityProperties* write = (EntityProperties*)bytePointer;
1932 for (int i = 0; i < arrayLength; i++)
1933 {
1934 *write++ = *read++;
1935 }
1936 }
1937 }
1938 return byteArray;
1939 }
1940 public static unsafe byte[] BulletXNAEntityStructToByteArray(BulletXNA.EntityProperties[] CollisionDescArray, int count)
1941 {
1942 int arrayLength = CollisionDescArray.Length > count ? count : CollisionDescArray.Length;
1943 byte[] byteArray = new byte[sizeof(BulletXNA.EntityProperties) * arrayLength];
1944 fixed (BulletXNA.EntityProperties* floatPointer = CollisionDescArray)
1945 {
1946 fixed (byte* bytePointer = byteArray)
1947 {
1948 BulletXNA.EntityProperties* read = floatPointer;
1949 BulletXNA.EntityProperties* write = (BulletXNA.EntityProperties*)bytePointer;
1950 for (int i = 0; i < arrayLength; i++)
1951 {
1952 *write++ = *read++;
1953 }
1954 }
1955 }
1956 return byteArray;
1957 }
1958}
1959}