vh: update BulletSim (OpenSim/Region/Physics/BulletSPlugin

and DLL/SO) to ac6dcd35fb
(Mon May 6 21:10:02 2013 -0400) on top of 0.7.5-postfixes.
0.7.5-pf-bulletsim
Robert Adams 2013-05-08 06:02:12 -07:00
parent aeb5ccaa0a
commit eb0687f5af
41 changed files with 7244 additions and 3334 deletions

View File

@ -75,11 +75,11 @@ private sealed class BulletBodyUnman : BulletBody
private sealed class BulletShapeUnman : BulletShape
{
public IntPtr ptr;
public BulletShapeUnman(IntPtr xx, BSPhysicsShapeType typ)
public BulletShapeUnman(IntPtr xx, BSPhysicsShapeType typ)
: base()
{
ptr = xx;
type = typ;
shapeType = typ;
}
public override bool HasPhysicalShape
{
@ -91,7 +91,7 @@ private sealed class BulletShapeUnman : BulletShape
}
public override BulletShape Clone()
{
return new BulletShapeUnman(ptr, type);
return new BulletShapeUnman(ptr, shapeType);
}
public override bool ReferenceSame(BulletShape other)
{
@ -166,7 +166,7 @@ public override BulletWorld Initialize(Vector3 maxPosition, ConfigurationParamet
// If Debug logging level, enable logging from the unmanaged code
m_DebugLogCallbackHandle = null;
if (BSScene.m_log.IsDebugEnabled || PhysicsScene.PhysicsLogging.Enabled)
if (BSScene.m_log.IsDebugEnabled && PhysicsScene.PhysicsLogging.Enabled)
{
BSScene.m_log.DebugFormat("{0}: Initialize: Setting debug callback for unmanaged code", BSScene.LogHeader);
if (PhysicsScene.PhysicsLogging.Enabled)
@ -202,7 +202,7 @@ private void BulletLoggerPhysLog(string msg)
}
public override int PhysicsStep(BulletWorld world, float timeStep, int maxSubSteps, float fixedTimeStep,
out int updatedEntityCount, out int collidersCount)
out int updatedEntityCount, out int collidersCount)
{
BulletWorldUnman worldu = world as BulletWorldUnman;
return BSAPICPP.PhysicsStep2(worldu.ptr, timeStep, maxSubSteps, fixedTimeStep, out updatedEntityCount, out collidersCount);
@ -212,6 +212,19 @@ public override void Shutdown(BulletWorld world)
{
BulletWorldUnman worldu = world as BulletWorldUnman;
BSAPICPP.Shutdown2(worldu.ptr);
if (m_paramsHandle.IsAllocated)
{
m_paramsHandle.Free();
}
if (m_collisionArrayPinnedHandle.IsAllocated)
{
m_collisionArrayPinnedHandle.Free();
}
if (m_updateArrayPinnedHandle.IsAllocated)
{
m_updateArrayPinnedHandle.Free();
}
}
public override bool PushUpdate(BulletBody obj)
@ -242,19 +255,38 @@ public override BulletShape CreateHullShape(BulletWorld world, int hullCount, fl
{
BulletWorldUnman worldu = world as BulletWorldUnman;
return new BulletShapeUnman(
BSAPICPP.CreateHullShape2(worldu.ptr, hullCount, hulls),
BSAPICPP.CreateHullShape2(worldu.ptr, hullCount, hulls),
BSPhysicsShapeType.SHAPE_HULL);
}
public override BulletShape BuildHullShapeFromMesh(BulletWorld world, BulletShape meshShape)
public override BulletShape BuildHullShapeFromMesh(BulletWorld world, BulletShape meshShape, HACDParams parms)
{
BulletWorldUnman worldu = world as BulletWorldUnman;
BulletShapeUnman shapeu = meshShape as BulletShapeUnman;
return new BulletShapeUnman(
BSAPICPP.BuildHullShapeFromMesh2(worldu.ptr, shapeu.ptr),
BSAPICPP.BuildHullShapeFromMesh2(worldu.ptr, shapeu.ptr, parms),
BSPhysicsShapeType.SHAPE_HULL);
}
public override BulletShape BuildConvexHullShapeFromMesh(BulletWorld world, BulletShape meshShape)
{
BulletWorldUnman worldu = world as BulletWorldUnman;
BulletShapeUnman shapeu = meshShape as BulletShapeUnman;
return new BulletShapeUnman(
BSAPICPP.BuildConvexHullShapeFromMesh2(worldu.ptr, shapeu.ptr),
BSPhysicsShapeType.SHAPE_CONVEXHULL);
}
public override BulletShape CreateConvexHullShape(BulletWorld world,
int indicesCount, int[] indices,
int verticesCount, float[] vertices)
{
BulletWorldUnman worldu = world as BulletWorldUnman;
return new BulletShapeUnman(
BSAPICPP.CreateConvexHullShape2(worldu.ptr, indicesCount, indices, verticesCount, vertices),
BSPhysicsShapeType.SHAPE_CONVEXHULL);
}
public override BulletShape BuildNativeShape(BulletWorld world, ShapeData shapeData)
{
BulletWorldUnman worldu = world as BulletWorldUnman;
@ -273,7 +305,7 @@ public override void SetShapeCollisionMargin(BulletShape shape, float margin)
{
BulletShapeUnman shapeu = shape as BulletShapeUnman;
if (shapeu != null && shapeu.HasPhysicalShape)
BSAPICPP.SetShapeCollisionMargin2(shapeu.ptr, margin);
BSAPICPP.SetShapeCollisionMargin(shapeu.ptr, margin);
}
public override BulletShape BuildCapsuleShape(BulletWorld world, float radius, float height, Vector3 scale)
@ -327,6 +359,12 @@ public override void RemoveChildShapeFromCompoundShape(BulletShape shape, Bullet
BSAPICPP.RemoveChildShapeFromCompoundShape2(shapeu.ptr, removeShapeu.ptr);
}
public override void UpdateChildTransform(BulletShape pShape, int childIndex, Vector3 pos, Quaternion rot, bool shouldRecalculateLocalAabb)
{
BulletShapeUnman shapeu = pShape as BulletShapeUnman;
BSAPICPP.UpdateChildTransform2(shapeu.ptr, childIndex, pos, rot, shouldRecalculateLocalAabb);
}
public override void RecalculateCompoundShapeLocalAabb(BulletShape shape)
{
BulletShapeUnman shapeu = shape as BulletShapeUnman;
@ -337,7 +375,7 @@ public override BulletShape DuplicateCollisionShape(BulletWorld world, BulletSha
{
BulletWorldUnman worldu = world as BulletWorldUnman;
BulletShapeUnman srcShapeu = srcShape as BulletShapeUnman;
return new BulletShapeUnman(BSAPICPP.DuplicateCollisionShape2(worldu.ptr, srcShapeu.ptr, id), srcShape.type);
return new BulletShapeUnman(BSAPICPP.DuplicateCollisionShape2(worldu.ptr, srcShapeu.ptr, id), srcShape.shapeType);
}
public override bool DeleteCollisionShape(BulletWorld world, BulletShape shape)
@ -419,6 +457,28 @@ public override BulletConstraint Create6DofConstraintToPoint(BulletWorld world,
joinPoint, useLinearReferenceFrameA, disableCollisionsBetweenLinkedBodies));
}
public override BulletConstraint Create6DofConstraintFixed(BulletWorld world, BulletBody obj1,
Vector3 frameInBloc, Quaternion frameInBrot,
bool useLinearReferenceFrameB, bool disableCollisionsBetweenLinkedBodies)
{
BulletWorldUnman worldu = world as BulletWorldUnman;
BulletBodyUnman bodyu1 = obj1 as BulletBodyUnman;
return new BulletConstraintUnman(BSAPICPP.Create6DofConstraintFixed2(worldu.ptr, bodyu1.ptr,
frameInBloc, frameInBrot, useLinearReferenceFrameB, disableCollisionsBetweenLinkedBodies));
}
public override BulletConstraint Create6DofSpringConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
Vector3 frame1loc, Quaternion frame1rot,
Vector3 frame2loc, Quaternion frame2rot,
bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies)
{
BulletWorldUnman worldu = world as BulletWorldUnman;
BulletBodyUnman bodyu1 = obj1 as BulletBodyUnman;
BulletBodyUnman bodyu2 = obj2 as BulletBodyUnman;
return new BulletConstraintUnman(BSAPICPP.Create6DofSpringConstraint2(worldu.ptr, bodyu1.ptr, bodyu2.ptr, frame1loc, frame1rot,
frame2loc, frame2rot, useLinearReferenceFrameA, disableCollisionsBetweenLinkedBodies));
}
public override BulletConstraint CreateHingeConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
Vector3 pivotinA, Vector3 pivotinB,
Vector3 axisInA, Vector3 axisInB,
@ -431,6 +491,52 @@ public override BulletConstraint CreateHingeConstraint(BulletWorld world, Bullet
pivotinA, pivotinB, axisInA, axisInB, useLinearReferenceFrameA, disableCollisionsBetweenLinkedBodies));
}
public override BulletConstraint CreateSliderConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
Vector3 frame1loc, Quaternion frame1rot,
Vector3 frame2loc, Quaternion frame2rot,
bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies)
{
BulletWorldUnman worldu = world as BulletWorldUnman;
BulletBodyUnman bodyu1 = obj1 as BulletBodyUnman;
BulletBodyUnman bodyu2 = obj2 as BulletBodyUnman;
return new BulletConstraintUnman(BSAPICPP.CreateSliderConstraint2(worldu.ptr, bodyu1.ptr, bodyu2.ptr, frame1loc, frame1rot,
frame2loc, frame2rot, useLinearReferenceFrameA, disableCollisionsBetweenLinkedBodies));
}
public override BulletConstraint CreateConeTwistConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
Vector3 frame1loc, Quaternion frame1rot,
Vector3 frame2loc, Quaternion frame2rot,
bool disableCollisionsBetweenLinkedBodies)
{
BulletWorldUnman worldu = world as BulletWorldUnman;
BulletBodyUnman bodyu1 = obj1 as BulletBodyUnman;
BulletBodyUnman bodyu2 = obj2 as BulletBodyUnman;
return new BulletConstraintUnman(BSAPICPP.CreateConeTwistConstraint2(worldu.ptr, bodyu1.ptr, bodyu2.ptr, frame1loc, frame1rot,
frame2loc, frame2rot, disableCollisionsBetweenLinkedBodies));
}
public override BulletConstraint CreateGearConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
Vector3 axisInA, Vector3 axisInB,
float ratio, bool disableCollisionsBetweenLinkedBodies)
{
BulletWorldUnman worldu = world as BulletWorldUnman;
BulletBodyUnman bodyu1 = obj1 as BulletBodyUnman;
BulletBodyUnman bodyu2 = obj2 as BulletBodyUnman;
return new BulletConstraintUnman(BSAPICPP.CreateGearConstraint2(worldu.ptr, bodyu1.ptr, bodyu2.ptr, axisInA, axisInB,
ratio, disableCollisionsBetweenLinkedBodies));
}
public override BulletConstraint CreatePoint2PointConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
Vector3 pivotInA, Vector3 pivotInB,
bool disableCollisionsBetweenLinkedBodies)
{
BulletWorldUnman worldu = world as BulletWorldUnman;
BulletBodyUnman bodyu1 = obj1 as BulletBodyUnman;
BulletBodyUnman bodyu2 = obj2 as BulletBodyUnman;
return new BulletConstraintUnman(BSAPICPP.CreatePoint2PointConstraint2(worldu.ptr, bodyu1.ptr, bodyu2.ptr, pivotInA, pivotInB,
disableCollisionsBetweenLinkedBodies));
}
public override void SetConstraintEnable(BulletConstraint constrain, float numericTrueFalse)
{
BulletConstraintUnman constrainu = constrain as BulletConstraintUnman;
@ -530,12 +636,12 @@ public override void SetForceUpdateAllAabbs(BulletWorld world, bool force)
// btDynamicsWorld entries
public override bool AddObjectToWorld(BulletWorld world, BulletBody obj)
{
// Bullet resets several variables when an object is added to the world.
// Gravity is reset to world default depending on the static/dynamic
// type. Of course, the collision flags in the broadphase proxy are initialized to default.
BulletWorldUnman worldu = world as BulletWorldUnman;
BulletBodyUnman bodyu = obj as BulletBodyUnman;
// Bullet resets several variables when an object is added to the world.
// Gravity is reset to world default depending on the static/dynamic
// type. Of course, the collision flags in the broadphase proxy are initialized to default.
Vector3 origGrav = BSAPICPP.GetGravity2(bodyu.ptr);
bool ret = BSAPICPP.AddObjectToWorld2(worldu.ptr, bodyu.ptr);
@ -921,6 +1027,7 @@ public override void SetCenterOfMassByPosRot(BulletBody obj, Vector3 pos, Quater
}
// Add a force to the object as if its mass is one.
// Deep down in Bullet: m_totalForce += force*m_linearFactor;
public override void ApplyCentralForce(BulletBody obj, Vector3 force)
{
BulletBodyUnman bodyu = obj as BulletBodyUnman;
@ -964,6 +1071,7 @@ public override void SetSleepingThresholds(BulletBody obj, float lin_threshold,
BSAPICPP.SetSleepingThresholds2(bodyu.ptr, lin_threshold, ang_threshold);
}
// Deep down in Bullet: m_totalTorque += torque*m_angularFactor;
public override void ApplyTorque(BulletBody obj, Vector3 torque)
{
BulletBodyUnman bodyu = obj as BulletBodyUnman;
@ -971,6 +1079,8 @@ public override void ApplyTorque(BulletBody obj, Vector3 torque)
}
// Apply force at the given point. Will add torque to the object.
// Deep down in Bullet: applyCentralForce(force);
// applyTorque(rel_pos.cross(force*m_linearFactor));
public override void ApplyForce(BulletBody obj, Vector3 force, Vector3 pos)
{
BulletBodyUnman bodyu = obj as BulletBodyUnman;
@ -978,6 +1088,7 @@ public override void ApplyForce(BulletBody obj, Vector3 force, Vector3 pos)
}
// Apply impulse to the object. Same as "ApplycentralForce" but force scaled by object's mass.
// Deep down in Bullet: m_linearVelocity += impulse *m_linearFactor * m_inverseMass;
public override void ApplyCentralImpulse(BulletBody obj, Vector3 imp)
{
BulletBodyUnman bodyu = obj as BulletBodyUnman;
@ -985,6 +1096,7 @@ public override void ApplyCentralImpulse(BulletBody obj, Vector3 imp)
}
// Apply impulse to the object's torque. Force is scaled by object's mass.
// Deep down in Bullet: m_angularVelocity += m_invInertiaTensorWorld * torque * m_angularFactor;
public override void ApplyTorqueImpulse(BulletBody obj, Vector3 imp)
{
BulletBodyUnman bodyu = obj as BulletBodyUnman;
@ -992,6 +1104,8 @@ public override void ApplyTorqueImpulse(BulletBody obj, Vector3 imp)
}
// Apply impulse at the point given. For is scaled by object's mass and effects both linear and angular forces.
// Deep down in Bullet: applyCentralImpulse(impulse);
// applyTorqueImpulse(rel_pos.cross(impulse*m_linearFactor));
public override void ApplyImpulse(BulletBody obj, Vector3 imp, Vector3 pos)
{
BulletBodyUnman bodyu = obj as BulletBodyUnman;
@ -1259,6 +1373,16 @@ public override void DumpPhysicsStatistics(BulletWorld world)
BulletWorldUnman worldu = world as BulletWorldUnman;
BSAPICPP.DumpPhysicsStatistics2(worldu.ptr);
}
public override void ResetBroadphasePool(BulletWorld world)
{
BulletWorldUnman worldu = world as BulletWorldUnman;
BSAPICPP.ResetBroadphasePool(worldu.ptr);
}
public override void ResetConstraintSolver(BulletWorld world)
{
BulletWorldUnman worldu = world as BulletWorldUnman;
BSAPICPP.ResetConstraintSolver(worldu.ptr);
}
// =====================================================================================
// =====================================================================================
@ -1306,7 +1430,15 @@ public static extern IntPtr CreateHullShape2(IntPtr world,
int hullCount, [MarshalAs(UnmanagedType.LPArray)] float[] hulls);
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern IntPtr BuildHullShapeFromMesh2(IntPtr world, IntPtr meshShape);
public static extern IntPtr BuildHullShapeFromMesh2(IntPtr world, IntPtr meshShape, HACDParams parms);
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern IntPtr BuildConvexHullShapeFromMesh2(IntPtr world, IntPtr meshShape);
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern IntPtr CreateConvexHullShape2(IntPtr world,
int indicesCount, [MarshalAs(UnmanagedType.LPArray)] int[] indices,
int verticesCount, [MarshalAs(UnmanagedType.LPArray)] float[] vertices );
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern IntPtr BuildNativeShape2(IntPtr world, ShapeData shapeData);
@ -1315,7 +1447,7 @@ public static extern IntPtr BuildNativeShape2(IntPtr world, ShapeData shapeData)
public static extern bool IsNativeShape2(IntPtr shape);
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern void SetShapeCollisionMargin2(IntPtr shape, float margin);
public static extern void SetShapeCollisionMargin(IntPtr shape, float margin);
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern IntPtr BuildCapsuleShape2(IntPtr world, float radius, float height, Vector3 scale);
@ -1338,6 +1470,9 @@ public static extern IntPtr RemoveChildShapeFromCompoundShapeIndex2(IntPtr cShap
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern void RemoveChildShapeFromCompoundShape2(IntPtr cShape, IntPtr removeShape);
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern void UpdateChildTransform2(IntPtr pShape, int childIndex, Vector3 pos, Quaternion rot, bool shouldRecalculateLocalAabb);
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern void RecalculateCompoundShapeLocalAabb2(IntPtr cShape);
@ -1368,7 +1503,7 @@ public static extern void DestroyObject2(IntPtr sim, IntPtr obj);
public static extern IntPtr CreateGroundPlaneShape2(uint id, float height, float collisionMargin);
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern IntPtr CreateTerrainShape2(uint id, Vector3 size, float minHeight, float maxHeight,
public static extern IntPtr CreateTerrainShape2(uint id, Vector3 size, float minHeight, float maxHeight,
[MarshalAs(UnmanagedType.LPArray)] float[] heightMap,
float scaleFactor, float collisionMargin);
@ -1385,12 +1520,46 @@ public static extern IntPtr Create6DofConstraintToPoint2(IntPtr world, IntPtr ob
Vector3 joinPoint,
bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern IntPtr Create6DofConstraintFixed2(IntPtr world, IntPtr obj1,
Vector3 frameInBloc, Quaternion frameInBrot,
bool useLinearReferenceFrameB, bool disableCollisionsBetweenLinkedBodies);
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern IntPtr Create6DofSpringConstraint2(IntPtr world, IntPtr obj1, IntPtr obj2,
Vector3 frame1loc, Quaternion frame1rot,
Vector3 frame2loc, Quaternion frame2rot,
bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern IntPtr CreateHingeConstraint2(IntPtr world, IntPtr obj1, IntPtr obj2,
Vector3 pivotinA, Vector3 pivotinB,
Vector3 axisInA, Vector3 axisInB,
bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern IntPtr CreateSliderConstraint2(IntPtr world, IntPtr obj1, IntPtr obj2,
Vector3 frameInAloc, Quaternion frameInArot,
Vector3 frameInBloc, Quaternion frameInBrot,
bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern IntPtr CreateConeTwistConstraint2(IntPtr world, IntPtr obj1, IntPtr obj2,
Vector3 frameInAloc, Quaternion frameInArot,
Vector3 frameInBloc, Quaternion frameInBrot,
bool disableCollisionsBetweenLinkedBodies);
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern IntPtr CreateGearConstraint2(IntPtr world, IntPtr obj1, IntPtr obj2,
Vector3 axisInA, Vector3 axisInB,
float ratio, bool disableCollisionsBetweenLinkedBodies);
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern IntPtr CreatePoint2PointConstraint2(IntPtr world, IntPtr obj1, IntPtr obj2,
Vector3 pivotInA, Vector3 pivotInB,
bool disableCollisionsBetweenLinkedBodies);
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern void SetConstraintEnable2(IntPtr constrain, float numericTrueFalse);
@ -1832,6 +2001,12 @@ public static extern void DumpAllInfo2(IntPtr sim);
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern void DumpPhysicsStatistics2(IntPtr sim);
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern void ResetBroadphasePool(IntPtr sim);
[DllImport("BulletSim", CallingConvention = CallingConvention.Cdecl), SuppressUnmanagedCodeSecurity]
public static extern void ResetConstraintSolver(IntPtr sim);
}
}

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,351 @@
/*
* Copyright (c) Contributors, http://opensimulator.org/
* See CONTRIBUTORS.TXT for a full list of copyright holders.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyrightD
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the OpenSimulator Project nor the
* names of its contributors may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE DEVELOPERS ``AS IS'' AND ANY
* EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE CONTRIBUTORS BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
using OpenSim.Region.Physics.Manager;
using OMV = OpenMetaverse;
namespace OpenSim.Region.Physics.BulletSPlugin
{
public class BSActorAvatarMove : BSActor
{
BSVMotor m_velocityMotor;
// Set to true if we think we're going up stairs.
// This state is remembered because collisions will turn on and off as we go up stairs.
int m_walkingUpStairs;
float m_lastStepUp;
public BSActorAvatarMove(BSScene physicsScene, BSPhysObject pObj, string actorName)
: base(physicsScene, pObj, actorName)
{
m_velocityMotor = null;
m_walkingUpStairs = 0;
m_physicsScene.DetailLog("{0},BSActorAvatarMove,constructor", m_controllingPrim.LocalID);
}
// BSActor.isActive
public override bool isActive
{
get { return Enabled && m_controllingPrim.IsPhysicallyActive; }
}
// Release any connections and resources used by the actor.
// BSActor.Dispose()
public override void Dispose()
{
Enabled = false;
}
// Called when physical parameters (properties set in Bullet) need to be re-applied.
// Called at taint-time.
// BSActor.Refresh()
public override void Refresh()
{
m_physicsScene.DetailLog("{0},BSActorAvatarMove,refresh", m_controllingPrim.LocalID);
// If the object is physically active, add the hoverer prestep action
if (isActive)
{
ActivateAvatarMove();
}
else
{
DeactivateAvatarMove();
}
}
// The object's physical representation is being rebuilt so pick up any physical dependencies (constraints, ...).
// Register a prestep action to restore physical requirements before the next simulation step.
// Called at taint-time.
// BSActor.RemoveDependencies()
public override void RemoveDependencies()
{
// Nothing to do for the hoverer since it is all software at pre-step action time.
}
// Usually called when target velocity changes to set the current velocity and the target
// into the movement motor.
public void SetVelocityAndTarget(OMV.Vector3 vel, OMV.Vector3 targ, bool inTaintTime)
{
m_physicsScene.TaintedObject(inTaintTime, "BSActorAvatarMove.setVelocityAndTarget", delegate()
{
if (m_velocityMotor != null)
{
m_velocityMotor.Reset();
m_velocityMotor.SetTarget(targ);
m_velocityMotor.SetCurrent(vel);
m_velocityMotor.Enabled = true;
}
});
}
// If a hover motor has not been created, create one and start the hovering.
private void ActivateAvatarMove()
{
if (m_velocityMotor == null)
{
// Infinite decay and timescale values so motor only changes current to target values.
m_velocityMotor = new BSVMotor("BSCharacter.Velocity",
0.2f, // time scale
BSMotor.Infinite, // decay time scale
1f // efficiency
);
// _velocityMotor.PhysicsScene = PhysicsScene; // DEBUG DEBUG so motor will output detail log messages.
SetVelocityAndTarget(m_controllingPrim.RawVelocity, m_controllingPrim.TargetVelocity, true /* inTaintTime */);
m_physicsScene.BeforeStep += Mover;
m_walkingUpStairs = 0;
}
}
private void DeactivateAvatarMove()
{
if (m_velocityMotor != null)
{
m_physicsScene.BeforeStep -= Mover;
m_velocityMotor = null;
}
}
// Called just before the simulation step. Update the vertical position for hoverness.
private void Mover(float timeStep)
{
// Don't do movement while the object is selected.
if (!isActive)
return;
// TODO: Decide if the step parameters should be changed depending on the avatar's
// state (flying, colliding, ...). There is code in ODE to do this.
// COMMENTARY: when the user is making the avatar walk, except for falling, the velocity
// specified for the avatar is the one that should be used. For falling, if the avatar
// is not flying and is not colliding then it is presumed to be falling and the Z
// component is not fooled with (thus allowing gravity to do its thing).
// When the avatar is standing, though, the user has specified a velocity of zero and
// the avatar should be standing. But if the avatar is pushed by something in the world
// (raising elevator platform, moving vehicle, ...) the avatar should be allowed to
// move. Thus, the velocity cannot be forced to zero. The problem is that small velocity
// errors can creap in and the avatar will slowly float off in some direction.
// So, the problem is that, when an avatar is standing, we cannot tell creaping error
// from real pushing.
// The code below uses whether the collider is static or moving to decide whether to zero motion.
m_velocityMotor.Step(timeStep);
m_controllingPrim.IsStationary = false;
// If we're not supposed to be moving, make sure things are zero.
if (m_velocityMotor.ErrorIsZero() && m_velocityMotor.TargetValue == OMV.Vector3.Zero)
{
// The avatar shouldn't be moving
m_velocityMotor.Zero();
if (m_controllingPrim.IsColliding)
{
// If we are colliding with a stationary object, presume we're standing and don't move around
if (!m_controllingPrim.ColliderIsMoving)
{
m_physicsScene.DetailLog("{0},BSCharacter.MoveMotor,collidingWithStationary,zeroingMotion", m_controllingPrim.LocalID);
m_controllingPrim.IsStationary = true;
m_controllingPrim.ZeroMotion(true /* inTaintTime */);
}
// Standing has more friction on the ground
if (m_controllingPrim.Friction != BSParam.AvatarStandingFriction)
{
m_controllingPrim.Friction = BSParam.AvatarStandingFriction;
m_physicsScene.PE.SetFriction(m_controllingPrim.PhysBody, m_controllingPrim.Friction);
}
}
else
{
if (m_controllingPrim.Flying)
{
// Flying and not collising and velocity nearly zero.
m_controllingPrim.ZeroMotion(true /* inTaintTime */);
}
}
m_physicsScene.DetailLog("{0},BSCharacter.MoveMotor,taint,stopping,target={1},colliding={2}",
m_controllingPrim.LocalID, m_velocityMotor.TargetValue, m_controllingPrim.IsColliding);
}
else
{
// Supposed to be moving.
OMV.Vector3 stepVelocity = m_velocityMotor.CurrentValue;
if (m_controllingPrim.Friction != BSParam.AvatarFriction)
{
// Probably starting up walking. Set friction to moving friction.
m_controllingPrim.Friction = BSParam.AvatarFriction;
m_physicsScene.PE.SetFriction(m_controllingPrim.PhysBody, m_controllingPrim.Friction);
}
// If falling, we keep the world's downward vector no matter what the other axis specify.
// The check for RawVelocity.Z < 0 makes jumping work (temporary upward force).
if (!m_controllingPrim.Flying && !m_controllingPrim.IsColliding)
{
if (m_controllingPrim.RawVelocity.Z < 0)
stepVelocity.Z = m_controllingPrim.RawVelocity.Z;
// DetailLog("{0},BSCharacter.MoveMotor,taint,overrideStepZWithWorldZ,stepVel={1}", LocalID, stepVelocity);
}
// 'stepVelocity' is now the speed we'd like the avatar to move in. Turn that into an instantanous force.
OMV.Vector3 moveForce = (stepVelocity - m_controllingPrim.RawVelocity) * m_controllingPrim.Mass;
// Add special movement force to allow avatars to walk up stepped surfaces.
moveForce += WalkUpStairs();
m_physicsScene.DetailLog("{0},BSCharacter.MoveMotor,move,stepVel={1},vel={2},mass={3},moveForce={4}",
m_controllingPrim.LocalID, stepVelocity, m_controllingPrim.RawVelocity, m_controllingPrim.Mass, moveForce);
m_physicsScene.PE.ApplyCentralImpulse(m_controllingPrim.PhysBody, moveForce);
}
}
// Decide if the character is colliding with a low object and compute a force to pop the
// avatar up so it can walk up and over the low objects.
private OMV.Vector3 WalkUpStairs()
{
OMV.Vector3 ret = OMV.Vector3.Zero;
m_physicsScene.DetailLog("{0},BSCharacter.WalkUpStairs,IsColliding={1},flying={2},targSpeed={3},collisions={4},avHeight={5}",
m_controllingPrim.LocalID, m_controllingPrim.IsColliding, m_controllingPrim.Flying,
m_controllingPrim.TargetVelocitySpeed, m_controllingPrim.CollisionsLastTick.Count, m_controllingPrim.Size.Z);
// This test is done if moving forward, not flying and is colliding with something.
// Check for stairs climbing if colliding, not flying and moving forward
if ( m_controllingPrim.IsColliding
&& !m_controllingPrim.Flying
&& m_controllingPrim.TargetVelocitySpeed > 0.1f )
{
// The range near the character's feet where we will consider stairs
// float nearFeetHeightMin = m_controllingPrim.RawPosition.Z - (m_controllingPrim.Size.Z / 2f) + 0.05f;
// Note: there is a problem with the computation of the capsule height. Thus RawPosition is off
// from the height. Revisit size and this computation when height is scaled properly.
float nearFeetHeightMin = m_controllingPrim.RawPosition.Z - (m_controllingPrim.Size.Z / 2f) - 0.05f;
float nearFeetHeightMax = nearFeetHeightMin + BSParam.AvatarStepHeight;
// Look for a collision point that is near the character's feet and is oriented the same as the charactor is.
// Find the highest 'good' collision.
OMV.Vector3 highestTouchPosition = OMV.Vector3.Zero;
foreach (KeyValuePair<uint, ContactPoint> kvp in m_controllingPrim.CollisionsLastTick.m_objCollisionList)
{
// Don't care about collisions with the terrain
if (kvp.Key > m_physicsScene.TerrainManager.HighestTerrainID)
{
OMV.Vector3 touchPosition = kvp.Value.Position;
m_physicsScene.DetailLog("{0},BSCharacter.WalkUpStairs,min={1},max={2},touch={3}",
m_controllingPrim.LocalID, nearFeetHeightMin, nearFeetHeightMax, touchPosition);
if (touchPosition.Z >= nearFeetHeightMin && touchPosition.Z <= nearFeetHeightMax)
{
// This contact is within the 'near the feet' range.
// The normal should be our contact point to the object so it is pointing away
// thus the difference between our facing orientation and the normal should be small.
OMV.Vector3 directionFacing = OMV.Vector3.UnitX * m_controllingPrim.RawOrientation;
OMV.Vector3 touchNormal = OMV.Vector3.Normalize(kvp.Value.SurfaceNormal);
float diff = Math.Abs(OMV.Vector3.Distance(directionFacing, touchNormal));
if (diff < BSParam.AvatarStepApproachFactor)
{
if (highestTouchPosition.Z < touchPosition.Z)
highestTouchPosition = touchPosition;
}
}
}
}
m_walkingUpStairs = 0;
// If there is a good step sensing, move the avatar over the step.
if (highestTouchPosition != OMV.Vector3.Zero)
{
// Remember that we are going up stairs. This is needed because collisions
// will stop when we move up so this smoothes out that effect.
m_walkingUpStairs = BSParam.AvatarStepSmoothingSteps;
m_lastStepUp = highestTouchPosition.Z - nearFeetHeightMin;
ret = ComputeStairCorrection(m_lastStepUp);
m_physicsScene.DetailLog("{0},BSCharacter.WalkUpStairs,touchPos={1},nearFeetMin={2},ret={3}",
m_controllingPrim.LocalID, highestTouchPosition, nearFeetHeightMin, ret);
}
}
else
{
// If we used to be going up stairs but are not now, smooth the case where collision goes away while
// we are bouncing up the stairs.
if (m_walkingUpStairs > 0)
{
m_walkingUpStairs--;
ret = ComputeStairCorrection(m_lastStepUp);
}
}
return ret;
}
private OMV.Vector3 ComputeStairCorrection(float stepUp)
{
OMV.Vector3 ret = OMV.Vector3.Zero;
OMV.Vector3 displacement = OMV.Vector3.Zero;
if (stepUp > 0f)
{
// Found the stairs contact point. Push up a little to raise the character.
if (BSParam.AvatarStepForceFactor > 0f)
{
float upForce = stepUp * m_controllingPrim.Mass * BSParam.AvatarStepForceFactor;
ret = new OMV.Vector3(0f, 0f, upForce);
}
// Also move the avatar up for the new height
if (BSParam.AvatarStepUpCorrectionFactor > 0f)
{
// Move the avatar up related to the height of the collision
displacement = new OMV.Vector3(0f, 0f, stepUp * BSParam.AvatarStepUpCorrectionFactor);
m_controllingPrim.ForcePosition = m_controllingPrim.RawPosition + displacement;
}
else
{
if (BSParam.AvatarStepUpCorrectionFactor < 0f)
{
// Move the avatar up about the specified step height
displacement = new OMV.Vector3(0f, 0f, BSParam.AvatarStepHeight);
m_controllingPrim.ForcePosition = m_controllingPrim.RawPosition + displacement;
}
}
m_physicsScene.DetailLog("{0},BSCharacter.WalkUpStairs.ComputeStairCorrection,disp={1},force={2}",
m_controllingPrim.LocalID, displacement, ret);
}
return ret;
}
}
}

View File

@ -0,0 +1,173 @@
/*
* Copyright (c) Contributors, http://opensimulator.org/
* See CONTRIBUTORS.TXT for a full list of copyright holders.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyrightD
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the OpenSimulator Project nor the
* names of its contributors may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE DEVELOPERS ``AS IS'' AND ANY
* EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE CONTRIBUTORS BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
using OpenSim.Region.Physics.Manager;
using OMV = OpenMetaverse;
namespace OpenSim.Region.Physics.BulletSPlugin
{
public class BSActorHover : BSActor
{
private BSFMotor m_hoverMotor;
public BSActorHover(BSScene physicsScene, BSPhysObject pObj, string actorName)
: base(physicsScene, pObj, actorName)
{
m_hoverMotor = null;
m_physicsScene.DetailLog("{0},BSActorHover,constructor", m_controllingPrim.LocalID);
}
// BSActor.isActive
public override bool isActive
{
get { return Enabled; }
}
// Release any connections and resources used by the actor.
// BSActor.Dispose()
public override void Dispose()
{
Enabled = false;
}
// Called when physical parameters (properties set in Bullet) need to be re-applied.
// Called at taint-time.
// BSActor.Refresh()
public override void Refresh()
{
m_physicsScene.DetailLog("{0},BSActorHover,refresh", m_controllingPrim.LocalID);
// If not active any more, turn me off
if (!m_controllingPrim.HoverActive)
{
SetEnabled(false);
}
// If the object is physically active, add the hoverer prestep action
if (isActive)
{
ActivateHover();
}
else
{
DeactivateHover();
}
}
// The object's physical representation is being rebuilt so pick up any physical dependencies (constraints, ...).
// Register a prestep action to restore physical requirements before the next simulation step.
// Called at taint-time.
// BSActor.RemoveDependencies()
public override void RemoveDependencies()
{
// Nothing to do for the hoverer since it is all software at pre-step action time.
}
// If a hover motor has not been created, create one and start the hovering.
private void ActivateHover()
{
if (m_hoverMotor == null)
{
// Turning the target on
m_hoverMotor = new BSFMotor("BSActorHover",
m_controllingPrim.HoverTau, // timeScale
BSMotor.Infinite, // decay time scale
1f // efficiency
);
m_hoverMotor.SetTarget(ComputeCurrentHoverHeight());
m_hoverMotor.SetCurrent(m_controllingPrim.RawPosition.Z);
m_hoverMotor.PhysicsScene = m_physicsScene; // DEBUG DEBUG so motor will output detail log messages.
m_physicsScene.BeforeStep += Hoverer;
}
}
private void DeactivateHover()
{
if (m_hoverMotor != null)
{
m_physicsScene.BeforeStep -= Hoverer;
m_hoverMotor = null;
}
}
// Called just before the simulation step. Update the vertical position for hoverness.
private void Hoverer(float timeStep)
{
// Don't do hovering while the object is selected.
if (!isActive)
return;
m_hoverMotor.SetCurrent(m_controllingPrim.RawPosition.Z);
m_hoverMotor.SetTarget(ComputeCurrentHoverHeight());
float targetHeight = m_hoverMotor.Step(timeStep);
// 'targetHeight' is where we'd like the Z of the prim to be at this moment.
// Compute the amount of force to push us there.
float moveForce = (targetHeight - m_controllingPrim.RawPosition.Z) * m_controllingPrim.RawMass;
// Undo anything the object thinks it's doing at the moment
moveForce = -m_controllingPrim.RawVelocity.Z * m_controllingPrim.Mass;
m_physicsScene.PE.ApplyCentralImpulse(m_controllingPrim.PhysBody, new OMV.Vector3(0f, 0f, moveForce));
m_physicsScene.DetailLog("{0},BSPrim.Hover,move,targHt={1},moveForce={2},mass={3}",
m_controllingPrim.LocalID, targetHeight, moveForce, m_controllingPrim.RawMass);
}
// Based on current position, determine what we should be hovering at now.
// Must recompute often. What if we walked offa cliff>
private float ComputeCurrentHoverHeight()
{
float ret = m_controllingPrim.HoverHeight;
float groundHeight = m_physicsScene.TerrainManager.GetTerrainHeightAtXYZ(m_controllingPrim.RawPosition);
switch (m_controllingPrim.HoverType)
{
case PIDHoverType.Ground:
ret = groundHeight + m_controllingPrim.HoverHeight;
break;
case PIDHoverType.GroundAndWater:
float waterHeight = m_physicsScene.TerrainManager.GetWaterLevelAtXYZ(m_controllingPrim.RawPosition);
if (groundHeight > waterHeight)
{
ret = groundHeight + m_controllingPrim.HoverHeight;
}
else
{
ret = waterHeight + m_controllingPrim.HoverHeight;
}
break;
}
return ret;
}
}
}

View File

@ -0,0 +1,187 @@
/*
* Copyright (c) Contributors, http://opensimulator.org/
* See CONTRIBUTORS.TXT for a full list of copyright holders.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyrightD
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the OpenSimulator Project nor the
* names of its contributors may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE DEVELOPERS ``AS IS'' AND ANY
* EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE CONTRIBUTORS BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
using OMV = OpenMetaverse;
namespace OpenSim.Region.Physics.BulletSPlugin
{
public class BSActorLockAxis : BSActor
{
BSConstraint LockAxisConstraint = null;
public BSActorLockAxis(BSScene physicsScene, BSPhysObject pObj, string actorName)
: base(physicsScene, pObj, actorName)
{
m_physicsScene.DetailLog("{0},BSActorLockAxis,constructor", m_controllingPrim.LocalID);
LockAxisConstraint = null;
}
// BSActor.isActive
public override bool isActive
{
get { return Enabled && m_controllingPrim.IsPhysicallyActive; }
}
// Release any connections and resources used by the actor.
// BSActor.Dispose()
public override void Dispose()
{
RemoveAxisLockConstraint();
}
// Called when physical parameters (properties set in Bullet) need to be re-applied.
// Called at taint-time.
// BSActor.Refresh()
public override void Refresh()
{
m_physicsScene.DetailLog("{0},BSActorLockAxis,refresh,lockedAxis={1},enabled={2},pActive={3}",
m_controllingPrim.LocalID, m_controllingPrim.LockedAngularAxis, Enabled, m_controllingPrim.IsPhysicallyActive);
// If all the axis are free, we don't need to exist
if (m_controllingPrim.LockedAngularAxis == m_controllingPrim.LockedAxisFree)
{
Enabled = false;
}
// If the object is physically active, add the axis locking constraint
if (isActive)
{
AddAxisLockConstraint();
}
else
{
RemoveAxisLockConstraint();
}
}
// The object's physical representation is being rebuilt so pick up any physical dependencies (constraints, ...).
// Register a prestep action to restore physical requirements before the next simulation step.
// Called at taint-time.
// BSActor.RemoveDependencies()
public override void RemoveDependencies()
{
if (LockAxisConstraint != null)
{
// If a constraint is set up, remove it from the physical scene
RemoveAxisLockConstraint();
// Schedule a call before the next simulation step to restore the constraint.
m_physicsScene.PostTaintObject("BSActorLockAxis:" + ActorName, m_controllingPrim.LocalID, delegate()
{
Refresh();
});
}
}
private void AddAxisLockConstraint()
{
if (LockAxisConstraint == null)
{
// Lock that axis by creating a 6DOF constraint that has one end in the world and
// the other in the object.
// http://www.bulletphysics.org/Bullet/phpBB3/viewtopic.php?p=20817
// http://www.bulletphysics.org/Bullet/phpBB3/viewtopic.php?p=26380
// Remove any existing axis constraint (just to be sure)
RemoveAxisLockConstraint();
BSConstraint6Dof axisConstrainer = new BSConstraint6Dof(m_physicsScene.World, m_controllingPrim.PhysBody,
OMV.Vector3.Zero, OMV.Quaternion.Identity,
false /* useLinearReferenceFrameB */, true /* disableCollisionsBetweenLinkedBodies */);
LockAxisConstraint = axisConstrainer;
m_physicsScene.Constraints.AddConstraint(LockAxisConstraint);
// The constraint is tied to the world and oriented to the prim.
// Free to move linearly in the region
OMV.Vector3 linearLow = OMV.Vector3.Zero;
OMV.Vector3 linearHigh = m_physicsScene.TerrainManager.DefaultRegionSize;
if (m_controllingPrim.LockedLinearAxis.X != BSPhysObject.FreeAxis)
{
linearLow.X = m_controllingPrim.RawPosition.X;
linearHigh.X = m_controllingPrim.RawPosition.X;
}
if (m_controllingPrim.LockedLinearAxis.Y != BSPhysObject.FreeAxis)
{
linearLow.Y = m_controllingPrim.RawPosition.Y;
linearHigh.Y = m_controllingPrim.RawPosition.Y;
}
if (m_controllingPrim.LockedLinearAxis.Z != BSPhysObject.FreeAxis)
{
linearLow.Z = m_controllingPrim.RawPosition.Z;
linearHigh.Z = m_controllingPrim.RawPosition.Z;
}
axisConstrainer.SetLinearLimits(linearLow, linearHigh);
// Angular with some axis locked
float fPI = (float)Math.PI;
OMV.Vector3 angularLow = new OMV.Vector3(-fPI, -fPI, -fPI);
OMV.Vector3 angularHigh = new OMV.Vector3(fPI, fPI, fPI);
if (m_controllingPrim.LockedAngularAxis.X != BSPhysObject.FreeAxis)
{
angularLow.X = 0f;
angularHigh.X = 0f;
}
if (m_controllingPrim.LockedAngularAxis.Y != BSPhysObject.FreeAxis)
{
angularLow.Y = 0f;
angularHigh.Y = 0f;
}
if (m_controllingPrim.LockedAngularAxis.Z != BSPhysObject.FreeAxis)
{
angularLow.Z = 0f;
angularHigh.Z = 0f;
}
if (!axisConstrainer.SetAngularLimits(angularLow, angularHigh))
{
m_physicsScene.DetailLog("{0},BSActorLockAxis.AddAxisLockConstraint,failedSetAngularLimits", m_controllingPrim.LocalID);
}
m_physicsScene.DetailLog("{0},BSActorLockAxis.AddAxisLockConstraint,create,linLow={1},linHi={2},angLow={3},angHi={4}",
m_controllingPrim.LocalID, linearLow, linearHigh, angularLow, angularHigh);
// Constants from one of the posts mentioned above and used in Bullet's ConstraintDemo.
axisConstrainer.TranslationalLimitMotor(true /* enable */, 5.0f, 0.1f);
axisConstrainer.RecomputeConstraintVariables(m_controllingPrim.RawMass);
}
}
private void RemoveAxisLockConstraint()
{
if (LockAxisConstraint != null)
{
m_physicsScene.Constraints.RemoveAndDestroyConstraint(LockAxisConstraint);
LockAxisConstraint = null;
m_physicsScene.DetailLog("{0},BSActorLockAxis.RemoveAxisLockConstraint,destroyingConstraint", m_controllingPrim.LocalID);
}
}
}
}

View File

@ -0,0 +1,157 @@
/*
* Copyright (c) Contributors, http://opensimulator.org/
* See CONTRIBUTORS.TXT for a full list of copyright holders.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyrightD
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the OpenSimulator Project nor the
* names of its contributors may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE DEVELOPERS ``AS IS'' AND ANY
* EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE CONTRIBUTORS BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
using OpenSim.Region.Physics.Manager;
using OMV = OpenMetaverse;
namespace OpenSim.Region.Physics.BulletSPlugin
{
public class BSActorMoveToTarget : BSActor
{
private BSVMotor m_targetMotor;
public BSActorMoveToTarget(BSScene physicsScene, BSPhysObject pObj, string actorName)
: base(physicsScene, pObj, actorName)
{
m_targetMotor = null;
m_physicsScene.DetailLog("{0},BSActorMoveToTarget,constructor", m_controllingPrim.LocalID);
}
// BSActor.isActive
public override bool isActive
{
get { return Enabled; }
}
// Release any connections and resources used by the actor.
// BSActor.Dispose()
public override void Dispose()
{
Enabled = false;
}
// Called when physical parameters (properties set in Bullet) need to be re-applied.
// Called at taint-time.
// BSActor.Refresh()
public override void Refresh()
{
m_physicsScene.DetailLog("{0},BSActorMoveToTarget,refresh,enabled={1},active={2},target={3},tau={4}",
m_controllingPrim.LocalID, Enabled, m_controllingPrim.MoveToTargetActive,
m_controllingPrim.MoveToTargetTarget, m_controllingPrim.MoveToTargetTau );
// If not active any more...
if (!m_controllingPrim.MoveToTargetActive)
{
Enabled = false;
}
if (isActive)
{
ActivateMoveToTarget();
}
else
{
DeactivateMoveToTarget();
}
}
// The object's physical representation is being rebuilt so pick up any physical dependencies (constraints, ...).
// Register a prestep action to restore physical requirements before the next simulation step.
// Called at taint-time.
// BSActor.RemoveDependencies()
public override void RemoveDependencies()
{
// Nothing to do for the moveToTarget since it is all software at pre-step action time.
}
// If a hover motor has not been created, create one and start the hovering.
private void ActivateMoveToTarget()
{
if (m_targetMotor == null)
{
// We're taking over after this.
m_controllingPrim.ZeroMotion(true);
m_targetMotor = new BSVMotor("BSActorMoveToTargget.Activate",
m_controllingPrim.MoveToTargetTau, // timeScale
BSMotor.Infinite, // decay time scale
1f // efficiency
);
m_targetMotor.PhysicsScene = m_physicsScene; // DEBUG DEBUG so motor will output detail log messages.
m_targetMotor.SetTarget(m_controllingPrim.MoveToTargetTarget);
m_targetMotor.SetCurrent(m_controllingPrim.RawPosition);
m_physicsScene.BeforeStep += Mover;
}
}
private void DeactivateMoveToTarget()
{
if (m_targetMotor != null)
{
m_physicsScene.BeforeStep -= Mover;
m_targetMotor = null;
}
}
// Called just before the simulation step. Update the vertical position for hoverness.
private void Mover(float timeStep)
{
// Don't do hovering while the object is selected.
if (!isActive)
return;
OMV.Vector3 origPosition = m_controllingPrim.RawPosition; // DEBUG DEBUG (for printout below)
// 'movePosition' is where we'd like the prim to be at this moment.
OMV.Vector3 movePosition = m_controllingPrim.RawPosition + m_targetMotor.Step(timeStep);
// If we are very close to our target, turn off the movement motor.
if (m_targetMotor.ErrorIsZero())
{
m_physicsScene.DetailLog("{0},BSActorMoveToTarget.Mover,zeroMovement,movePos={1},pos={2},mass={3}",
m_controllingPrim.LocalID, movePosition, m_controllingPrim.RawPosition, m_controllingPrim.Mass);
m_controllingPrim.ForcePosition = m_targetMotor.TargetValue;
// Setting the position does not cause the physics engine to generate a property update. Force it.
m_physicsScene.PE.PushUpdate(m_controllingPrim.PhysBody);
}
else
{
m_controllingPrim.ForcePosition = movePosition;
// Setting the position does not cause the physics engine to generate a property update. Force it.
m_physicsScene.PE.PushUpdate(m_controllingPrim.PhysBody);
}
m_physicsScene.DetailLog("{0},BSActorMoveToTarget.Mover,move,fromPos={1},movePos={2}", m_controllingPrim.LocalID, origPosition, movePosition);
}
}
}

View File

@ -0,0 +1,137 @@
/*
* Copyright (c) Contributors, http://opensimulator.org/
* See CONTRIBUTORS.TXT for a full list of copyright holders.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyrightD
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the OpenSimulator Project nor the
* names of its contributors may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE DEVELOPERS ``AS IS'' AND ANY
* EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE CONTRIBUTORS BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
using OpenSim.Region.Physics.Manager;
using OMV = OpenMetaverse;
namespace OpenSim.Region.Physics.BulletSPlugin
{
public class BSActorSetForce : BSActor
{
BSFMotor m_forceMotor;
public BSActorSetForce(BSScene physicsScene, BSPhysObject pObj, string actorName)
: base(physicsScene, pObj, actorName)
{
m_forceMotor = null;
m_physicsScene.DetailLog("{0},BSActorSetForce,constructor", m_controllingPrim.LocalID);
}
// BSActor.isActive
public override bool isActive
{
get { return Enabled && m_controllingPrim.IsPhysicallyActive; }
}
// Release any connections and resources used by the actor.
// BSActor.Dispose()
public override void Dispose()
{
Enabled = false;
}
// Called when physical parameters (properties set in Bullet) need to be re-applied.
// Called at taint-time.
// BSActor.Refresh()
public override void Refresh()
{
m_physicsScene.DetailLog("{0},BSActorSetForce,refresh", m_controllingPrim.LocalID);
// If not active any more, get rid of me (shouldn't ever happen, but just to be safe)
if (m_controllingPrim.RawForce == OMV.Vector3.Zero)
{
m_physicsScene.DetailLog("{0},BSActorSetForce,refresh,notSetForce,removing={1}", m_controllingPrim.LocalID, ActorName);
Enabled = false;
return;
}
// If the object is physically active, add the hoverer prestep action
if (isActive)
{
ActivateSetForce();
}
else
{
DeactivateSetForce();
}
}
// The object's physical representation is being rebuilt so pick up any physical dependencies (constraints, ...).
// Register a prestep action to restore physical requirements before the next simulation step.
// Called at taint-time.
// BSActor.RemoveDependencies()
public override void RemoveDependencies()
{
// Nothing to do for the hoverer since it is all software at pre-step action time.
}
// If a hover motor has not been created, create one and start the hovering.
private void ActivateSetForce()
{
if (m_forceMotor == null)
{
// A fake motor that might be used someday
m_forceMotor = new BSFMotor("setForce", 1f, 1f, 1f);
m_physicsScene.BeforeStep += Mover;
}
}
private void DeactivateSetForce()
{
if (m_forceMotor != null)
{
m_physicsScene.BeforeStep -= Mover;
m_forceMotor = null;
}
}
// Called just before the simulation step. Update the vertical position for hoverness.
private void Mover(float timeStep)
{
// Don't do force while the object is selected.
if (!isActive)
return;
m_physicsScene.DetailLog("{0},BSActorSetForce,preStep,force={1}", m_controllingPrim.LocalID, m_controllingPrim.RawForce);
if (m_controllingPrim.PhysBody.HasPhysicalBody)
{
m_physicsScene.PE.ApplyCentralForce(m_controllingPrim.PhysBody, m_controllingPrim.RawForce);
m_controllingPrim.ActivateIfPhysical(false);
}
// TODO:
}
}
}

View File

@ -0,0 +1,138 @@
/*
* Copyright (c) Contributors, http://opensimulator.org/
* See CONTRIBUTORS.TXT for a full list of copyright holders.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyrightD
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the OpenSimulator Project nor the
* names of its contributors may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE DEVELOPERS ``AS IS'' AND ANY
* EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE CONTRIBUTORS BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
using OpenSim.Region.Physics.Manager;
using OMV = OpenMetaverse;
namespace OpenSim.Region.Physics.BulletSPlugin
{
public class BSActorSetTorque : BSActor
{
BSFMotor m_torqueMotor;
public BSActorSetTorque(BSScene physicsScene, BSPhysObject pObj, string actorName)
: base(physicsScene, pObj, actorName)
{
m_torqueMotor = null;
m_physicsScene.DetailLog("{0},BSActorSetTorque,constructor", m_controllingPrim.LocalID);
}
// BSActor.isActive
public override bool isActive
{
get { return Enabled && m_controllingPrim.IsPhysicallyActive; }
}
// Release any connections and resources used by the actor.
// BSActor.Dispose()
public override void Dispose()
{
Enabled = false;
}
// Called when physical parameters (properties set in Bullet) need to be re-applied.
// Called at taint-time.
// BSActor.Refresh()
public override void Refresh()
{
m_physicsScene.DetailLog("{0},BSActorSetTorque,refresh,torque={1}", m_controllingPrim.LocalID, m_controllingPrim.RawTorque);
// If not active any more, get rid of me (shouldn't ever happen, but just to be safe)
if (m_controllingPrim.RawTorque == OMV.Vector3.Zero)
{
m_physicsScene.DetailLog("{0},BSActorSetTorque,refresh,notSetTorque,disabling={1}", m_controllingPrim.LocalID, ActorName);
Enabled = false;
return;
}
// If the object is physically active, add the hoverer prestep action
if (isActive)
{
ActivateSetTorque();
}
else
{
DeactivateSetTorque();
}
}
// The object's physical representation is being rebuilt so pick up any physical dependencies (constraints, ...).
// Register a prestep action to restore physical requirements before the next simulation step.
// Called at taint-time.
// BSActor.RemoveDependencies()
public override void RemoveDependencies()
{
// Nothing to do for the hoverer since it is all software at pre-step action time.
}
// If a hover motor has not been created, create one and start the hovering.
private void ActivateSetTorque()
{
if (m_torqueMotor == null)
{
// A fake motor that might be used someday
m_torqueMotor = new BSFMotor("setTorque", 1f, 1f, 1f);
m_physicsScene.BeforeStep += Mover;
}
}
private void DeactivateSetTorque()
{
if (m_torqueMotor != null)
{
m_physicsScene.BeforeStep -= Mover;
m_torqueMotor = null;
}
}
// Called just before the simulation step. Update the vertical position for hoverness.
private void Mover(float timeStep)
{
// Don't do force while the object is selected.
if (!isActive)
return;
m_physicsScene.DetailLog("{0},BSActorSetTorque,preStep,force={1}", m_controllingPrim.LocalID, m_controllingPrim.RawTorque);
if (m_controllingPrim.PhysBody.HasPhysicalBody)
{
m_controllingPrim.AddAngularForce(m_controllingPrim.RawTorque, false, true);
m_controllingPrim.ActivateIfPhysical(false);
}
// TODO:
}
}
}

View File

@ -0,0 +1,160 @@
/*
* Copyright (c) Contributors, http://opensimulator.org/
* See CONTRIBUTORS.TXT for a full list of copyright holders.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyrightD
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the OpenSimulator Project nor the
* names of its contributors may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE DEVELOPERS ``AS IS'' AND ANY
* EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE CONTRIBUTORS BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
using System;
using System.Collections.Generic;
using System.Text;
namespace OpenSim.Region.Physics.BulletSPlugin
{
public class BSActorCollection
{
private BSScene m_physicsScene { get; set; }
private Dictionary<string, BSActor> m_actors;
public BSActorCollection(BSScene physicsScene)
{
m_physicsScene = physicsScene;
m_actors = new Dictionary<string, BSActor>();
}
public void Add(string name, BSActor actor)
{
lock (m_actors)
{
if (!m_actors.ContainsKey(name))
{
m_actors[name] = actor;
}
}
}
public bool RemoveAndRelease(string name)
{
bool ret = false;
lock (m_actors)
{
if (m_actors.ContainsKey(name))
{
BSActor beingRemoved = m_actors[name];
m_actors.Remove(name);
beingRemoved.Dispose();
ret = true;
}
}
return ret;
}
public void Clear()
{
lock (m_actors)
{
Release();
m_actors.Clear();
}
}
public void Dispose()
{
Clear();
}
public bool HasActor(string name)
{
return m_actors.ContainsKey(name);
}
public bool TryGetActor(string actorName, out BSActor theActor)
{
return m_actors.TryGetValue(actorName, out theActor);
}
public void ForEachActor(Action<BSActor> act)
{
lock (m_actors)
{
foreach (KeyValuePair<string, BSActor> kvp in m_actors)
act(kvp.Value);
}
}
public void Enable(bool enabl)
{
ForEachActor(a => a.SetEnabled(enabl));
}
public void Release()
{
ForEachActor(a => a.Dispose());
}
public void Refresh()
{
ForEachActor(a => a.Refresh());
}
public void RemoveDependencies()
{
ForEachActor(a => a.RemoveDependencies());
}
}
// =============================================================================
/// <summary>
/// Each physical object can have 'actors' who are pushing the object around.
/// This can be used for hover, locking axis, making vehicles, etc.
/// Each physical object can have multiple actors acting on it.
///
/// An actor usually registers itself with physics scene events (pre-step action)
/// and modifies the parameters on the host physical object.
/// </summary>
public abstract class BSActor
{
protected BSScene m_physicsScene { get; private set; }
protected BSPhysObject m_controllingPrim { get; private set; }
public virtual bool Enabled { get; set; }
public string ActorName { get; private set; }
public BSActor(BSScene physicsScene, BSPhysObject pObj, string actorName)
{
m_physicsScene = physicsScene;
m_controllingPrim = pObj;
ActorName = actorName;
Enabled = true;
}
// Return 'true' if activily updating the prim
public virtual bool isActive
{
get { return Enabled; }
}
// Turn the actor on an off. Only used by ActorCollection to set all enabled/disabled.
// Anyone else should assign true/false to 'Enabled'.
public void SetEnabled(bool setEnabled)
{
Enabled = setEnabled;
}
// Release any connections and resources used by the actor.
public abstract void Dispose();
// Called when physical parameters (properties set in Bullet) need to be re-applied.
public abstract void Refresh();
// The object's physical representation is being rebuilt so pick up any physical dependencies (constraints, ...).
// Register a prestep action to restore physical requirements before the next simulation step.
public abstract void RemoveDependencies();
}
}

View File

@ -6,7 +6,7 @@
* modification, are permitted provided that the following conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyrightD
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the OpenSimulator Project nor the
@ -70,6 +70,7 @@ public enum BSPhysicsShapeType
SHAPE_COMPOUND = 22,
SHAPE_HEIGHTMAP = 23,
SHAPE_AVATAR = 24,
SHAPE_CONVEXHULL= 25,
};
// The native shapes have predefined shape hash keys
@ -87,7 +88,7 @@ public enum FixedShapeKey : ulong
[StructLayout(LayoutKind.Sequential)]
public struct ShapeData
{
public uint ID;
public UInt32 ID;
public BSPhysicsShapeType Type;
public Vector3 Position;
public Quaternion Rotation;
@ -111,7 +112,7 @@ public struct ShapeData
[StructLayout(LayoutKind.Sequential)]
public struct SweepHit
{
public uint ID;
public UInt32 ID;
public float Fraction;
public Vector3 Normal;
public Vector3 Point;
@ -119,27 +120,47 @@ public struct SweepHit
[StructLayout(LayoutKind.Sequential)]
public struct RaycastHit
{
public uint ID;
public UInt32 ID;
public float Fraction;
public Vector3 Normal;
}
[StructLayout(LayoutKind.Sequential)]
public struct CollisionDesc
{
public uint aID;
public uint bID;
public UInt32 aID;
public UInt32 bID;
public Vector3 point;
public Vector3 normal;
public float penetration;
}
[StructLayout(LayoutKind.Sequential)]
public struct EntityProperties
{
public uint ID;
public UInt32 ID;
public Vector3 Position;
public Quaternion Rotation;
public Vector3 Velocity;
public Vector3 Acceleration;
public Vector3 RotationalVelocity;
public override string ToString()
{
StringBuilder buff = new StringBuilder();
buff.Append("<i=");
buff.Append(ID.ToString());
buff.Append(",p=");
buff.Append(Position.ToString());
buff.Append(",r=");
buff.Append(Rotation.ToString());
buff.Append(",v=");
buff.Append(Velocity.ToString());
buff.Append(",a=");
buff.Append(Acceleration.ToString());
buff.Append(",rv=");
buff.Append(RotationalVelocity.ToString());
buff.Append(">");
return buff.ToString();
}
}
// Format of this structure must match the definition in the C++ code
@ -154,32 +175,6 @@ public struct ConfigurationParameters
public float collisionMargin;
public float gravity;
public float XlinearDamping;
public float XangularDamping;
public float XdeactivationTime;
public float XlinearSleepingThreshold;
public float XangularSleepingThreshold;
public float XccdMotionThreshold;
public float XccdSweptSphereRadius;
public float XcontactProcessingThreshold;
public float XterrainImplementation;
public float XterrainFriction;
public float XterrainHitFraction;
public float XterrainRestitution;
public float XterrainCollisionMargin;
public float XavatarFriction;
public float XavatarStandingFriction;
public float XavatarDensity;
public float XavatarRestitution;
public float XavatarCapsuleWidth;
public float XavatarCapsuleDepth;
public float XavatarCapsuleHeight;
public float XavatarContactProcessingThreshold;
public float XvehicleAngularDamping;
public float maxPersistantManifoldPoolSize;
public float maxCollisionAlgorithmPoolSize;
public float shouldDisableContactPoolDynamicAllocation;
@ -188,22 +183,30 @@ public struct ConfigurationParameters
public float shouldSplitSimulationIslands;
public float shouldEnableFrictionCaching;
public float numberOfSolverIterations;
public float useSingleSidedMeshes;
public float globalContactBreakingThreshold;
public float XlinksetImplementation;
public float XlinkConstraintUseFrameOffset;
public float XlinkConstraintEnableTransMotor;
public float XlinkConstraintTransMotorMaxVel;
public float XlinkConstraintTransMotorMaxForce;
public float XlinkConstraintERP;
public float XlinkConstraintCFM;
public float XlinkConstraintSolverIterations;
public float XphysicsLoggingFrames;
public float physicsLoggingFrames;
public const float numericTrue = 1f;
public const float numericFalse = 0f;
}
// Parameters passed for the conversion of a mesh to a hull using Bullet's HACD library.
[StructLayout(LayoutKind.Sequential)]
public struct HACDParams
{
// usual default values
public float maxVerticesPerHull; // 100
public float minClusters; // 2
public float compacityWeight; // 0.1
public float volumeWeight; // 0.0
public float concavity; // 100
public float addExtraDistPoints; // false
public float addNeighboursDistPoints; // false
public float addFacesPoints; // false
public float shouldAdjustCollisionMargin; // false
}
// The states a bullet collision object can have
public enum ActivationState : uint
@ -238,9 +241,10 @@ public enum CollisionFlags : uint
CF_DISABLE_VISUALIZE_OBJECT = 1 << 5,
CF_DISABLE_SPU_COLLISION_PROCESS = 1 << 6,
// Following used by BulletSim to control collisions and updates
BS_SUBSCRIBE_COLLISION_EVENTS = 1 << 10,
BS_FLOATS_ON_WATER = 1 << 11,
BS_VEHICLE_COLLISIONS = 1 << 12,
BS_SUBSCRIBE_COLLISION_EVENTS = 1 << 10, // return collision events from unmanaged to managed
BS_FLOATS_ON_WATER = 1 << 11, // the object should float at water level
BS_VEHICLE_COLLISIONS = 1 << 12, // return collisions for vehicle ground checking
BS_RETURN_ROOT_COMPOUND_SHAPE = 1 << 13, // return the pos/rot of the root shape in a compound shape
BS_NONE = 0,
BS_ALL = 0xFFFFFFFF
};
@ -294,7 +298,7 @@ public abstract class BSAPITemplate
{
// Returns the name of the underlying Bullet engine
public abstract string BulletEngineName { get; }
public abstract string BulletEngineVersion { get; protected set;}
public abstract string BulletEngineVersion { get; protected set;}
// Initialization and simulation
public abstract BulletWorld Initialize(Vector3 maxPosition, ConfigurationParameters parms,
@ -305,7 +309,7 @@ public abstract BulletWorld Initialize(Vector3 maxPosition, ConfigurationParamet
public abstract int PhysicsStep(BulletWorld world, float timeStep, int maxSubSteps, float fixedTimeStep,
out int updatedEntityCount, out int collidersCount);
public abstract bool UpdateParameter(BulletWorld world, uint localID, String parm, float value);
public abstract bool UpdateParameter(BulletWorld world, UInt32 localID, String parm, float value);
public abstract void Shutdown(BulletWorld sim);
@ -320,7 +324,13 @@ public abstract BulletShape CreateMeshShape(BulletWorld world,
public abstract BulletShape CreateHullShape(BulletWorld world,
int hullCount, float[] hulls);
public abstract BulletShape BuildHullShapeFromMesh(BulletWorld world, BulletShape meshShape);
public abstract BulletShape BuildHullShapeFromMesh(BulletWorld world, BulletShape meshShape, HACDParams parms);
public abstract BulletShape BuildConvexHullShapeFromMesh(BulletWorld world, BulletShape meshShape);
public abstract BulletShape CreateConvexHullShape(BulletWorld world,
int indicesCount, int[] indices,
int verticesCount, float[] vertices );
public abstract BulletShape BuildNativeShape(BulletWorld world, ShapeData shapeData);
@ -342,26 +352,28 @@ public abstract BulletShape RemoveChildShapeFromCompoundShapeIndex(BulletShape c
public abstract void RemoveChildShapeFromCompoundShape(BulletShape cShape, BulletShape removeShape);
public abstract void UpdateChildTransform(BulletShape pShape, int childIndex, Vector3 pos, Quaternion rot, bool shouldRecalculateLocalAabb);
public abstract void RecalculateCompoundShapeLocalAabb(BulletShape cShape);
public abstract BulletShape DuplicateCollisionShape(BulletWorld sim, BulletShape srcShape, uint id);
public abstract BulletShape DuplicateCollisionShape(BulletWorld sim, BulletShape srcShape, UInt32 id);
public abstract bool DeleteCollisionShape(BulletWorld world, BulletShape shape);
public abstract CollisionObjectTypes GetBodyType(BulletBody obj);
public abstract BulletBody CreateBodyFromShape(BulletWorld sim, BulletShape shape, uint id, Vector3 pos, Quaternion rot);
public abstract BulletBody CreateBodyFromShape(BulletWorld sim, BulletShape shape, UInt32 id, Vector3 pos, Quaternion rot);
public abstract BulletBody CreateBodyWithDefaultMotionState(BulletShape shape, uint id, Vector3 pos, Quaternion rot);
public abstract BulletBody CreateBodyWithDefaultMotionState(BulletShape shape, UInt32 id, Vector3 pos, Quaternion rot);
public abstract BulletBody CreateGhostFromShape(BulletWorld sim, BulletShape shape, uint id, Vector3 pos, Quaternion rot);
public abstract BulletBody CreateGhostFromShape(BulletWorld sim, BulletShape shape, UInt32 id, Vector3 pos, Quaternion rot);
public abstract void DestroyObject(BulletWorld sim, BulletBody obj);
// =====================================================================================
public abstract BulletShape CreateGroundPlaneShape(uint id, float height, float collisionMargin);
public abstract BulletShape CreateGroundPlaneShape(UInt32 id, float height, float collisionMargin);
public abstract BulletShape CreateTerrainShape(uint id, Vector3 size, float minHeight, float maxHeight, float[] heightMap,
public abstract BulletShape CreateTerrainShape(UInt32 id, Vector3 size, float minHeight, float maxHeight, float[] heightMap,
float scaleFactor, float collisionMargin);
// =====================================================================================
@ -375,11 +387,38 @@ public abstract BulletConstraint Create6DofConstraintToPoint(BulletWorld world,
Vector3 joinPoint,
bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
public abstract BulletConstraint Create6DofConstraintFixed(BulletWorld world, BulletBody obj1,
Vector3 frameInBloc, Quaternion frameInBrot,
bool useLinearReferenceFrameB, bool disableCollisionsBetweenLinkedBodies);
public abstract BulletConstraint Create6DofSpringConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
Vector3 frame1loc, Quaternion frame1rot,
Vector3 frame2loc, Quaternion frame2rot,
bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
public abstract BulletConstraint CreateHingeConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
Vector3 pivotinA, Vector3 pivotinB,
Vector3 axisInA, Vector3 axisInB,
bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
public abstract BulletConstraint CreateSliderConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
Vector3 frameInAloc, Quaternion frameInArot,
Vector3 frameInBloc, Quaternion frameInBrot,
bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies);
public abstract BulletConstraint CreateConeTwistConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
Vector3 frameInAloc, Quaternion frameInArot,
Vector3 frameInBloc, Quaternion frameInBrot,
bool disableCollisionsBetweenLinkedBodies);
public abstract BulletConstraint CreateGearConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
Vector3 axisInA, Vector3 axisInB,
float ratio, bool disableCollisionsBetweenLinkedBodies);
public abstract BulletConstraint CreatePoint2PointConstraint(BulletWorld world, BulletBody obj1, BulletBody obj2,
Vector3 pivotInA, Vector3 pivotInB,
bool disableCollisionsBetweenLinkedBodies);
public abstract void SetConstraintEnable(BulletConstraint constrain, float numericTrueFalse);
public abstract void SetConstraintNumSolverIterations(BulletConstraint constrain, float iterations);
@ -607,7 +646,7 @@ public abstract BulletConstraint GetConstraintRef(BulletBody obj, int index);
public abstract int GetNumConstraintRefs(BulletBody obj);
public abstract bool SetCollisionGroupMask(BulletBody body, uint filter, uint mask);
public abstract bool SetCollisionGroupMask(BulletBody body, UInt32 filter, UInt32 mask);
// =====================================================================================
// btCollisionShape entries
@ -646,17 +685,21 @@ public abstract float GetMargin(BulletShape shape);
// =====================================================================================
// Debugging
public abstract void DumpRigidBody(BulletWorld sim, BulletBody collisionObject);
public virtual void DumpRigidBody(BulletWorld sim, BulletBody collisionObject) { }
public abstract void DumpCollisionShape(BulletWorld sim, BulletShape collisionShape);
public virtual void DumpCollisionShape(BulletWorld sim, BulletShape collisionShape) { }
public abstract void DumpConstraint(BulletWorld sim, BulletConstraint constrain);
public virtual void DumpConstraint(BulletWorld sim, BulletConstraint constrain) { }
public abstract void DumpActivationInfo(BulletWorld sim);
public virtual void DumpActivationInfo(BulletWorld sim) { }
public abstract void DumpAllInfo(BulletWorld sim);
public virtual void DumpAllInfo(BulletWorld sim) { }
public abstract void DumpPhysicsStatistics(BulletWorld sim);
public virtual void DumpPhysicsStatistics(BulletWorld sim) { }
public virtual void ResetBroadphasePool(BulletWorld sim) { }
public virtual void ResetConstraintSolver(BulletWorld sim) { }
};
}

View File

@ -45,11 +45,7 @@ public sealed class BSCharacter : BSPhysObject
private bool _selected;
private OMV.Vector3 _position;
private float _mass;
private float _avatarDensity;
private float _avatarVolume;
private OMV.Vector3 _force;
private OMV.Vector3 _velocity;
private OMV.Vector3 _torque;
private float _collisionScore;
private OMV.Vector3 _acceleration;
private OMV.Quaternion _orientation;
@ -58,25 +54,17 @@ public sealed class BSCharacter : BSPhysObject
private bool _flying;
private bool _setAlwaysRun;
private bool _throttleUpdates;
private bool _isColliding;
private bool _collidingObj;
private bool _floatOnWater;
private OMV.Vector3 _rotationalVelocity;
private bool _kinematic;
private float _buoyancy;
// The friction and velocity of the avatar is modified depending on whether walking or not.
private float _currentFriction; // the friction currently being used (changed by setVelocity).
private BSVMotor _velocityMotor;
private BSActorAvatarMove m_moveActor;
private const string AvatarMoveActorName = "BSCharacter.AvatarMove";
private OMV.Vector3 _PIDTarget;
private bool _usePID;
private float _PIDTau;
private bool _useHoverPID;
private float _PIDHoverHeight;
private PIDHoverType _PIDHoverType;
private float _PIDHoverTao;
public BSCharacter(uint localID, String avName, BSScene parent_scene, OMV.Vector3 pos, OMV.Vector3 size, bool isFlying)
: base(parent_scene, localID, avName, "BSCharacter")
@ -86,10 +74,10 @@ public sealed class BSCharacter : BSPhysObject
_flying = isFlying;
_orientation = OMV.Quaternion.Identity;
_velocity = OMV.Vector3.Zero;
RawVelocity = OMV.Vector3.Zero;
_buoyancy = ComputeBuoyancyFromFlying(isFlying);
_currentFriction = BSParam.AvatarStandingFriction;
_avatarDensity = BSParam.AvatarDensity;
Friction = BSParam.AvatarStandingFriction;
Density = BSParam.AvatarDensity / BSParam.DensityScaleFactor;
// Old versions of ScenePresence passed only the height. If width and/or depth are zero,
// replace with the default values.
@ -103,17 +91,22 @@ public sealed class BSCharacter : BSPhysObject
// set _avatarVolume and _mass based on capsule size, _density and Scale
ComputeAvatarVolumeAndMass();
SetupMovementMotor();
// The avatar's movement is controlled by this motor that speeds up and slows down
// the avatar seeking to reach the motor's target speed.
// This motor runs as a prestep action for the avatar so it will keep the avatar
// standing as well as moving. Destruction of the avatar will destroy the pre-step action.
m_moveActor = new BSActorAvatarMove(PhysScene, this, AvatarMoveActorName);
PhysicalActors.Add(AvatarMoveActorName, m_moveActor);
DetailLog("{0},BSCharacter.create,call,size={1},scale={2},density={3},volume={4},mass={5}",
LocalID, _size, Scale, _avatarDensity, _avatarVolume, RawMass);
LocalID, _size, Scale, Density, _avatarVolume, RawMass);
// do actual creation in taint time
PhysicsScene.TaintedObject("BSCharacter.create", delegate()
PhysScene.TaintedObject("BSCharacter.create", delegate()
{
DetailLog("{0},BSCharacter.create,taint", LocalID);
// New body and shape into PhysBody and PhysShape
PhysicsScene.Shapes.GetBodyAndShape(true, PhysicsScene.World, this);
PhysScene.Shapes.GetBodyAndShape(true, PhysScene.World, this);
SetPhysicalProperties();
});
@ -126,114 +119,63 @@ public sealed class BSCharacter : BSPhysObject
base.Destroy();
DetailLog("{0},BSCharacter.Destroy", LocalID);
PhysicsScene.TaintedObject("BSCharacter.destroy", delegate()
PhysScene.TaintedObject("BSCharacter.destroy", delegate()
{
PhysicsScene.Shapes.DereferenceBody(PhysBody, true, null);
PhysScene.Shapes.DereferenceBody(PhysBody, null /* bodyCallback */);
PhysBody.Clear();
PhysicsScene.Shapes.DereferenceShape(PhysShape, true, null);
PhysShape.Clear();
PhysShape.Dereference(PhysScene);
PhysShape = new BSShapeNull();
});
}
private void SetPhysicalProperties()
{
PhysicsScene.PE.RemoveObjectFromWorld(PhysicsScene.World, PhysBody);
PhysScene.PE.RemoveObjectFromWorld(PhysScene.World, PhysBody);
ZeroMotion(true);
ForcePosition = _position;
// Set the velocity and compute the proper friction
_velocityMotor.Reset();
_velocityMotor.SetTarget(_velocity);
_velocityMotor.SetCurrent(_velocity);
ForceVelocity = _velocity;
// Set the velocity
if (m_moveActor != null)
m_moveActor.SetVelocityAndTarget(RawVelocity, RawVelocity, false);
ForceVelocity = RawVelocity;
// This will enable or disable the flying buoyancy of the avatar.
// Needs to be reset especially when an avatar is recreated after crossing a region boundry.
Flying = _flying;
PhysicsScene.PE.SetRestitution(PhysBody, BSParam.AvatarRestitution);
PhysicsScene.PE.SetMargin(PhysShape, PhysicsScene.Params.collisionMargin);
PhysicsScene.PE.SetLocalScaling(PhysShape, Scale);
PhysicsScene.PE.SetContactProcessingThreshold(PhysBody, BSParam.ContactProcessingThreshold);
PhysScene.PE.SetRestitution(PhysBody, BSParam.AvatarRestitution);
PhysScene.PE.SetMargin(PhysShape.physShapeInfo, PhysScene.Params.collisionMargin);
PhysScene.PE.SetLocalScaling(PhysShape.physShapeInfo, Scale);
PhysScene.PE.SetContactProcessingThreshold(PhysBody, BSParam.ContactProcessingThreshold);
if (BSParam.CcdMotionThreshold > 0f)
{
PhysicsScene.PE.SetCcdMotionThreshold(PhysBody, BSParam.CcdMotionThreshold);
PhysicsScene.PE.SetCcdSweptSphereRadius(PhysBody, BSParam.CcdSweptSphereRadius);
PhysScene.PE.SetCcdMotionThreshold(PhysBody, BSParam.CcdMotionThreshold);
PhysScene.PE.SetCcdSweptSphereRadius(PhysBody, BSParam.CcdSweptSphereRadius);
}
UpdatePhysicalMassProperties(RawMass, false);
// Make so capsule does not fall over
PhysicsScene.PE.SetAngularFactorV(PhysBody, OMV.Vector3.Zero);
PhysScene.PE.SetAngularFactorV(PhysBody, OMV.Vector3.Zero);
PhysicsScene.PE.AddToCollisionFlags(PhysBody, CollisionFlags.CF_CHARACTER_OBJECT);
// The avatar mover sets some parameters.
PhysicalActors.Refresh();
PhysicsScene.PE.AddObjectToWorld(PhysicsScene.World, PhysBody);
PhysScene.PE.AddToCollisionFlags(PhysBody, CollisionFlags.CF_CHARACTER_OBJECT);
PhysScene.PE.AddObjectToWorld(PhysScene.World, PhysBody);
// PhysicsScene.PE.ForceActivationState(PhysBody, ActivationState.ACTIVE_TAG);
PhysicsScene.PE.ForceActivationState(PhysBody, ActivationState.DISABLE_DEACTIVATION);
PhysicsScene.PE.UpdateSingleAabb(PhysicsScene.World, PhysBody);
PhysScene.PE.ForceActivationState(PhysBody, ActivationState.DISABLE_DEACTIVATION);
PhysScene.PE.UpdateSingleAabb(PhysScene.World, PhysBody);
// Do this after the object has been added to the world
PhysBody.collisionType = CollisionType.Avatar;
PhysBody.ApplyCollisionMask(PhysicsScene);
PhysBody.ApplyCollisionMask(PhysScene);
}
// The avatar's movement is controlled by this motor that speeds up and slows down
// the avatar seeking to reach the motor's target speed.
// This motor runs as a prestep action for the avatar so it will keep the avatar
// standing as well as moving. Destruction of the avatar will destroy the pre-step action.
private void SetupMovementMotor()
{
// Someday, use a PID motor for asymmetric speed up and slow down
// _velocityMotor = new BSPIDVMotor("BSCharacter.Velocity", 3f, 5f, BSMotor.InfiniteVector, 1f);
// Infinite decay and timescale values so motor only changes current to target values.
_velocityMotor = new BSVMotor("BSCharacter.Velocity",
0.2f, // time scale
BSMotor.Infinite, // decay time scale
BSMotor.InfiniteVector, // friction timescale
1f // efficiency
);
// _velocityMotor.PhysicsScene = PhysicsScene; // DEBUG DEBUG so motor will output detail log messages.
RegisterPreStepAction("BSCharactor.Movement", LocalID, delegate(float timeStep)
{
// TODO: Decide if the step parameters should be changed depending on the avatar's
// state (flying, colliding, ...). There is code in ODE to do this.
OMV.Vector3 stepVelocity = _velocityMotor.Step(timeStep);
// If falling, we keep the world's downward vector no matter what the other axis specify.
if (!Flying && !IsColliding)
{
stepVelocity.Z = _velocity.Z;
// DetailLog("{0},BSCharacter.MoveMotor,taint,overrideStepZWithWorldZ,stepVel={1}", LocalID, stepVelocity);
}
// 'stepVelocity' is now the speed we'd like the avatar to move in. Turn that into an instantanous force.
OMV.Vector3 moveForce = (stepVelocity - _velocity) * Mass / PhysicsScene.LastTimeStep;
/*
// If moveForce is very small, zero things so we don't keep sending microscopic updates to the user
float moveForceMagnitudeSquared = moveForce.LengthSquared();
if (moveForceMagnitudeSquared < 0.0001)
{
DetailLog("{0},BSCharacter.MoveMotor,zeroMovement,stepVel={1},vel={2},mass={3},magSq={4},moveForce={5}",
LocalID, stepVelocity, _velocity, Mass, moveForceMagnitudeSquared, moveForce);
ForceVelocity = OMV.Vector3.Zero;
}
else
{
AddForce(moveForce, false, true);
}
*/
// DetailLog("{0},BSCharacter.MoveMotor,move,stepVel={1},vel={2},mass={3},moveForce={4}", LocalID, stepVelocity, _velocity, Mass, moveForce);
AddForce(moveForce, false, true);
});
}
public override void RequestPhysicsterseUpdate()
{
@ -259,16 +201,16 @@ public sealed class BSCharacter : BSPhysObject
Scale = ComputeAvatarScale(_size);
ComputeAvatarVolumeAndMass();
DetailLog("{0},BSCharacter.setSize,call,size={1},scale={2},density={3},volume={4},mass={5}",
LocalID, _size, Scale, _avatarDensity, _avatarVolume, RawMass);
LocalID, _size, Scale, Density, _avatarVolume, RawMass);
PhysicsScene.TaintedObject("BSCharacter.setSize", delegate()
PhysScene.TaintedObject("BSCharacter.setSize", delegate()
{
if (PhysBody.HasPhysicalBody && PhysShape.HasPhysicalShape)
if (PhysBody.HasPhysicalBody && PhysShape.physShapeInfo.HasPhysicalShape)
{
PhysicsScene.PE.SetLocalScaling(PhysShape, Scale);
PhysScene.PE.SetLocalScaling(PhysShape.physShapeInfo, Scale);
UpdatePhysicalMassProperties(RawMass, true);
// Make sure this change appears as a property update event
PhysicsScene.PE.PushUpdate(PhysBody);
PhysScene.PE.PushUpdate(PhysBody);
}
});
@ -279,11 +221,6 @@ public sealed class BSCharacter : BSPhysObject
{
set { BaseShape = value; }
}
// I want the physics engine to make an avatar capsule
public override BSPhysicsShapeType PreferredPhysicalShape
{
get {return BSPhysicsShapeType.SHAPE_CAPSULE; }
}
public override bool Grabbed {
set { _grabbed = value; }
@ -291,6 +228,10 @@ public sealed class BSCharacter : BSPhysObject
public override bool Selected {
set { _selected = value; }
}
public override bool IsSelected
{
get { return _selected; }
}
public override void CrossingFailure() { return; }
public override void link(PhysicsActor obj) { return; }
public override void delink() { return; }
@ -301,29 +242,29 @@ public sealed class BSCharacter : BSPhysObject
// Called at taint time!
public override void ZeroMotion(bool inTaintTime)
{
_velocity = OMV.Vector3.Zero;
RawVelocity = OMV.Vector3.Zero;
_acceleration = OMV.Vector3.Zero;
_rotationalVelocity = OMV.Vector3.Zero;
// Zero some other properties directly into the physics engine
PhysicsScene.TaintedObject(inTaintTime, "BSCharacter.ZeroMotion", delegate()
PhysScene.TaintedObject(inTaintTime, "BSCharacter.ZeroMotion", delegate()
{
if (PhysBody.HasPhysicalBody)
PhysicsScene.PE.ClearAllForces(PhysBody);
PhysScene.PE.ClearAllForces(PhysBody);
});
}
public override void ZeroAngularMotion(bool inTaintTime)
{
_rotationalVelocity = OMV.Vector3.Zero;
PhysicsScene.TaintedObject(inTaintTime, "BSCharacter.ZeroMotion", delegate()
PhysScene.TaintedObject(inTaintTime, "BSCharacter.ZeroMotion", delegate()
{
if (PhysBody.HasPhysicalBody)
{
PhysicsScene.PE.SetInterpolationAngularVelocity(PhysBody, OMV.Vector3.Zero);
PhysicsScene.PE.SetAngularVelocity(PhysBody, OMV.Vector3.Zero);
PhysScene.PE.SetInterpolationAngularVelocity(PhysBody, OMV.Vector3.Zero);
PhysScene.PE.SetAngularVelocity(PhysBody, OMV.Vector3.Zero);
// The next also get rid of applied linear force but the linear velocity is untouched.
PhysicsScene.PE.ClearForces(PhysBody);
PhysScene.PE.ClearForces(PhysBody);
}
});
}
@ -344,25 +285,26 @@ public sealed class BSCharacter : BSPhysObject
}
set {
_position = value;
PositionSanityCheck();
PhysicsScene.TaintedObject("BSCharacter.setPosition", delegate()
PhysScene.TaintedObject("BSCharacter.setPosition", delegate()
{
DetailLog("{0},BSCharacter.SetPosition,taint,pos={1},orient={2}", LocalID, _position, _orientation);
if (PhysBody.HasPhysicalBody)
PhysicsScene.PE.SetTranslation(PhysBody, _position, _orientation);
PositionSanityCheck();
ForcePosition = _position;
});
}
}
public override OMV.Vector3 ForcePosition {
get {
_position = PhysicsScene.PE.GetPosition(PhysBody);
_position = PhysScene.PE.GetPosition(PhysBody);
return _position;
}
set {
_position = value;
PositionSanityCheck();
PhysicsScene.PE.SetTranslation(PhysBody, _position, _orientation);
if (PhysBody.HasPhysicalBody)
{
PhysScene.PE.SetTranslation(PhysBody, _position, _orientation);
}
}
}
@ -375,25 +317,27 @@ public sealed class BSCharacter : BSPhysObject
bool ret = false;
// TODO: check for out of bounds
if (!PhysicsScene.TerrainManager.IsWithinKnownTerrain(_position))
if (!PhysScene.TerrainManager.IsWithinKnownTerrain(RawPosition))
{
// The character is out of the known/simulated area.
// Upper levels of code will handle the transition to other areas so, for
// the time, we just ignore the position.
return ret;
// Force the avatar position to be within known. ScenePresence will use the position
// plus the velocity to decide if the avatar is moving out of the region.
RawPosition = PhysScene.TerrainManager.ClampPositionIntoKnownTerrain(RawPosition);
DetailLog("{0},BSCharacter.PositionSanityCheck,notWithinKnownTerrain,clampedPos={1}", LocalID, RawPosition);
return true;
}
// If below the ground, move the avatar up
float terrainHeight = PhysicsScene.TerrainManager.GetTerrainHeightAtXYZ(_position);
float terrainHeight = PhysScene.TerrainManager.GetTerrainHeightAtXYZ(RawPosition);
if (Position.Z < terrainHeight)
{
DetailLog("{0},BSCharacter.PositionAdjustUnderGround,call,pos={1},terrain={2}", LocalID, _position, terrainHeight);
_position.Z = terrainHeight + 2.0f;
DetailLog("{0},BSCharacter.PositionSanityCheck,adjustForUnderGround,pos={1},terrain={2}", LocalID, _position, terrainHeight);
_position.Z = terrainHeight + BSParam.AvatarBelowGroundUpCorrectionMeters;
ret = true;
}
if ((CurrentCollisionFlags & CollisionFlags.BS_FLOATS_ON_WATER) != 0)
{
float waterHeight = PhysicsScene.TerrainManager.GetWaterLevelAtXYZ(_position);
float waterHeight = PhysScene.TerrainManager.GetWaterLevelAtXYZ(_position);
if (Position.Z < waterHeight)
{
_position.Z = waterHeight;
@ -414,11 +358,10 @@ public sealed class BSCharacter : BSPhysObject
{
// The new position value must be pushed into the physics engine but we can't
// just assign to "Position" because of potential call loops.
PhysicsScene.TaintedObject(inTaintTime, "BSCharacter.PositionSanityCheck", delegate()
PhysScene.TaintedObject(inTaintTime, "BSCharacter.PositionSanityCheck", delegate()
{
DetailLog("{0},BSCharacter.PositionSanityCheck,taint,pos={1},orient={2}", LocalID, _position, _orientation);
if (PhysBody.HasPhysicalBody)
PhysicsScene.PE.SetTranslation(PhysBody, _position, _orientation);
ForcePosition = _position;
});
ret = true;
}
@ -428,25 +371,25 @@ public sealed class BSCharacter : BSPhysObject
public override float Mass { get { return _mass; } }
// used when we only want this prim's mass and not the linkset thing
public override float RawMass {
public override float RawMass {
get {return _mass; }
}
public override void UpdatePhysicalMassProperties(float physMass, bool inWorld)
{
OMV.Vector3 localInertia = PhysicsScene.PE.CalculateLocalInertia(PhysShape, physMass);
PhysicsScene.PE.SetMassProps(PhysBody, physMass, localInertia);
OMV.Vector3 localInertia = PhysScene.PE.CalculateLocalInertia(PhysShape.physShapeInfo, physMass);
PhysScene.PE.SetMassProps(PhysBody, physMass, localInertia);
}
public override OMV.Vector3 Force {
get { return _force; }
get { return RawForce; }
set {
_force = value;
RawForce = value;
// m_log.DebugFormat("{0}: Force = {1}", LogHeader, _force);
PhysicsScene.TaintedObject("BSCharacter.SetForce", delegate()
PhysScene.TaintedObject("BSCharacter.SetForce", delegate()
{
DetailLog("{0},BSCharacter.setForce,taint,force={1}", LocalID, _force);
DetailLog("{0},BSCharacter.setForce,taint,force={1}", LocalID, RawForce);
if (PhysBody.HasPhysicalBody)
PhysicsScene.PE.SetObjectForce(PhysBody, _force);
PhysScene.PE.SetObjectForce(PhysBody, RawForce);
});
}
}
@ -469,77 +412,49 @@ public sealed class BSCharacter : BSPhysObject
{
get
{
return _velocityMotor.TargetValue;
return base.m_targetVelocity;
}
set
{
DetailLog("{0},BSCharacter.setTargetVelocity,call,vel={1}", LocalID, value);
m_targetVelocity = value;
OMV.Vector3 targetVel = value;
if (_setAlwaysRun)
targetVel *= BSParam.AvatarAlwaysRunFactor;
targetVel *= new OMV.Vector3(BSParam.AvatarAlwaysRunFactor, BSParam.AvatarAlwaysRunFactor, 0f);
PhysicsScene.TaintedObject("BSCharacter.setTargetVelocity", delegate()
{
_velocityMotor.Reset();
_velocityMotor.SetTarget(targetVel);
_velocityMotor.SetCurrent(_velocity);
_velocityMotor.Enabled = true;
});
if (m_moveActor != null)
m_moveActor.SetVelocityAndTarget(RawVelocity, targetVel, false /* inTaintTime */);
}
}
// Directly setting velocity means this is what the user really wants now.
public override OMV.Vector3 Velocity {
get { return _velocity; }
get { return RawVelocity; }
set {
_velocity = value;
// m_log.DebugFormat("{0}: set velocity = {1}", LogHeader, _velocity);
PhysicsScene.TaintedObject("BSCharacter.setVelocity", delegate()
RawVelocity = value;
// m_log.DebugFormat("{0}: set velocity = {1}", LogHeader, RawVelocity);
PhysScene.TaintedObject("BSCharacter.setVelocity", delegate()
{
_velocityMotor.Reset();
_velocityMotor.SetCurrent(_velocity);
_velocityMotor.SetTarget(_velocity);
// Even though the motor is initialized, it's not used and the velocity goes straight into the avatar.
_velocityMotor.Enabled = false;
if (m_moveActor != null)
m_moveActor.SetVelocityAndTarget(RawVelocity, RawVelocity, true /* inTaintTime */);
DetailLog("{0},BSCharacter.setVelocity,taint,vel={1}", LocalID, _velocity);
ForceVelocity = _velocity;
DetailLog("{0},BSCharacter.setVelocity,taint,vel={1}", LocalID, RawVelocity);
ForceVelocity = RawVelocity;
});
}
}
public override OMV.Vector3 ForceVelocity {
get { return _velocity; }
get { return RawVelocity; }
set {
PhysicsScene.AssertInTaintTime("BSCharacter.ForceVelocity");
PhysScene.AssertInTaintTime("BSCharacter.ForceVelocity");
_velocity = value;
// Depending on whether the avatar is moving or not, change the friction
// to keep the avatar from slipping around
if (_velocity.Length() == 0)
{
if (_currentFriction != BSParam.AvatarStandingFriction)
{
_currentFriction = BSParam.AvatarStandingFriction;
if (PhysBody.HasPhysicalBody)
PhysicsScene.PE.SetFriction(PhysBody, _currentFriction);
}
}
else
{
if (_currentFriction != BSParam.AvatarFriction)
{
_currentFriction = BSParam.AvatarFriction;
if (PhysBody.HasPhysicalBody)
PhysicsScene.PE.SetFriction(PhysBody, _currentFriction);
}
}
PhysicsScene.PE.SetLinearVelocity(PhysBody, _velocity);
PhysicsScene.PE.Activate(PhysBody, true);
RawVelocity = value;
PhysScene.PE.SetLinearVelocity(PhysBody, RawVelocity);
PhysScene.PE.Activate(PhysBody, true);
}
}
public override OMV.Vector3 Torque {
get { return _torque; }
set { _torque = value;
get { return RawTorque; }
set { RawTorque = value;
}
}
public override float CollisionScore {
@ -564,7 +479,7 @@ public sealed class BSCharacter : BSPhysObject
if (_orientation != value)
{
_orientation = value;
PhysicsScene.TaintedObject("BSCharacter.setOrientation", delegate()
PhysScene.TaintedObject("BSCharacter.setOrientation", delegate()
{
ForceOrientation = _orientation;
});
@ -576,7 +491,7 @@ public sealed class BSCharacter : BSPhysObject
{
get
{
_orientation = PhysicsScene.PE.GetOrientation(PhysBody);
_orientation = PhysScene.PE.GetOrientation(PhysBody);
return _orientation;
}
set
@ -585,7 +500,7 @@ public sealed class BSCharacter : BSPhysObject
if (PhysBody.HasPhysicalBody)
{
// _position = PhysicsScene.PE.GetPosition(BSBody);
PhysicsScene.PE.SetTranslation(PhysBody, _position, _orientation);
PhysScene.PE.SetTranslation(PhysBody, _position, _orientation);
}
}
}
@ -605,6 +520,9 @@ public sealed class BSCharacter : BSPhysObject
public override bool IsStatic {
get { return false; }
}
public override bool IsPhysicallyActive {
get { return true; }
}
public override bool Flying {
get { return _flying; }
set {
@ -631,14 +549,14 @@ public sealed class BSCharacter : BSPhysObject
public override bool FloatOnWater {
set {
_floatOnWater = value;
PhysicsScene.TaintedObject("BSCharacter.setFloatOnWater", delegate()
PhysScene.TaintedObject("BSCharacter.setFloatOnWater", delegate()
{
if (PhysBody.HasPhysicalBody)
{
if (_floatOnWater)
CurrentCollisionFlags = PhysicsScene.PE.AddToCollisionFlags(PhysBody, CollisionFlags.BS_FLOATS_ON_WATER);
CurrentCollisionFlags = PhysScene.PE.AddToCollisionFlags(PhysBody, CollisionFlags.BS_FLOATS_ON_WATER);
else
CurrentCollisionFlags = PhysicsScene.PE.RemoveFromCollisionFlags(PhysBody, CollisionFlags.BS_FLOATS_ON_WATER);
CurrentCollisionFlags = PhysScene.PE.RemoveFromCollisionFlags(PhysBody, CollisionFlags.BS_FLOATS_ON_WATER);
}
});
}
@ -659,7 +577,7 @@ public sealed class BSCharacter : BSPhysObject
public override float Buoyancy {
get { return _buoyancy; }
set { _buoyancy = value;
PhysicsScene.TaintedObject("BSCharacter.setBuoyancy", delegate()
PhysScene.TaintedObject("BSCharacter.setBuoyancy", delegate()
{
DetailLog("{0},BSCharacter.setBuoyancy,taint,buoy={1}", LocalID, _buoyancy);
ForceBuoyancy = _buoyancy;
@ -668,15 +586,16 @@ public sealed class BSCharacter : BSPhysObject
}
public override float ForceBuoyancy {
get { return _buoyancy; }
set {
PhysicsScene.AssertInTaintTime("BSCharacter.ForceBuoyancy");
set {
PhysScene.AssertInTaintTime("BSCharacter.ForceBuoyancy");
_buoyancy = value;
DetailLog("{0},BSCharacter.setForceBuoyancy,taint,buoy={1}", LocalID, _buoyancy);
// Buoyancy is faked by changing the gravity applied to the object
float grav = PhysicsScene.Params.gravity * (1f - _buoyancy);
float grav = BSParam.Gravity * (1f - _buoyancy);
Gravity = new OMV.Vector3(0f, 0f, grav);
if (PhysBody.HasPhysicalBody)
PhysicsScene.PE.SetGravity(PhysBody, new OMV.Vector3(0f, 0f, grav));
PhysScene.PE.SetGravity(PhysBody, Gravity);
}
}
@ -691,53 +610,25 @@ public sealed class BSCharacter : BSPhysObject
set { _PIDTau = value; }
}
// Used for llSetHoverHeight and maybe vehicle height
// Hover Height will override MoveTo target's Z
public override bool PIDHoverActive {
set { _useHoverPID = value; }
}
public override float PIDHoverHeight {
set { _PIDHoverHeight = value; }
}
public override PIDHoverType PIDHoverType {
set { _PIDHoverType = value; }
}
public override float PIDHoverTau {
set { _PIDHoverTao = value; }
}
// For RotLookAt
public override OMV.Quaternion APIDTarget { set { return; } }
public override bool APIDActive { set { return; } }
public override float APIDStrength { set { return; } }
public override float APIDDamping { set { return; } }
public override void AddForce(OMV.Vector3 force, bool pushforce)
{
// Since this force is being applied in only one step, make this a force per second.
OMV.Vector3 addForce = force / PhysicsScene.LastTimeStep;
OMV.Vector3 addForce = force / PhysScene.LastTimeStep;
AddForce(addForce, pushforce, false);
}
private void AddForce(OMV.Vector3 force, bool pushforce, bool inTaintTime) {
if (force.IsFinite())
{
float magnitude = force.Length();
if (magnitude > BSParam.MaxAddForceMagnitude)
{
// Force has a limit
force = force / magnitude * BSParam.MaxAddForceMagnitude;
}
OMV.Vector3 addForce = force;
OMV.Vector3 addForce = Util.ClampV(force, BSParam.MaxAddForceMagnitude);
// DetailLog("{0},BSCharacter.addForce,call,force={1}", LocalID, addForce);
PhysicsScene.TaintedObject(inTaintTime, "BSCharacter.AddForce", delegate()
PhysScene.TaintedObject(inTaintTime, "BSCharacter.AddForce", delegate()
{
// Bullet adds this central force to the total force for this tick
// DetailLog("{0},BSCharacter.addForce,taint,force={1}", LocalID, addForce);
if (PhysBody.HasPhysicalBody)
{
PhysicsScene.PE.ApplyCentralForce(PhysBody, addForce);
PhysScene.PE.ApplyCentralForce(PhysBody, addForce);
}
});
}
@ -748,7 +639,7 @@ public sealed class BSCharacter : BSPhysObject
}
}
public override void AddAngularForce(OMV.Vector3 force, bool pushforce) {
public override void AddAngularForce(OMV.Vector3 force, bool pushforce, bool inTaintTime) {
}
public override void SetMomentum(OMV.Vector3 momentum) {
}
@ -756,7 +647,7 @@ public sealed class BSCharacter : BSPhysObject
private OMV.Vector3 ComputeAvatarScale(OMV.Vector3 size)
{
OMV.Vector3 newScale;
// Bullet's capsule total height is the "passed height + radius * 2";
// The base capsule is 1 diameter and 2 height (passed radius=0.5, passed height = 1)
// The number we pass in for 'scaling' is the multiplier to get that base
@ -794,34 +685,48 @@ public sealed class BSCharacter : BSPhysObject
* Math.Min(Size.X, Size.Y) / 2
* Size.Y / 2f // plus the volume of the capsule end caps
);
_mass = _avatarDensity * _avatarVolume;
_mass = Density * BSParam.DensityScaleFactor * _avatarVolume;
}
// The physics engine says that properties have updated. Update same and inform
// the world that things have changed.
public override void UpdateProperties(EntityProperties entprop)
{
_position = entprop.Position;
// Don't change position if standing on a stationary object.
if (!IsStationary)
_position = entprop.Position;
_orientation = entprop.Rotation;
_velocity = entprop.Velocity;
// Smooth velocity. OpenSimulator is VERY sensitive to changes in velocity of the avatar
// and will send agent updates to the clients if velocity changes by more than
// 0.001m/s. Bullet introduces a lot of jitter in the velocity which causes many
// extra updates.
if (!entprop.Velocity.ApproxEquals(RawVelocity, 0.1f))
RawVelocity = entprop.Velocity;
_acceleration = entprop.Acceleration;
_rotationalVelocity = entprop.RotationalVelocity;
// Do some sanity checking for the avatar. Make sure it's above ground and inbounds.
PositionSanityCheck(true);
if (PositionSanityCheck(true))
{
DetailLog("{0},BSCharacter.UpdateProperties,updatePosForSanity,pos={1}", LocalID, _position);
entprop.Position = _position;
}
// remember the current and last set values
LastEntityProperties = CurrentEntityProperties;
CurrentEntityProperties = entprop;
// Tell the linkset about value changes
Linkset.UpdateProperties(this, true);
// Linkset.UpdateProperties(UpdatedProperties.EntPropUpdates, this);
// Avatars don't report their changes the usual way. Changes are checked for in the heartbeat loop.
// base.RequestPhysicsterseUpdate();
DetailLog("{0},BSCharacter.UpdateProperties,call,pos={1},orient={2},vel={3},accel={4},rotVel={5}",
LocalID, _position, _orientation, _velocity, _acceleration, _rotationalVelocity);
LocalID, _position, _orientation, RawVelocity, _acceleration, _rotationalVelocity);
}
}
}

View File

@ -85,7 +85,9 @@ public abstract class BSConstraint : IDisposable
{
bool ret = false;
if (m_enabled)
{
ret = PhysicsScene.PE.SetAngularLimits(m_constraint, low, high);
}
return ret;
}

View File

@ -57,6 +57,7 @@ public sealed class BSConstraint6Dof : BSConstraint
obj1.ID, obj1.AddrString, obj2.ID, obj2.AddrString);
}
// 6 Dof constraint based on a midpoint between the two constrained bodies
public BSConstraint6Dof(BulletWorld world, BulletBody obj1, BulletBody obj2,
Vector3 joinPoint,
bool useLinearReferenceFrameA, bool disableCollisionsBetweenLinkedBodies)
@ -94,6 +95,21 @@ public sealed class BSConstraint6Dof : BSConstraint
}
}
// A 6 Dof constraint that is fixed in the world and constrained to a on-the-fly created static object
public BSConstraint6Dof(BulletWorld world, BulletBody obj1, Vector3 frameInBloc, Quaternion frameInBrot,
bool useLinearReferenceFrameB, bool disableCollisionsBetweenLinkedBodies)
: base(world)
{
m_body1 = obj1;
m_body2 = obj1; // Look out for confusion down the road
m_constraint = PhysicsScene.PE.Create6DofConstraintFixed(m_world, m_body1,
frameInBloc, frameInBrot,
useLinearReferenceFrameB, disableCollisionsBetweenLinkedBodies);
m_enabled = true;
world.physicsScene.DetailLog("{0},BS6DofConstraint,createFixed,wID={1},rID={2},rBody={3}",
BSScene.DetailLogZero, world.worldID, obj1.ID, obj1.AddrString);
}
public bool SetFrames(Vector3 frameA, Quaternion frameArot, Vector3 frameB, Quaternion frameBrot)
{
bool ret = false;

View File

@ -117,8 +117,7 @@ public sealed class BSConstraintCollection : IDisposable
if (this.TryGetConstraint(body1, body2, out constrain))
{
// remove the constraint from our collection
RemoveAndDestroyConstraint(constrain);
ret = true;
ret = RemoveAndDestroyConstraint(constrain);
}
}
@ -126,17 +125,19 @@ public sealed class BSConstraintCollection : IDisposable
}
// The constraint MUST exist in the collection
// Could be called if the constraint was previously removed.
// Return 'true' if the constraint was actually removed and disposed.
public bool RemoveAndDestroyConstraint(BSConstraint constrain)
{
bool removed = false;
lock (m_constraints)
{
// remove the constraint from our collection
m_constraints.Remove(constrain);
removed = m_constraints.Remove(constrain);
}
// tell the engine that all its structures need to be freed
// Dispose() is safe to call multiple times
constrain.Dispose();
// we destroyed something
return true;
return removed;
}
// Remove all constraints that reference the passed body.

View File

@ -45,7 +45,7 @@ public sealed class BSConstraintHinge : BSConstraint
m_body1 = obj1;
m_body2 = obj2;
m_constraint = PhysicsScene.PE.CreateHingeConstraint(world, obj1, obj2,
pivotInA, pivotInB, axisInA, axisInB,
pivotInA, pivotInB, axisInA, axisInB,
useLinearReferenceFrameA, disableCollisionsBetweenLinkedBodies);
m_enabled = true;
}

File diff suppressed because it is too large Load Diff

View File

@ -52,7 +52,7 @@ public abstract class BSLinkset
Manual = 2 // linkset tied together manually (code moves all the pieces)
}
// Create the correct type of linkset for this child
public static BSLinkset Factory(BSScene physScene, BSPhysObject parent)
public static BSLinkset Factory(BSScene physScene, BSPrimLinkable parent)
{
BSLinkset ret = null;
@ -71,31 +71,28 @@ public abstract class BSLinkset
ret = new BSLinksetCompound(physScene, parent);
break;
}
if (ret == null)
{
physScene.Logger.ErrorFormat("[BULLETSIM LINKSET] Factory could not create linkset. Parent name={1}, ID={2}", parent.Name, parent.LocalID);
}
return ret;
}
public BSPhysObject LinksetRoot { get; protected set; }
public BSPrimLinkable LinksetRoot { get; protected set; }
public BSScene PhysicsScene { get; private set; }
protected BSScene m_physicsScene { get; private set; }
static int m_nextLinksetID = 1;
public int LinksetID { get; private set; }
// The children under the root in this linkset.
protected HashSet<BSPhysObject> m_children;
protected HashSet<BSPrimLinkable> m_children;
// We lock the diddling of linkset classes to prevent any badness.
// This locks the modification of the instances of this class. Changes
// to the physical representation is done via the tainting mechenism.
protected object m_linksetActivityLock = new Object();
// Some linksets have a preferred physical shape.
// Returns SHAPE_UNKNOWN if there is no preference. Causes the correct shape to be selected.
public virtual BSPhysicsShapeType PreferredPhysicalShape(BSPhysObject requestor)
{
return BSPhysicsShapeType.SHAPE_UNKNOWN;
}
// We keep the prim's mass in the linkset structure since it could be dependent on other prims
public float LinksetMass { get; protected set; }
@ -111,25 +108,27 @@ public abstract class BSLinkset
get { return ComputeLinksetGeometricCenter(); }
}
protected BSLinkset(BSScene scene, BSPhysObject parent)
protected BSLinkset(BSScene scene, BSPrimLinkable parent)
{
// A simple linkset of one (no children)
LinksetID = m_nextLinksetID++;
// We create LOTS of linksets.
if (m_nextLinksetID <= 0)
m_nextLinksetID = 1;
PhysicsScene = scene;
m_physicsScene = scene;
LinksetRoot = parent;
m_children = new HashSet<BSPhysObject>();
m_children = new HashSet<BSPrimLinkable>();
LinksetMass = parent.RawMass;
Rebuilding = false;
parent.ClearDisplacement();
}
// Link to a linkset where the child knows the parent.
// Parent changing should not happen so do some sanity checking.
// We return the parent's linkset so the child can track its membership.
// Called at runtime.
public BSLinkset AddMeToLinkset(BSPhysObject child)
public BSLinkset AddMeToLinkset(BSPrimLinkable child)
{
lock (m_linksetActivityLock)
{
@ -145,7 +144,7 @@ public abstract class BSLinkset
// Returns a new linkset for the child which is a linkset of one (just the
// orphened child).
// Called at runtime.
public BSLinkset RemoveMeFromLinkset(BSPhysObject child)
public BSLinkset RemoveMeFromLinkset(BSPrimLinkable child)
{
lock (m_linksetActivityLock)
{
@ -159,11 +158,11 @@ public abstract class BSLinkset
}
// The child is down to a linkset of just itself
return BSLinkset.Factory(PhysicsScene, child);
return BSLinkset.Factory(m_physicsScene, child);
}
// Return 'true' if the passed object is the root object of this linkset
public bool IsRoot(BSPhysObject requestor)
public bool IsRoot(BSPrimLinkable requestor)
{
return (requestor.LocalID == LinksetRoot.LocalID);
}
@ -174,14 +173,14 @@ public abstract class BSLinkset
public bool HasAnyChildren { get { return (m_children.Count > 0); } }
// Return 'true' if this child is in this linkset
public bool HasChild(BSPhysObject child)
public bool HasChild(BSPrimLinkable child)
{
bool ret = false;
lock (m_linksetActivityLock)
{
ret = m_children.Contains(child);
/* Safer version but the above should work
foreach (BSPhysObject bp in m_children)
foreach (BSPrimLinkable bp in m_children)
{
if (child.LocalID == bp.LocalID)
{
@ -196,14 +195,14 @@ public abstract class BSLinkset
// Perform an action on each member of the linkset including root prim.
// Depends on the action on whether this should be done at taint time.
public delegate bool ForEachMemberAction(BSPhysObject obj);
public delegate bool ForEachMemberAction(BSPrimLinkable obj);
public virtual bool ForEachMember(ForEachMemberAction action)
{
bool ret = false;
lock (m_linksetActivityLock)
{
action(LinksetRoot);
foreach (BSPhysObject po in m_children)
foreach (BSPrimLinkable po in m_children)
{
if (action(po))
break;
@ -214,16 +213,16 @@ public abstract class BSLinkset
// I am the root of a linkset and a new child is being added
// Called while LinkActivity is locked.
protected abstract void AddChildToLinkset(BSPhysObject child);
protected abstract void AddChildToLinkset(BSPrimLinkable child);
// I am the root of a linkset and one of my children is being removed.
// Safe to call even if the child is not really in my linkset.
protected abstract void RemoveChildFromLinkset(BSPhysObject child);
protected abstract void RemoveChildFromLinkset(BSPrimLinkable child);
// When physical properties are changed the linkset needs to recalculate
// its internal properties.
// May be called at runtime or taint-time.
public virtual void Refresh(BSPhysObject requestor)
public virtual void Refresh(BSPrimLinkable requestor)
{
LinksetMass = ComputeLinksetMass();
}
@ -238,31 +237,26 @@ public abstract class BSLinkset
// has not yet been fully constructed.
// Return 'true' if any properties updated on the passed object.
// Called at taint-time!
public abstract bool MakeDynamic(BSPhysObject child);
public abstract bool MakeDynamic(BSPrimLinkable child);
// The object is going static (non-physical). Do any setup necessary
// for a static linkset.
// Return 'true' if any properties updated on the passed object.
// Called at taint-time!
public abstract bool MakeStatic(BSPhysObject child);
public abstract bool MakeStatic(BSPrimLinkable child);
// Called when a parameter update comes from the physics engine for any object
// of the linkset is received.
// Passed flag is update came from physics engine (true) or the user (false).
// Called at taint-time!!
public abstract void UpdateProperties(BSPhysObject physObject, bool physicalUpdate);
public abstract void UpdateProperties(UpdatedProperties whichUpdated, BSPrimLinkable physObject);
// Routine used when rebuilding the body of the root of the linkset
// Destroy all the constraints have have been made to root.
// This is called when the root body is changing.
// Returns 'true' of something was actually removed and would need restoring
// Called at taint-time!!
public abstract bool RemoveBodyDependencies(BSPrim child);
// Companion to RemoveBodyDependencies(). If RemoveBodyDependencies() returns 'true',
// this routine will restore the removed constraints.
// Called at taint-time!!
public abstract void RestoreBodyDependencies(BSPrim child);
public abstract bool RemoveDependencies(BSPrimLinkable child);
// ================================================================
protected virtual float ComputeLinksetMass()
@ -272,7 +266,7 @@ public abstract class BSLinkset
{
lock (m_linksetActivityLock)
{
foreach (BSPhysObject bp in m_children)
foreach (BSPrimLinkable bp in m_children)
{
mass += bp.RawMass;
}
@ -281,6 +275,7 @@ public abstract class BSLinkset
return mass;
}
// Computes linkset's center of mass in world coordinates.
protected virtual OMV.Vector3 ComputeLinksetCenterOfMass()
{
OMV.Vector3 com;
@ -289,7 +284,7 @@ public abstract class BSLinkset
com = LinksetRoot.Position * LinksetRoot.RawMass;
float totalMass = LinksetRoot.RawMass;
foreach (BSPhysObject bp in m_children)
foreach (BSPrimLinkable bp in m_children)
{
com += bp.Position * bp.RawMass;
totalMass += bp.RawMass;
@ -308,9 +303,9 @@ public abstract class BSLinkset
{
com = LinksetRoot.Position;
foreach (BSPhysObject bp in m_children)
foreach (BSPrimLinkable bp in m_children)
{
com += bp.Position * bp.RawMass;
com += bp.Position;
}
com /= (m_children.Count + 1);
}
@ -321,8 +316,8 @@ public abstract class BSLinkset
// Invoke the detailed logger and output something if it's enabled.
protected void DetailLog(string msg, params Object[] args)
{
if (PhysicsScene.PhysicsLogging.Enabled)
PhysicsScene.DetailLog(msg, args);
if (m_physicsScene.PhysicsLogging.Enabled)
m_physicsScene.DetailLog(msg, args);
}
}

View File

@ -35,59 +35,74 @@ using OMV = OpenMetaverse;
namespace OpenSim.Region.Physics.BulletSPlugin
{
/*
// When a child is linked, the relationship position of the child to the parent
// is remembered so the child's world position can be recomputed when it is
// removed from the linkset.
sealed class BSLinksetCompoundInfo : BSLinksetInfo
{
public OMV.Vector3 OffsetPos;
public int Index;
public OMV.Vector3 OffsetFromRoot;
public OMV.Vector3 OffsetFromCenterOfMass;
public OMV.Quaternion OffsetRot;
public BSLinksetCompoundInfo(OMV.Vector3 p, OMV.Quaternion r)
public BSLinksetCompoundInfo(int indx, OMV.Vector3 p, OMV.Quaternion r)
{
OffsetPos = p;
Index = indx;
OffsetFromRoot = p;
OffsetFromCenterOfMass = p;
OffsetRot = r;
}
// 'centerDisplacement' is the distance from the root the the center-of-mass (Bullet 'zero' of the shape)
public BSLinksetCompoundInfo(int indx, BSPrimLinkable root, BSPrimLinkable child, OMV.Vector3 centerDisplacement)
{
// Each child position and rotation is given relative to the center-of-mass.
OMV.Quaternion invRootOrientation = OMV.Quaternion.Inverse(root.RawOrientation);
OMV.Vector3 displacementFromRoot = (child.RawPosition - root.RawPosition) * invRootOrientation;
OMV.Vector3 displacementFromCOM = displacementFromRoot - centerDisplacement;
OMV.Quaternion displacementRot = child.RawOrientation * invRootOrientation;
// Save relative position for recomputing child's world position after moving linkset.
Index = indx;
OffsetFromRoot = displacementFromRoot;
OffsetFromCenterOfMass = displacementFromCOM;
OffsetRot = displacementRot;
}
public override void Clear()
{
OffsetPos = OMV.Vector3.Zero;
Index = 0;
OffsetFromRoot = OMV.Vector3.Zero;
OffsetFromCenterOfMass = OMV.Vector3.Zero;
OffsetRot = OMV.Quaternion.Identity;
}
public override string ToString()
{
StringBuilder buff = new StringBuilder();
buff.Append("<p=");
buff.Append(OffsetPos.ToString());
buff.Append("<i=");
buff.Append(Index.ToString());
buff.Append(",p=");
buff.Append(OffsetFromRoot.ToString());
buff.Append(",m=");
buff.Append(OffsetFromCenterOfMass.ToString());
buff.Append(",r=");
buff.Append(OffsetRot.ToString());
buff.Append(">");
return buff.ToString();
}
};
*/
public sealed class BSLinksetCompound : BSLinkset
{
private static string LogHeader = "[BULLETSIM LINKSET COMPOUND]";
public BSLinksetCompound(BSScene scene, BSPhysObject parent) : base(scene, parent)
public BSLinksetCompound(BSScene scene, BSPrimLinkable parent)
: base(scene, parent)
{
}
// For compound implimented linksets, if there are children, use compound shape for the root.
public override BSPhysicsShapeType PreferredPhysicalShape(BSPhysObject requestor)
{
// Returning 'unknown' means we don't have a preference.
BSPhysicsShapeType ret = BSPhysicsShapeType.SHAPE_UNKNOWN;
if (IsRoot(requestor) && HasAnyChildren)
{
ret = BSPhysicsShapeType.SHAPE_COMPOUND;
}
// DetailLog("{0},BSLinksetCompound.PreferredPhysicalShape,call,shape={1}", LinksetRoot.LocalID, ret);
return ret;
}
// When physical properties are changed the linkset needs to recalculate
// its internal properties.
public override void Refresh(BSPhysObject requestor)
public override void Refresh(BSPrimLinkable requestor)
{
base.Refresh(requestor);
@ -96,16 +111,16 @@ public sealed class BSLinksetCompound : BSLinkset
}
// Schedule a refresh to happen after all the other taint processing.
private void ScheduleRebuild(BSPhysObject requestor)
private void ScheduleRebuild(BSPrimLinkable requestor)
{
DetailLog("{0},BSLinksetCompound.ScheduleRebuild,,rebuilding={1},hasChildren={2}",
requestor.LocalID, Rebuilding, HasAnyChildren);
DetailLog("{0},BSLinksetCompound.ScheduleRebuild,,rebuilding={1},hasChildren={2},actuallyScheduling={3}",
requestor.LocalID, Rebuilding, HasAnyChildren, (!Rebuilding && HasAnyChildren));
// When rebuilding, it is possible to set properties that would normally require a rebuild.
// If already rebuilding, don't request another rebuild.
// If a linkset with just a root prim (simple non-linked prim) don't bother rebuilding.
if (!Rebuilding && HasAnyChildren)
{
PhysicsScene.PostTaintObject("BSLinksetCompound.ScheduleRebuild", LinksetRoot.LocalID, delegate()
m_physicsScene.PostTaintObject("BSLinksetCompound.ScheduleRebuild", LinksetRoot.LocalID, delegate()
{
if (HasAnyChildren)
RecomputeLinksetCompound();
@ -118,7 +133,7 @@ public sealed class BSLinksetCompound : BSLinkset
// has not yet been fully constructed.
// Return 'true' if any properties updated on the passed object.
// Called at taint-time!
public override bool MakeDynamic(BSPhysObject child)
public override bool MakeDynamic(BSPrimLinkable child)
{
bool ret = false;
DetailLog("{0},BSLinksetCompound.MakeDynamic,call,IsRoot={1}", child.LocalID, IsRoot(child));
@ -127,138 +142,131 @@ public sealed class BSLinksetCompound : BSLinkset
// The root is going dynamic. Rebuild the linkset so parts and mass get computed properly.
ScheduleRebuild(LinksetRoot);
}
else
{
// The origional prims are removed from the world as the shape of the root compound
// shape takes over.
PhysicsScene.PE.AddToCollisionFlags(child.PhysBody, CollisionFlags.CF_NO_CONTACT_RESPONSE);
PhysicsScene.PE.ForceActivationState(child.PhysBody, ActivationState.DISABLE_SIMULATION);
// We don't want collisions from the old linkset children.
PhysicsScene.PE.RemoveFromCollisionFlags(child.PhysBody, CollisionFlags.BS_SUBSCRIBE_COLLISION_EVENTS);
child.PhysBody.collisionType = CollisionType.LinksetChild;
ret = true;
}
return ret;
}
// The object is going static (non-physical). Do any setup necessary for a static linkset.
// The object is going static (non-physical). We do not do anything for static linksets.
// Return 'true' if any properties updated on the passed object.
// This doesn't normally happen -- OpenSim removes the objects from the physical
// world if it is a static linkset.
// Called at taint-time!
public override bool MakeStatic(BSPhysObject child)
public override bool MakeStatic(BSPrimLinkable child)
{
bool ret = false;
DetailLog("{0},BSLinksetCompound.MakeStatic,call,IsRoot={1}", child.LocalID, IsRoot(child));
if (IsRoot(child))
{
// Schedule a rebuild to verify that the root shape is set to the real shape.
ScheduleRebuild(LinksetRoot);
}
else
{
// The non-physical children can come back to life.
PhysicsScene.PE.RemoveFromCollisionFlags(child.PhysBody, CollisionFlags.CF_NO_CONTACT_RESPONSE);
child.PhysBody.collisionType = CollisionType.LinksetChild;
// Don't force activation so setting of DISABLE_SIMULATION can stay if used.
PhysicsScene.PE.Activate(child.PhysBody, false);
ret = true;
}
return ret;
}
public override void UpdateProperties(BSPhysObject updated, bool physicalUpdate)
// 'physicalUpdate' is true if these changes came directly from the physics engine. Don't need to rebuild then.
// Called at taint-time.
public override void UpdateProperties(UpdatedProperties whichUpdated, BSPrimLinkable updated)
{
if (!LinksetRoot.IsPhysicallyActive)
{
// No reason to do this physical stuff for static linksets.
DetailLog("{0},BSLinksetCompound.UpdateProperties,notPhysical", LinksetRoot.LocalID);
return;
}
// The user moving a child around requires the rebuilding of the linkset compound shape
// One problem is this happens when a border is crossed -- the simulator implementation
// is to store the position into the group which causes the move of the object
// stores the position into the group which causes the move of the object
// but it also means all the child positions get updated.
// What would cause an unnecessary rebuild so we make sure the linkset is in a
// region before bothering to do a rebuild.
if (!IsRoot(updated)
&& !physicalUpdate
&& PhysicsScene.TerrainManager.IsWithinKnownTerrain(LinksetRoot.RawPosition))
if (!IsRoot(updated) && m_physicsScene.TerrainManager.IsWithinKnownTerrain(LinksetRoot.RawPosition))
{
updated.LinksetInfo = null;
ScheduleRebuild(updated);
// If a child of the linkset is updating only the position or rotation, that can be done
// without rebuilding the linkset.
// If a handle for the child can be fetch, we update the child here. If a rebuild was
// scheduled by someone else, the rebuild will just replace this setting.
bool updatedChild = false;
// Anything other than updating position or orientation usually means a physical update
// and that is caused by us updating the object.
if ((whichUpdated & ~(UpdatedProperties.Position | UpdatedProperties.Orientation)) == 0)
{
// Find the physical instance of the child
if (LinksetRoot.PhysShape.HasPhysicalShape && m_physicsScene.PE.IsCompound(LinksetRoot.PhysShape.physShapeInfo))
{
// It is possible that the linkset is still under construction and the child is not yet
// inserted into the compound shape. A rebuild of the linkset in a pre-step action will
// build the whole thing with the new position or rotation.
// The index must be checked because Bullet references the child array but does no validity
// checking of the child index passed.
int numLinksetChildren = m_physicsScene.PE.GetNumberOfCompoundChildren(LinksetRoot.PhysShape.physShapeInfo);
if (updated.LinksetChildIndex < numLinksetChildren)
{
BulletShape linksetChildShape = m_physicsScene.PE.GetChildShapeFromCompoundShapeIndex(LinksetRoot.PhysShape.physShapeInfo, updated.LinksetChildIndex);
if (linksetChildShape.HasPhysicalShape)
{
// Found the child shape within the compound shape
m_physicsScene.PE.UpdateChildTransform(LinksetRoot.PhysShape.physShapeInfo, updated.LinksetChildIndex,
updated.RawPosition - LinksetRoot.RawPosition,
updated.RawOrientation * OMV.Quaternion.Inverse(LinksetRoot.RawOrientation),
true /* shouldRecalculateLocalAabb */);
updatedChild = true;
DetailLog("{0},BSLinksetCompound.UpdateProperties,changeChildPosRot,whichUpdated={1},pos={2},rot={3}",
updated.LocalID, whichUpdated, updated.RawPosition, updated.RawOrientation);
}
else // DEBUG DEBUG
{ // DEBUG DEBUG
DetailLog("{0},BSLinksetCompound.UpdateProperties,couldNotUpdateChild,noChildShape,shape={1}",
updated.LocalID, linksetChildShape);
} // DEBUG DEBUG
}
else // DEBUG DEBUG
{ // DEBUG DEBUG
// the child is not yet in the compound shape. This is non-fatal.
DetailLog("{0},BSLinksetCompound.UpdateProperties,couldNotUpdateChild,childNotInCompoundShape,numChildren={1},index={2}",
updated.LocalID, numLinksetChildren, updated.LinksetChildIndex);
} // DEBUG DEBUG
}
else // DEBUG DEBUG
{ // DEBUG DEBUG
DetailLog("{0},BSLinksetCompound.UpdateProperties,couldNotUpdateChild,noBodyOrNotCompound", updated.LocalID);
} // DEBUG DEBUG
if (!updatedChild)
{
// If couldn't do the individual child, the linkset needs a rebuild to incorporate the new child info.
// Note: there are several ways through this code that will not update the child if
// the linkset is being rebuilt. In this case, scheduling a rebuild is a NOOP since
// there will already be a rebuild scheduled.
DetailLog("{0},BSLinksetCompound.UpdateProperties,couldNotUpdateChild.schedulingRebuild,whichUpdated={1}",
updated.LocalID, whichUpdated);
updated.LinksetInfo = null; // setting to 'null' causes relative position to be recomputed.
ScheduleRebuild(updated);
}
}
}
}
// Routine called when rebuilding the body of some member of the linkset.
// Since we don't keep in world relationships, do nothing unless it's a child changing.
// If one of the bodies is being changed, the linkset needs rebuilding.
// For instance, a linkset is built and then a mesh asset is read in and the mesh is recreated.
// Returns 'true' of something was actually removed and would need restoring
// Called at taint-time!!
public override bool RemoveBodyDependencies(BSPrim child)
public override bool RemoveDependencies(BSPrimLinkable child)
{
bool ret = false;
DetailLog("{0},BSLinksetCompound.RemoveBodyDependencies,refreshIfChild,rID={1},rBody={2},isRoot={3}",
child.LocalID, LinksetRoot.LocalID, LinksetRoot.PhysBody.AddrString, IsRoot(child));
child.LocalID, LinksetRoot.LocalID, LinksetRoot.PhysBody, IsRoot(child));
if (!IsRoot(child))
{
// Because it is a convenient time, recompute child world position and rotation based on
// its position in the linkset.
RecomputeChildWorldPosition(child, true);
}
// Cannot schedule a refresh/rebuild here because this routine is called when
// the linkset is being rebuilt.
// InternalRefresh(LinksetRoot);
ScheduleRebuild(child);
return ret;
}
// Companion to RemoveBodyDependencies(). If RemoveBodyDependencies() returns 'true',
// this routine will restore the removed constraints.
// Called at taint-time!!
public override void RestoreBodyDependencies(BSPrim child)
{
}
// When the linkset is built, the child shape is added to the compound shape relative to the
// root shape. The linkset then moves around but this does not move the actual child
// prim. The child prim's location must be recomputed based on the location of the root shape.
private void RecomputeChildWorldPosition(BSPhysObject child, bool inTaintTime)
{
BSLinksetCompoundInfo lci = child.LinksetInfo as BSLinksetCompoundInfo;
if (lci != null)
{
if (inTaintTime)
{
OMV.Vector3 oldPos = child.RawPosition;
child.ForcePosition = LinksetRoot.RawPosition + lci.OffsetPos;
child.ForceOrientation = LinksetRoot.RawOrientation * lci.OffsetRot;
DetailLog("{0},BSLinksetCompound.RecomputeChildWorldPosition,oldPos={1},lci={2},newPos={3}",
child.LocalID, oldPos, lci, child.RawPosition);
}
else
{
// TaintedObject is not used here so the raw position is set now and not at taint-time.
child.Position = LinksetRoot.RawPosition + lci.OffsetPos;
child.Orientation = LinksetRoot.RawOrientation * lci.OffsetRot;
}
}
else
{
// This happens when children have been added to the linkset but the linkset
// has not been constructed yet. So like, at taint time, adding children to a linkset
// and then changing properties of the children (makePhysical, for instance)
// but the post-print action of actually rebuilding the linkset has not yet happened.
// PhysicsScene.Logger.WarnFormat("{0} Restoring linkset child position failed because of no relative position computed. ID={1}",
// LogHeader, child.LocalID);
DetailLog("{0},BSLinksetCompound.recomputeChildWorldPosition,noRelativePositonInfo", child.LocalID);
}
}
// ================================================================
// Add a new child to the linkset.
// Called while LinkActivity is locked.
protected override void AddChildToLinkset(BSPhysObject child)
protected override void AddChildToLinkset(BSPrimLinkable child)
{
if (!HasChild(child))
{
@ -274,8 +282,10 @@ public sealed class BSLinksetCompound : BSLinkset
// Remove the specified child from the linkset.
// Safe to call even if the child is not really in the linkset.
protected override void RemoveChildFromLinkset(BSPhysObject child)
protected override void RemoveChildFromLinkset(BSPrimLinkable child)
{
child.ClearDisplacement();
if (m_children.Remove(child))
{
DetailLog("{0},BSLinksetCompound.RemoveChildFromLinkset,call,rID={1},rBody={2},cID={3},cBody={4}",
@ -284,7 +294,7 @@ public sealed class BSLinksetCompound : BSLinkset
child.LocalID, child.PhysBody.AddrString);
// Cause the child's body to be rebuilt and thus restored to normal operation
RecomputeChildWorldPosition(child, false);
child.LinksetInfo = null;
child.ForceBodyShapeRebuild(false);
if (!HasAnyChildren)
@ -295,7 +305,7 @@ public sealed class BSLinksetCompound : BSLinkset
else
{
// Rebuild the compound shape with the child removed
ScheduleRebuild(child);
ScheduleRebuild(LinksetRoot);
}
}
return;
@ -306,87 +316,113 @@ public sealed class BSLinksetCompound : BSLinkset
// Constraint linksets are rebuilt every time.
// Note that this works for rebuilding just the root after a linkset is taken apart.
// Called at taint time!!
private bool UseBulletSimRootOffsetHack = false; // Attempt to have Bullet track the coords of root compound shape
private bool disableCOM = true; // For basic linkset debugging, turn off the center-of-mass setting
private void RecomputeLinksetCompound()
{
try
{
// Suppress rebuilding while rebuilding
Rebuilding = true;
// Cause the root shape to be rebuilt as a compound object with just the root in it
// No matter what is being done, force the root prim's PhysBody and PhysShape to get set
// to what they should be as if the root was not in a linkset.
// Not that bad since we only get into this routine if there are children in the linkset and
// something has been updated/changed.
LinksetRoot.ForceBodyShapeRebuild(true);
DetailLog("{0},BSLinksetCompound.RecomputeLinksetCompound,start,rBody={1},rShape={2},numChildren={3}",
LinksetRoot.LocalID, LinksetRoot.PhysBody, LinksetRoot.PhysShape, NumberOfChildren);
// Add a shape for each of the other children in the linkset
ForEachMember(delegate(BSPhysObject cPrim)
// There is no reason to build all this physical stuff for a non-physical linkset.
if (!LinksetRoot.IsPhysicallyActive)
{
// Clean up any old linkset shape and make sure the root shape is set to the root object.
DetailLog("{0},BSLinksetCompound.RecomputeLinksetCompound,notPhysical", LinksetRoot.LocalID);
return; // Note the 'finally' clause at the botton which will get executed.
}
// Get a new compound shape to build the linkset shape in.
BSShape linksetShape = BSShapeCompound.GetReference(m_physicsScene);
// The center of mass for the linkset is the geometric center of the group.
// Compute a displacement for each component so it is relative to the center-of-mass.
// Bullet presumes an object's origin (relative <0,0,0>) is its center-of-mass
OMV.Vector3 centerOfMassW = ComputeLinksetCenterOfMass();
OMV.Quaternion invRootOrientation = OMV.Quaternion.Normalize(OMV.Quaternion.Inverse(LinksetRoot.RawOrientation));
// 'centerDisplacement' is the value to subtract from children to give physical offset position
OMV.Vector3 centerDisplacementV = (centerOfMassW - LinksetRoot.RawPosition) * invRootOrientation;
if (UseBulletSimRootOffsetHack || disableCOM)
{
centerDisplacementV = OMV.Vector3.Zero;
LinksetRoot.ClearDisplacement();
}
else
{
LinksetRoot.SetEffectiveCenterOfMassDisplacement(centerDisplacementV);
}
DetailLog("{0},BSLinksetCompound.RecomputeLinksetCompound,COM,rootPos={1},com={2},comDisp={3}",
LinksetRoot.LocalID, LinksetRoot.RawPosition, centerOfMassW, centerDisplacementV);
// Add the shapes of all the components of the linkset
int memberIndex = 1;
ForEachMember(delegate(BSPrimLinkable cPrim)
{
// Root shape is always index zero.
cPrim.LinksetChildIndex = IsRoot(cPrim) ? 0 : memberIndex;
// Get a reference to the shape of the child and add that shape to the linkset compound shape
BSShape childShape = cPrim.PhysShape.GetReference(m_physicsScene, cPrim);
OMV.Vector3 offsetPos = (cPrim.RawPosition - LinksetRoot.RawPosition) * invRootOrientation - centerDisplacementV;
OMV.Quaternion offsetRot = OMV.Quaternion.Normalize(cPrim.RawOrientation) * invRootOrientation;
m_physicsScene.PE.AddChildShapeToCompoundShape(linksetShape.physShapeInfo, childShape.physShapeInfo, offsetPos, offsetRot);
DetailLog("{0},BSLinksetCompound.RecomputeLinksetCompound,addChild,indx={1},cShape={2},offPos={3},offRot={4}",
LinksetRoot.LocalID, memberIndex, childShape, offsetPos, offsetRot);
// Since we are borrowing the shape of the child, disable the origional child body
if (!IsRoot(cPrim))
{
// Compute the displacement of the child from the root of the linkset.
// This info is saved in the child prim so the relationship does not
// change over time and the new child position can be computed
// when the linkset is being disassembled (the linkset may have moved).
BSLinksetCompoundInfo lci = cPrim.LinksetInfo as BSLinksetCompoundInfo;
if (lci == null)
{
// Each child position and rotation is given relative to the root.
OMV.Quaternion invRootOrientation = OMV.Quaternion.Inverse(LinksetRoot.RawOrientation);
OMV.Vector3 displacementPos = (cPrim.RawPosition - LinksetRoot.RawPosition) * invRootOrientation;
OMV.Quaternion displacementRot = cPrim.RawOrientation * invRootOrientation;
// Save relative position for recomputing child's world position after moving linkset.
lci = new BSLinksetCompoundInfo(displacementPos, displacementRot);
cPrim.LinksetInfo = lci;
DetailLog("{0},BSLinksetCompound.RecomputeLinksetCompound,creatingRelPos,lci={1}", cPrim.LocalID, lci);
}
DetailLog("{0},BSLinksetCompound.RecomputeLinksetCompound,addMemberToShape,mID={1},mShape={2},dispPos={3},dispRot={4}",
LinksetRoot.LocalID, cPrim.LocalID, cPrim.PhysShape, lci.OffsetPos, lci.OffsetRot);
if (cPrim.PhysShape.isNativeShape)
{
// A native shape is turning into a hull collision shape because native
// shapes are not shared so we have to hullify it so it will be tracked
// and freed at the correct time. This also solves the scaling problem
// (native shapes scaled but hull/meshes are assumed to not be).
// TODO: decide of the native shape can just be used in the compound shape.
// Use call to CreateGeomNonSpecial().
BulletShape saveShape = cPrim.PhysShape;
cPrim.PhysShape.Clear(); // Don't let the create free the child's shape
// PhysicsScene.Shapes.CreateGeomNonSpecial(true, cPrim, null);
PhysicsScene.Shapes.CreateGeomMeshOrHull(cPrim, null);
BulletShape newShape = cPrim.PhysShape;
cPrim.PhysShape = saveShape;
PhysicsScene.PE.AddChildShapeToCompoundShape(LinksetRoot.PhysShape, newShape, lci.OffsetPos, lci.OffsetRot);
}
else
{
// For the shared shapes (meshes and hulls), just use the shape in the child.
// The reference count added here will be decremented when the compound shape
// is destroyed in BSShapeCollection (the child shapes are looped over and dereferenced).
if (PhysicsScene.Shapes.ReferenceShape(cPrim.PhysShape))
{
PhysicsScene.Logger.ErrorFormat("{0} Rebuilt sharable shape when building linkset! Region={1}, primID={2}, shape={3}",
LogHeader, PhysicsScene.RegionName, cPrim.LocalID, cPrim.PhysShape);
}
PhysicsScene.PE.AddChildShapeToCompoundShape(LinksetRoot.PhysShape, cPrim.PhysShape, lci.OffsetPos, lci.OffsetRot);
}
m_physicsScene.PE.AddToCollisionFlags(cPrim.PhysBody, CollisionFlags.CF_NO_CONTACT_RESPONSE);
m_physicsScene.PE.ForceActivationState(cPrim.PhysBody, ActivationState.DISABLE_SIMULATION);
// We don't want collisions from the old linkset children.
m_physicsScene.PE.RemoveFromCollisionFlags(cPrim.PhysBody, CollisionFlags.BS_SUBSCRIBE_COLLISION_EVENTS);
cPrim.PhysBody.collisionType = CollisionType.LinksetChild;
}
memberIndex++;
return false; // 'false' says to move onto the next child in the list
});
// Replace the root shape with the built compound shape.
// Object removed and added to world to get collision cache rebuilt for new shape.
LinksetRoot.PhysShape.Dereference(m_physicsScene);
LinksetRoot.PhysShape = linksetShape;
m_physicsScene.PE.RemoveObjectFromWorld(m_physicsScene.World, LinksetRoot.PhysBody);
m_physicsScene.PE.SetCollisionShape(m_physicsScene.World, LinksetRoot.PhysBody, linksetShape.physShapeInfo);
m_physicsScene.PE.AddObjectToWorld(m_physicsScene.World, LinksetRoot.PhysBody);
DetailLog("{0},BSLinksetCompound.RecomputeLinksetCompound,addBody,body={1},shape={2}",
LinksetRoot.LocalID, LinksetRoot.PhysBody, linksetShape);
// With all of the linkset packed into the root prim, it has the mass of everyone.
LinksetMass = ComputeLinksetMass();
LinksetRoot.UpdatePhysicalMassProperties(LinksetMass, true);
if (UseBulletSimRootOffsetHack)
{
// Enable the physical position updator to return the position and rotation of the root shape.
// This enables a feature in the C++ code to return the world coordinates of the first shape in the
// compound shape. This eleviates the need to offset the returned physical position by the
// center-of-mass offset.
m_physicsScene.PE.AddToCollisionFlags(LinksetRoot.PhysBody, CollisionFlags.BS_RETURN_ROOT_COMPOUND_SHAPE);
}
}
finally
{
Rebuilding = false;
}
PhysicsScene.PE.RecalculateCompoundShapeLocalAabb(LinksetRoot.PhysShape);
// See that the Aabb surrounds the new shape
m_physicsScene.PE.RecalculateCompoundShapeLocalAabb(LinksetRoot.PhysShape.physShapeInfo);
}
}
}

View File

@ -36,7 +36,7 @@ public sealed class BSLinksetConstraints : BSLinkset
{
// private static string LogHeader = "[BULLETSIM LINKSET CONSTRAINTS]";
public BSLinksetConstraints(BSScene scene, BSPhysObject parent) : base(scene, parent)
public BSLinksetConstraints(BSScene scene, BSPrimLinkable parent) : base(scene, parent)
{
}
@ -44,14 +44,14 @@ public sealed class BSLinksetConstraints : BSLinkset
// its internal properties.
// This is queued in the 'post taint' queue so the
// refresh will happen once after all the other taints are applied.
public override void Refresh(BSPhysObject requestor)
public override void Refresh(BSPrimLinkable requestor)
{
base.Refresh(requestor);
if (HasAnyChildren && IsRoot(requestor))
{
// Queue to happen after all the other taint processing
PhysicsScene.PostTaintObject("BSLinksetContraints.Refresh", requestor.LocalID, delegate()
m_physicsScene.PostTaintObject("BSLinksetContraints.Refresh", requestor.LocalID, delegate()
{
if (HasAnyChildren && IsRoot(requestor))
RecomputeLinksetConstraints();
@ -65,7 +65,7 @@ public sealed class BSLinksetConstraints : BSLinkset
// has not yet been fully constructed.
// Return 'true' if any properties updated on the passed object.
// Called at taint-time!
public override bool MakeDynamic(BSPhysObject child)
public override bool MakeDynamic(BSPrimLinkable child)
{
// What is done for each object in BSPrim is what we want.
return false;
@ -76,14 +76,14 @@ public sealed class BSLinksetConstraints : BSLinkset
// This doesn't normally happen -- OpenSim removes the objects from the physical
// world if it is a static linkset.
// Called at taint-time!
public override bool MakeStatic(BSPhysObject child)
public override bool MakeStatic(BSPrimLinkable child)
{
// What is done for each object in BSPrim is what we want.
return false;
}
// Called at taint-time!!
public override void UpdateProperties(BSPhysObject updated, bool inTaintTime)
public override void UpdateProperties(UpdatedProperties whichUpdated, BSPrimLinkable pObj)
{
// Nothing to do for constraints on property updates
}
@ -93,11 +93,11 @@ public sealed class BSLinksetConstraints : BSLinkset
// up to rebuild the constraints before the next simulation step.
// Returns 'true' of something was actually removed and would need restoring
// Called at taint-time!!
public override bool RemoveBodyDependencies(BSPrim child)
public override bool RemoveDependencies(BSPrimLinkable child)
{
bool ret = false;
DetailLog("{0},BSLinksetConstraint.RemoveBodyDependencies,removeChildrenForRoot,rID={1},rBody={2}",
DetailLog("{0},BSLinksetConstraint.RemoveDependencies,removeChildrenForRoot,rID={1},rBody={2}",
child.LocalID, LinksetRoot.LocalID, LinksetRoot.PhysBody.AddrString);
lock (m_linksetActivityLock)
@ -110,19 +110,11 @@ public sealed class BSLinksetConstraints : BSLinkset
return ret;
}
// Companion to RemoveBodyDependencies(). If RemoveBodyDependencies() returns 'true',
// this routine will restore the removed constraints.
// Called at taint-time!!
public override void RestoreBodyDependencies(BSPrim child)
{
// The Refresh operation queued by RemoveBodyDependencies() will build any missing constraints.
}
// ================================================================
// Add a new child to the linkset.
// Called while LinkActivity is locked.
protected override void AddChildToLinkset(BSPhysObject child)
protected override void AddChildToLinkset(BSPrimLinkable child)
{
if (!HasChild(child))
{
@ -138,19 +130,19 @@ public sealed class BSLinksetConstraints : BSLinkset
// Remove the specified child from the linkset.
// Safe to call even if the child is not really in my linkset.
protected override void RemoveChildFromLinkset(BSPhysObject child)
protected override void RemoveChildFromLinkset(BSPrimLinkable child)
{
if (m_children.Remove(child))
{
BSPhysObject rootx = LinksetRoot; // capture the root and body as of now
BSPhysObject childx = child;
BSPrimLinkable rootx = LinksetRoot; // capture the root and body as of now
BSPrimLinkable childx = child;
DetailLog("{0},BSLinksetConstraints.RemoveChildFromLinkset,call,rID={1},rBody={2},cID={3},cBody={4}",
childx.LocalID,
rootx.LocalID, rootx.PhysBody.AddrString,
childx.LocalID, childx.PhysBody.AddrString);
PhysicsScene.TaintedObject("BSLinksetConstraints.RemoveChildFromLinkset", delegate()
m_physicsScene.TaintedObject("BSLinksetConstraints.RemoveChildFromLinkset", delegate()
{
PhysicallyUnlinkAChildFromRoot(rootx, childx);
});
@ -167,13 +159,13 @@ public sealed class BSLinksetConstraints : BSLinkset
// Create a constraint between me (root of linkset) and the passed prim (the child).
// Called at taint time!
private void PhysicallyLinkAChildToRoot(BSPhysObject rootPrim, BSPhysObject childPrim)
private void PhysicallyLinkAChildToRoot(BSPrimLinkable rootPrim, BSPrimLinkable childPrim)
{
// Don't build the constraint when asked. Put it off until just before the simulation step.
Refresh(rootPrim);
}
private BSConstraint BuildConstraint(BSPhysObject rootPrim, BSPhysObject childPrim)
private BSConstraint BuildConstraint(BSPrimLinkable rootPrim, BSPrimLinkable childPrim)
{
// Zero motion for children so they don't interpolate
childPrim.ZeroMotion(true);
@ -195,7 +187,7 @@ public sealed class BSLinksetConstraints : BSLinkset
// http://bulletphysics.org/Bullet/phpBB3/viewtopic.php?t=4818
BSConstraint6Dof constrain = new BSConstraint6Dof(
PhysicsScene.World, rootPrim.PhysBody, childPrim.PhysBody, midPoint, true, true );
m_physicsScene.World, rootPrim.PhysBody, childPrim.PhysBody, midPoint, true, true );
// PhysicsScene.World, childPrim.BSBody, rootPrim.BSBody, midPoint, true, true );
/* NOTE: below is an attempt to build constraint with full frame computation, etc.
@ -224,15 +216,15 @@ public sealed class BSLinksetConstraints : BSLinkset
// ==================================================================================
*/
PhysicsScene.Constraints.AddConstraint(constrain);
m_physicsScene.Constraints.AddConstraint(constrain);
// zero linear and angular limits makes the objects unable to move in relation to each other
constrain.SetLinearLimits(OMV.Vector3.Zero, OMV.Vector3.Zero);
constrain.SetAngularLimits(OMV.Vector3.Zero, OMV.Vector3.Zero);
// tweek the constraint to increase stability
constrain.UseFrameOffset(BSParam.BoolNumeric(BSParam.LinkConstraintUseFrameOffset));
constrain.TranslationalLimitMotor(BSParam.BoolNumeric(BSParam.LinkConstraintEnableTransMotor),
constrain.UseFrameOffset(BSParam.LinkConstraintUseFrameOffset);
constrain.TranslationalLimitMotor(BSParam.LinkConstraintEnableTransMotor,
BSParam.LinkConstraintTransMotorMaxVel,
BSParam.LinkConstraintTransMotorMaxForce);
constrain.SetCFMAndERP(BSParam.LinkConstraintCFM, BSParam.LinkConstraintERP);
@ -247,7 +239,7 @@ public sealed class BSLinksetConstraints : BSLinkset
// The root and child bodies are passed in because we need to remove the constraint between
// the bodies that were present at unlink time.
// Called at taint time!
private bool PhysicallyUnlinkAChildFromRoot(BSPhysObject rootPrim, BSPhysObject childPrim)
private bool PhysicallyUnlinkAChildFromRoot(BSPrimLinkable rootPrim, BSPrimLinkable childPrim)
{
bool ret = false;
DetailLog("{0},BSLinksetConstraint.PhysicallyUnlinkAChildFromRoot,taint,root={1},rBody={2},child={3},cBody={4}",
@ -256,10 +248,10 @@ public sealed class BSLinksetConstraints : BSLinkset
childPrim.LocalID, childPrim.PhysBody.AddrString);
// Find the constraint for this link and get rid of it from the overall collection and from my list
if (PhysicsScene.Constraints.RemoveAndDestroyConstraint(rootPrim.PhysBody, childPrim.PhysBody))
if (m_physicsScene.Constraints.RemoveAndDestroyConstraint(rootPrim.PhysBody, childPrim.PhysBody))
{
// Make the child refresh its location
PhysicsScene.PE.PushUpdate(childPrim.PhysBody);
m_physicsScene.PE.PushUpdate(childPrim.PhysBody);
ret = true;
}
@ -269,11 +261,11 @@ public sealed class BSLinksetConstraints : BSLinkset
// Remove linkage between myself and any possible children I might have.
// Returns 'true' of any constraints were destroyed.
// Called at taint time!
private bool PhysicallyUnlinkAllChildrenFromRoot(BSPhysObject rootPrim)
private bool PhysicallyUnlinkAllChildrenFromRoot(BSPrimLinkable rootPrim)
{
DetailLog("{0},BSLinksetConstraint.PhysicallyUnlinkAllChildren,taint", rootPrim.LocalID);
return PhysicsScene.Constraints.RemoveAndDestroyConstraint(rootPrim.PhysBody);
return m_physicsScene.Constraints.RemoveAndDestroyConstraint(rootPrim.PhysBody);
}
// Call each of the constraints that make up this linkset and recompute the
@ -289,7 +281,7 @@ public sealed class BSLinksetConstraints : BSLinkset
DetailLog("{0},BSLinksetConstraint.RecomputeLinksetConstraints,set,rBody={1},linksetMass={2}",
LinksetRoot.LocalID, LinksetRoot.PhysBody.AddrString, linksetMass);
foreach (BSPhysObject child in m_children)
foreach (BSPrimLinkable child in m_children)
{
// A child in the linkset physically shows the mass of the whole linkset.
// This allows Bullet to apply enough force on the child to move the whole linkset.
@ -297,7 +289,7 @@ public sealed class BSLinksetConstraints : BSLinkset
child.UpdatePhysicalMassProperties(linksetMass, true);
BSConstraint constrain;
if (!PhysicsScene.Constraints.TryGetConstraint(LinksetRoot.PhysBody, child.PhysBody, out constrain))
if (!m_physicsScene.Constraints.TryGetConstraint(LinksetRoot.PhysBody, child.PhysBody, out constrain))
{
// If constraint doesn't exist yet, create it.
constrain = BuildConstraint(LinksetRoot, child);

View File

@ -180,11 +180,14 @@ public static class BSMaterials
// Use reflection to set the value in the attribute structure.
private static void SetAttributeValue(int matType, string attribName, float val)
{
// Get the current attribute values for this material
MaterialAttributes thisAttrib = Attributes[matType];
// Find the field for the passed attribute name (eg, find field named 'friction')
FieldInfo fieldInfo = thisAttrib.GetType().GetField(attribName.ToLower());
if (fieldInfo != null)
{
fieldInfo.SetValue(thisAttrib, val);
// Copy new attributes back to array -- since MaterialAttributes is 'struct', passed by value, not reference.
Attributes[matType] = thisAttrib;
}
}

View File

@ -59,22 +59,17 @@ public abstract class BSMotor
{
if (PhysicsScene != null)
{
if (PhysicsScene.VehicleLoggingEnabled)
{
PhysicsScene.DetailLog(msg, parms);
}
PhysicsScene.DetailLog(msg, parms);
}
}
}
// Motor which moves CurrentValue to TargetValue over TimeScale seconds.
// The TargetValue decays in TargetValueDecayTimeScale and
// the CurrentValue will be held back by FrictionTimeScale.
// The TargetValue decays in TargetValueDecayTimeScale.
// This motor will "zero itself" over time in that the targetValue will
// decay to zero and the currentValue will follow it to that zero.
// The overall effect is for the returned correction value to go from large
// values (the total difference between current and target minus friction)
// to small and eventually zero values.
// values to small and eventually zero values.
// TimeScale and TargetDelayTimeScale may be 'infinite' which means no decay.
// For instance, if something is moving at speed X and the desired speed is Y,
@ -91,7 +86,6 @@ public class BSVMotor : BSMotor
public virtual float TimeScale { get; set; }
public virtual float TargetValueDecayTimeScale { get; set; }
public virtual Vector3 FrictionTimescale { get; set; }
public virtual float Efficiency { get; set; }
public virtual float ErrorZeroThreshold { get; set; }
@ -100,10 +94,13 @@ public class BSVMotor : BSMotor
public virtual Vector3 CurrentValue { get; protected set; }
public virtual Vector3 LastError { get; protected set; }
public virtual bool ErrorIsZero
{ get {
return (LastError == Vector3.Zero || LastError.LengthSquared() <= ErrorZeroThreshold);
}
public virtual bool ErrorIsZero()
{
return ErrorIsZero(LastError);
}
public virtual bool ErrorIsZero(Vector3 err)
{
return (err == Vector3.Zero || err.ApproxEquals(Vector3.Zero, ErrorZeroThreshold));
}
public BSVMotor(string useName)
@ -111,16 +108,14 @@ public class BSVMotor : BSMotor
{
TimeScale = TargetValueDecayTimeScale = BSMotor.Infinite;
Efficiency = 1f;
FrictionTimescale = BSMotor.InfiniteVector;
CurrentValue = TargetValue = Vector3.Zero;
ErrorZeroThreshold = 0.001f;
}
public BSVMotor(string useName, float timeScale, float decayTimeScale, Vector3 frictionTimeScale, float efficiency)
public BSVMotor(string useName, float timeScale, float decayTimeScale, float efficiency)
: this(useName)
{
TimeScale = timeScale;
TargetValueDecayTimeScale = decayTimeScale;
FrictionTimescale = frictionTimeScale;
Efficiency = efficiency;
CurrentValue = TargetValue = Vector3.Zero;
}
@ -138,7 +133,8 @@ public class BSVMotor : BSMotor
CurrentValue = TargetValue = Vector3.Zero;
}
// Compute the next step and return the new current value
// Compute the next step and return the new current value.
// Returns the correction needed to move 'current' to 'target'.
public virtual Vector3 Step(float timeStep)
{
if (!Enabled) return TargetValue;
@ -148,9 +144,10 @@ public class BSVMotor : BSMotor
Vector3 correction = Vector3.Zero;
Vector3 error = TargetValue - CurrentValue;
if (!error.ApproxEquals(Vector3.Zero, ErrorZeroThreshold))
LastError = error;
if (!ErrorIsZero(error))
{
correction = Step(timeStep, error);
correction = StepError(timeStep, error);
CurrentValue += correction;
@ -163,44 +160,40 @@ public class BSVMotor : BSMotor
TargetValue *= (1f - decayFactor);
}
// The amount we can correct the error is reduced by the friction
Vector3 frictionFactor = Vector3.Zero;
if (FrictionTimescale != BSMotor.InfiniteVector)
{
// frictionFactor = (Vector3.One / FrictionTimescale) * timeStep;
// Individual friction components can be 'infinite' so compute each separately.
frictionFactor.X = (FrictionTimescale.X == BSMotor.Infinite) ? 0f : (1f / FrictionTimescale.X);
frictionFactor.Y = (FrictionTimescale.Y == BSMotor.Infinite) ? 0f : (1f / FrictionTimescale.Y);
frictionFactor.Z = (FrictionTimescale.Z == BSMotor.Infinite) ? 0f : (1f / FrictionTimescale.Z);
frictionFactor *= timeStep;
CurrentValue *= (Vector3.One - frictionFactor);
}
MDetailLog("{0}, BSVMotor.Step,nonZero,{1},origCurr={2},origTarget={3},timeStep={4},err={5},corr={6}",
BSScene.DetailLogZero, UseName, origCurrVal, origTarget,
timeStep, error, correction);
MDetailLog("{0}, BSVMotor.Step,nonZero,{1},tgtDecayTS={2},decayFact={3},frictTS={4},frictFact={5},tgt={6},curr={7}",
BSScene.DetailLogZero, UseName,
TargetValueDecayTimeScale, decayFactor, FrictionTimescale, frictionFactor,
TargetValue, CurrentValue);
MDetailLog("{0}, BSVMotor.Step,nonZero,{1},tgtDecayTS={2},decayFact={3},tgt={4},curr={5}",
BSScene.DetailLogZero, UseName, TargetValueDecayTimeScale, decayFactor, TargetValue, CurrentValue);
}
else
{
// Difference between what we have and target is small. Motor is done.
if (TargetValue.ApproxEquals(Vector3.Zero, ErrorZeroThreshold))
{
// The target can step down to nearly zero but not get there. If close to zero
// it is really zero.
TargetValue = Vector3.Zero;
}
CurrentValue = TargetValue;
MDetailLog("{0}, BSVMotor.Step,zero,{1},origTgt={2},origCurr={3},ret={4}",
BSScene.DetailLogZero, UseName, origCurrVal, origTarget, CurrentValue);
MDetailLog("{0}, BSVMotor.Step,zero,{1},origTgt={2},origCurr={3},currTgt={4},currCurr={5}",
BSScene.DetailLogZero, UseName, origCurrVal, origTarget, TargetValue, CurrentValue);
}
return CurrentValue;
return correction;
}
public virtual Vector3 Step(float timeStep, Vector3 error)
// version of step that sets the current value before doing the step
public virtual Vector3 Step(float timeStep, Vector3 current)
{
CurrentValue = current;
return Step(timeStep);
}
public virtual Vector3 StepError(float timeStep, Vector3 error)
{
if (!Enabled) return Vector3.Zero;
LastError = error;
Vector3 returnCorrection = Vector3.Zero;
if (!error.ApproxEquals(Vector3.Zero, ErrorZeroThreshold))
if (!ErrorIsZero(error))
{
// correction = error / secondsItShouldTakeToCorrect
Vector3 correctionAmount;
@ -222,9 +215,9 @@ public class BSVMotor : BSMotor
// maximum number of outputs to generate.
int maxOutput = 50;
MDetailLog("{0},BSVMotor.Test,{1},===================================== BEGIN Test Output", BSScene.DetailLogZero, UseName);
MDetailLog("{0},BSVMotor.Test,{1},timeScale={2},targDlyTS={3},frictTS={4},eff={5},curr={6},tgt={7}",
MDetailLog("{0},BSVMotor.Test,{1},timeScale={2},targDlyTS={3},eff={4},curr={5},tgt={6}",
BSScene.DetailLogZero, UseName,
TimeScale, TargetValueDecayTimeScale, FrictionTimescale, Efficiency,
TimeScale, TargetValueDecayTimeScale, Efficiency,
CurrentValue, TargetValue);
LastError = BSMotor.InfiniteVector;
@ -235,43 +228,141 @@ public class BSVMotor : BSMotor
BSScene.DetailLogZero, UseName, CurrentValue, TargetValue, LastError, lastStep);
}
MDetailLog("{0},BSVMotor.Test,{1},===================================== END Test Output", BSScene.DetailLogZero, UseName);
}
public override string ToString()
{
return String.Format("<{0},curr={1},targ={2},lastErr={3},decayTS={4},frictTS={5}>",
UseName, CurrentValue, TargetValue, LastError, TargetValueDecayTimeScale, FrictionTimescale);
return String.Format("<{0},curr={1},targ={2},lastErr={3},decayTS={4}>",
UseName, CurrentValue, TargetValue, LastError, TargetValueDecayTimeScale);
}
}
// ============================================================================
// ============================================================================
public class BSFMotor : BSMotor
{
public float TimeScale { get; set; }
public float DecayTimeScale { get; set; }
public float Friction { get; set; }
public float Efficiency { get; set; }
public virtual float TimeScale { get; set; }
public virtual float TargetValueDecayTimeScale { get; set; }
public virtual float Efficiency { get; set; }
public float Target { get; private set; }
public float CurrentValue { get; private set; }
public virtual float ErrorZeroThreshold { get; set; }
public BSFMotor(string useName, float timeScale, float decayTimescale, float friction, float efficiency)
public virtual float TargetValue { get; protected set; }
public virtual float CurrentValue { get; protected set; }
public virtual float LastError { get; protected set; }
public virtual bool ErrorIsZero()
{
return ErrorIsZero(LastError);
}
public virtual bool ErrorIsZero(float err)
{
return (err >= -ErrorZeroThreshold && err <= ErrorZeroThreshold);
}
public BSFMotor(string useName, float timeScale, float decayTimescale, float efficiency)
: base(useName)
{
TimeScale = TargetValueDecayTimeScale = BSMotor.Infinite;
Efficiency = 1f;
CurrentValue = TargetValue = 0f;
ErrorZeroThreshold = 0.01f;
}
public void SetCurrent(float target)
public void SetCurrent(float current)
{
CurrentValue = current;
}
public void SetTarget(float target)
{
TargetValue = target;
}
public override void Zero()
{
base.Zero();
CurrentValue = TargetValue = 0f;
}
public virtual float Step(float timeStep)
{
return 0f;
if (!Enabled) return TargetValue;
float origTarget = TargetValue; // DEBUG
float origCurrVal = CurrentValue; // DEBUG
float correction = 0f;
float error = TargetValue - CurrentValue;
LastError = error;
if (!ErrorIsZero(error))
{
correction = StepError(timeStep, error);
CurrentValue += correction;
// The desired value reduces to zero which also reduces the difference with current.
// If the decay time is infinite, don't decay at all.
float decayFactor = 0f;
if (TargetValueDecayTimeScale != BSMotor.Infinite)
{
decayFactor = (1.0f / TargetValueDecayTimeScale) * timeStep;
TargetValue *= (1f - decayFactor);
}
MDetailLog("{0}, BSFMotor.Step,nonZero,{1},origCurr={2},origTarget={3},timeStep={4},err={5},corr={6}",
BSScene.DetailLogZero, UseName, origCurrVal, origTarget,
timeStep, error, correction);
MDetailLog("{0}, BSFMotor.Step,nonZero,{1},tgtDecayTS={2},decayFact={3},tgt={4},curr={5}",
BSScene.DetailLogZero, UseName, TargetValueDecayTimeScale, decayFactor, TargetValue, CurrentValue);
}
else
{
// Difference between what we have and target is small. Motor is done.
if (Util.InRange<float>(TargetValue, -ErrorZeroThreshold, ErrorZeroThreshold))
{
// The target can step down to nearly zero but not get there. If close to zero
// it is really zero.
TargetValue = 0f;
}
CurrentValue = TargetValue;
MDetailLog("{0}, BSFMotor.Step,zero,{1},origTgt={2},origCurr={3},ret={4}",
BSScene.DetailLogZero, UseName, origCurrVal, origTarget, CurrentValue);
}
return CurrentValue;
}
public virtual float StepError(float timeStep, float error)
{
if (!Enabled) return 0f;
float returnCorrection = 0f;
if (!ErrorIsZero(error))
{
// correction = error / secondsItShouldTakeToCorrect
float correctionAmount;
if (TimeScale == 0f || TimeScale == BSMotor.Infinite)
correctionAmount = error * timeStep;
else
correctionAmount = error / TimeScale * timeStep;
returnCorrection = correctionAmount;
MDetailLog("{0}, BSFMotor.Step,nonZero,{1},timeStep={2},timeScale={3},err={4},corr={5}",
BSScene.DetailLogZero, UseName, timeStep, TimeScale, error, correctionAmount);
}
return returnCorrection;
}
public override string ToString()
{
return String.Format("<{0},curr={1},targ={2},lastErr={3},decayTS={4}>",
UseName, CurrentValue, TargetValue, LastError, TargetValueDecayTimeScale);
}
}
// ============================================================================
// ============================================================================
// Proportional, Integral, Derivitive Motor
// Good description at http://www.answers.com/topic/pid-controller . Includes processes for choosing p, i and d factors.
public class BSPIDVMotor : BSVMotor
@ -281,6 +372,12 @@ public class BSPIDVMotor : BSVMotor
public Vector3 integralFactor { get; set; }
public Vector3 derivFactor { get; set; }
// The factors are vectors for the three dimensions. This is the proportional of each
// that is applied. This could be multiplied through the actual factors but it
// is sometimes easier to manipulate the factors and their mix separately.
// to
public Vector3 FactorMix;
// Arbritrary factor range.
// EfficiencyHigh means move quickly to the correct number. EfficiencyLow means might over correct.
public float EfficiencyHigh = 0.4f;
@ -295,6 +392,7 @@ public class BSPIDVMotor : BSVMotor
proportionFactor = new Vector3(1.00f, 1.00f, 1.00f);
integralFactor = new Vector3(1.00f, 1.00f, 1.00f);
derivFactor = new Vector3(1.00f, 1.00f, 1.00f);
FactorMix = new Vector3(0.5f, 0.25f, 0.25f);
RunningIntegration = Vector3.Zero;
LastError = Vector3.Zero;
}
@ -310,20 +408,24 @@ public class BSPIDVMotor : BSVMotor
set
{
base.Efficiency = Util.Clamp(value, 0f, 1f);
// Compute factors based on efficiency.
// If efficiency is high (1f), use a factor value that moves the error value to zero with little overshoot.
// If efficiency is low (0f), use a factor value that overcorrects.
// TODO: might want to vary contribution of different factor depending on efficiency.
float factor = ((1f - this.Efficiency) * EfficiencyHigh + EfficiencyLow) / 3f;
// float factor = (1f - this.Efficiency) * EfficiencyHigh + EfficiencyLow;
proportionFactor = new Vector3(factor, factor, factor);
integralFactor = new Vector3(factor, factor, factor);
derivFactor = new Vector3(factor, factor, factor);
MDetailLog("{0},BSPIDVMotor.setEfficiency,eff={1},factor={2}", BSScene.DetailLogZero, Efficiency, factor);
}
}
// Ignore Current and Target Values and just advance the PID computation on this error.
public override Vector3 Step(float timeStep, Vector3 error)
// Advance the PID computation on this error.
public override Vector3 StepError(float timeStep, Vector3 error)
{
if (!Enabled) return Vector3.Zero;
@ -331,15 +433,17 @@ public class BSPIDVMotor : BSVMotor
RunningIntegration += error * timeStep;
// A simple derivitive is the rate of change from the last error.
Vector3 derivFactor = (error - LastError) * timeStep;
Vector3 derivitive = (error - LastError) * timeStep;
LastError = error;
// Correction = -(proportionOfPresentError + accumulationOfPastError + rateOfChangeOfError)
Vector3 ret = -(
error * proportionFactor
+ RunningIntegration * integralFactor
+ derivFactor * derivFactor
);
// Correction = (proportionOfPresentError + accumulationOfPastError + rateOfChangeOfError)
Vector3 ret = error * timeStep * proportionFactor * FactorMix.X
+ RunningIntegration * integralFactor * FactorMix.Y
+ derivitive * derivFactor * FactorMix.Z
;
MDetailLog("{0},BSPIDVMotor.step,ts={1},err={2},runnInt={3},deriv={4},ret={5}",
BSScene.DetailLogZero, timeStep, error, RunningIntegration, derivitive, ret);
return ret;
}

File diff suppressed because it is too large Load Diff

View File

@ -38,12 +38,12 @@ namespace OpenSim.Region.Physics.BulletSPlugin
* Class to wrap all objects.
* The rest of BulletSim doesn't need to keep checking for avatars or prims
* unless the difference is significant.
*
*
* Variables in the physicsl objects are in three forms:
* VariableName: used by the simulator and performs taint operations, etc
* RawVariableName: direct reference to the BulletSim storage for the variable value
* ForceVariableName: direct reference (store and fetch) to the value in the physics engine.
* The last two (and certainly the last one) should be referenced only in taint-time.
* The last one should only be referenced in taint-time.
*/
/*
@ -52,9 +52,19 @@ namespace OpenSim.Region.Physics.BulletSPlugin
* SOP.ApplyImpulse SOP.ApplyAngularImpulse SOP.SetAngularImpulse SOP.SetForce
* SOG.ApplyImpulse SOG.ApplyAngularImpulse SOG.SetAngularImpulse
* PA.AddForce PA.AddAngularForce PA.Torque = v PA.Force = v
* BS.ApplyCentralForce BS.ApplyTorque
* BS.ApplyCentralForce BS.ApplyTorque
*/
// Flags used to denote which properties updates when making UpdateProperties calls to linksets, etc.
public enum UpdatedProperties : uint
{
Position = 1 << 0,
Orientation = 1 << 1,
Velocity = 1 << 2,
Acceleration = 1 << 3,
RotationalVelocity = 1 << 4,
EntPropUpdates = Position | Orientation | Velocity | Acceleration | RotationalVelocity,
}
public abstract class BSPhysObject : PhysicsActor
{
protected BSPhysObject()
@ -62,41 +72,61 @@ public abstract class BSPhysObject : PhysicsActor
}
protected BSPhysObject(BSScene parentScene, uint localID, string name, string typeName)
{
PhysicsScene = parentScene;
PhysScene = parentScene;
LocalID = localID;
PhysObjectName = name;
Name = name; // PhysicsActor also has the name of the object. Someday consolidate.
TypeName = typeName;
// The collection of things that push me around
PhysicalActors = new BSActorCollection(PhysScene);
// Initialize variables kept in base.
GravModifier = 1.0f;
Gravity = new OMV.Vector3(0f, 0f, BSParam.Gravity);
HoverActive = false;
// We don't have any physical representation yet.
PhysBody = new BulletBody(localID);
PhysShape = new BulletShape();
PhysShape = new BSShapeNull();
// A linkset of just me
Linkset = BSLinkset.Factory(PhysicsScene, this);
LastAssetBuildFailed = false;
PrimAssetState = PrimAssetCondition.Unknown;
// Default material type
Material = MaterialAttributes.Material.Wood;
// Default material type. Also sets Friction, Restitution and Density.
SetMaterial((int)MaterialAttributes.Material.Wood);
CollisionCollection = new CollisionEventUpdate();
CollisionsLastReported = CollisionCollection;
CollisionsLastTick = new CollisionEventUpdate();
CollisionsLastTickStep = -1;
SubscribedEventsMs = 0;
CollidingStep = 0;
CollidingGroundStep = 0;
CollisionAccumulation = 0;
ColliderIsMoving = false;
CollisionScore = 0;
// All axis free.
LockedLinearAxis = LockedAxisFree;
LockedAngularAxis = LockedAxisFree;
}
// Tell the object to clean up.
public virtual void Destroy()
{
UnRegisterAllPreStepActions();
PhysicalActors.Enable(false);
PhysScene.TaintedObject("BSPhysObject.Destroy", delegate()
{
PhysicalActors.Dispose();
});
}
public BSScene PhysicsScene { get; protected set; }
public BSScene PhysScene { get; protected set; }
// public override uint LocalID { get; set; } // Use the LocalID definition in PhysicsActor
public string PhysObjectName { get; protected set; }
public string TypeName { get; protected set; }
public BSLinkset Linkset { get; set; }
public BSLinksetInfo LinksetInfo { get; set; }
// Return the object mass without calculating it or having side effects
public abstract float RawMass { get; }
@ -104,26 +134,26 @@ public abstract class BSPhysObject : PhysicsActor
// 'inWorld' true if the object has already been added to the dynamic world.
public abstract void UpdatePhysicalMassProperties(float mass, bool inWorld);
// The gravity being applied to the object. A function of default grav, GravityModifier and Buoyancy.
public virtual OMV.Vector3 Gravity { get; set; }
// The last value calculated for the prim's inertia
public OMV.Vector3 Inertia { get; set; }
// Reference to the physical body (btCollisionObject) of this object
public BulletBody PhysBody;
// Reference to the physical shape (btCollisionShape) of this object
public BulletShape PhysShape;
public BSShape PhysShape;
// 'true' if the mesh's underlying asset failed to build.
// This will keep us from looping after the first time the build failed.
public bool LastAssetBuildFailed { get; set; }
// The physical representation of the prim might require an asset fetch.
// The asset state is first 'Unknown' then 'Waiting' then either 'Failed' or 'Fetched'.
public enum PrimAssetCondition
{
Unknown, Waiting, Failed, Fetched
}
public PrimAssetCondition PrimAssetState { get; set; }
// The objects base shape information. Null if not a prim type shape.
public PrimitiveBaseShape BaseShape { get; protected set; }
// Some types of objects have preferred physical representations.
// Returns SHAPE_UNKNOWN if there is no preference.
public virtual BSPhysicsShapeType PreferredPhysicalShape
{
get { return BSPhysicsShapeType.SHAPE_UNKNOWN; }
}
// When the physical properties are updated, an EntityProperty holds the update values.
// Keep the current and last EntityProperties to enable computation of differences
@ -132,23 +162,35 @@ public abstract class BSPhysObject : PhysicsActor
public EntityProperties LastEntityProperties { get; set; }
public virtual OMV.Vector3 Scale { get; set; }
// It can be confusing for an actor to know if it should move or update an object
// depeneding on the setting of 'selected', 'physical, ...
// This flag is the true test -- if true, the object is being acted on in the physical world
public abstract bool IsPhysicallyActive { get; }
// Detailed state of the object.
public abstract bool IsSolid { get; }
public abstract bool IsStatic { get; }
public abstract bool IsSelected { get; }
// Materialness
public MaterialAttributes.Material Material { get; private set; }
public override void SetMaterial(int material)
{
Material = (MaterialAttributes.Material)material;
// Setting the material sets the material attributes also.
MaterialAttributes matAttrib = BSMaterials.GetAttributes(Material, false);
Friction = matAttrib.friction;
Restitution = matAttrib.restitution;
Density = matAttrib.density / BSParam.DensityScaleFactor;
// DetailLog("{0},{1}.SetMaterial,Mat={2},frict={3},rest={4},den={5}", LocalID, TypeName, Material, Friction, Restitution, Density);
}
// Stop all physical motion.
public abstract void ZeroMotion(bool inTaintTime);
public abstract void ZeroAngularMotion(bool inTaintTime);
// Step the vehicle simulation for this object. A NOOP if the vehicle was not configured.
public virtual void StepVehicle(float timeStep) { }
// Update the physical location and motion of the object. Called with data from Bullet.
public abstract void UpdateProperties(EntityProperties entprop);
@ -158,25 +200,122 @@ public abstract class BSPhysObject : PhysicsActor
public abstract OMV.Quaternion RawOrientation { get; set; }
public abstract OMV.Quaternion ForceOrientation { get; set; }
// The system is telling us the velocity it wants to move at.
// protected OMV.Vector3 m_targetVelocity; // use the definition in PhysicsActor
public override OMV.Vector3 TargetVelocity
{
get { return m_targetVelocity; }
set
{
m_targetVelocity = value;
Velocity = value;
}
}
public OMV.Vector3 RawVelocity { get; set; }
public abstract OMV.Vector3 ForceVelocity { get; set; }
public OMV.Vector3 RawForce { get; set; }
public OMV.Vector3 RawTorque { get; set; }
public override void AddAngularForce(OMV.Vector3 force, bool pushforce)
{
AddAngularForce(force, pushforce, false);
}
public abstract void AddAngularForce(OMV.Vector3 force, bool pushforce, bool inTaintTime);
public abstract OMV.Vector3 ForceRotationalVelocity { get; set; }
public abstract float ForceBuoyancy { get; set; }
public virtual bool ForceBodyShapeRebuild(bool inTaintTime) { return false; }
public override bool PIDActive { set { MoveToTargetActive = value; } }
public override OMV.Vector3 PIDTarget { set { MoveToTargetTarget = value; } }
public override float PIDTau { set { MoveToTargetTau = value; } }
public bool MoveToTargetActive { get; set; }
public OMV.Vector3 MoveToTargetTarget { get; set; }
public float MoveToTargetTau { get; set; }
// Used for llSetHoverHeight and maybe vehicle height. Hover Height will override MoveTo target's Z
public override bool PIDHoverActive { set { HoverActive = value; } }
public override float PIDHoverHeight { set { HoverHeight = value; } }
public override PIDHoverType PIDHoverType { set { HoverType = value; } }
public override float PIDHoverTau { set { HoverTau = value; } }
public bool HoverActive { get; set; }
public float HoverHeight { get; set; }
public PIDHoverType HoverType { get; set; }
public float HoverTau { get; set; }
// For RotLookAt
public override OMV.Quaternion APIDTarget { set { return; } }
public override bool APIDActive { set { return; } }
public override float APIDStrength { set { return; } }
public override float APIDDamping { set { return; } }
// The current velocity forward
public virtual float ForwardSpeed
{
get
{
OMV.Vector3 characterOrientedVelocity = RawVelocity * OMV.Quaternion.Inverse(OMV.Quaternion.Normalize(RawOrientation));
return characterOrientedVelocity.X;
}
}
// The forward speed we are trying to achieve (TargetVelocity)
public virtual float TargetVelocitySpeed
{
get
{
OMV.Vector3 characterOrientedVelocity = TargetVelocity * OMV.Quaternion.Inverse(OMV.Quaternion.Normalize(RawOrientation));
return characterOrientedVelocity.X;
}
}
// The user can optionally set the center of mass. The user's setting will override any
// computed center-of-mass (like in linksets).
// Note this is a displacement from the root's coordinates. Zero means use the root prim as center-of-mass.
public OMV.Vector3? UserSetCenterOfMassDisplacement { get; set; }
public OMV.Vector3 LockedLinearAxis { get; set; } // zero means locked. one means free.
public OMV.Vector3 LockedAngularAxis { get; set; } // zero means locked. one means free.
public const float FreeAxis = 1f;
public readonly OMV.Vector3 LockedAxisFree = new OMV.Vector3(FreeAxis, FreeAxis, FreeAxis); // All axis are free
// Enable physical actions. Bullet will keep sleeping non-moving physical objects so
// they need waking up when parameters are changed.
// Called in taint-time!!
public void ActivateIfPhysical(bool forceIt)
{
if (IsPhysical && PhysBody.HasPhysicalBody)
PhysScene.PE.Activate(PhysBody, forceIt);
}
// 'actors' act on the physical object to change or constrain its motion. These can range from
// hovering to complex vehicle motion.
// May be called at non-taint time as this just adds the actor to the action list and the real
// work is done during the simulation step.
// Note that, if the actor is already in the list and we are disabling same, the actor is just left
// in the list disabled.
public delegate BSActor CreateActor();
public void EnableActor(bool enableActor, string actorName, CreateActor creator)
{
lock (PhysicalActors)
{
BSActor theActor;
if (PhysicalActors.TryGetActor(actorName, out theActor))
{
// The actor already exists so just turn it on or off
DetailLog("{0},BSPhysObject.EnableActor,enablingExistingActor,name={1},enable={2}", LocalID, actorName, enableActor);
theActor.Enabled = enableActor;
}
else
{
// The actor does not exist. If it should, create it.
if (enableActor)
{
DetailLog("{0},BSPhysObject.EnableActor,creatingActor,name={1}", LocalID, actorName);
theActor = creator();
PhysicalActors.Add(actorName, theActor);
theActor.Enabled = true;
}
else
{
DetailLog("{0},BSPhysObject.EnableActor,notCreatingActorSinceNotEnabled,name={1}", LocalID, actorName);
}
}
}
}
#region Collisions
// Requested number of milliseconds between collision events. Zero means disabled.
@ -191,41 +330,56 @@ public abstract class BSPhysObject : PhysicsActor
protected long CollidingObjectStep { get; set; }
// The collision flags we think are set in Bullet
protected CollisionFlags CurrentCollisionFlags { get; set; }
// On a collision, check the collider and remember if the last collider was moving
// Used to modify the standing of avatars (avatars on stationary things stand still)
public bool ColliderIsMoving;
// Used by BSCharacter to manage standing (and not slipping)
public bool IsStationary;
// Count of collisions for this object
protected long CollisionAccumulation { get; set; }
public override bool IsColliding {
get { return (CollidingStep == PhysicsScene.SimulationStep); }
get { return (CollidingStep == PhysScene.SimulationStep); }
set {
if (value)
CollidingStep = PhysicsScene.SimulationStep;
CollidingStep = PhysScene.SimulationStep;
else
CollidingStep = 0;
}
}
public override bool CollidingGround {
get { return (CollidingGroundStep == PhysicsScene.SimulationStep); }
get { return (CollidingGroundStep == PhysScene.SimulationStep); }
set
{
if (value)
CollidingGroundStep = PhysicsScene.SimulationStep;
CollidingGroundStep = PhysScene.SimulationStep;
else
CollidingGroundStep = 0;
}
}
public override bool CollidingObj {
get { return (CollidingObjectStep == PhysicsScene.SimulationStep); }
set {
get { return (CollidingObjectStep == PhysScene.SimulationStep); }
set {
if (value)
CollidingObjectStep = PhysicsScene.SimulationStep;
CollidingObjectStep = PhysScene.SimulationStep;
else
CollidingObjectStep = 0;
}
}
// The collisions that have been collected this tick
// The collisions that have been collected for the next collision reporting (throttled by subscription)
protected CollisionEventUpdate CollisionCollection;
// This is the collision collection last reported to the Simulator.
public CollisionEventUpdate CollisionsLastReported;
// Remember the collisions recorded in the last tick for fancy collision checking
// (like a BSCharacter walking up stairs).
public CollisionEventUpdate CollisionsLastTick;
private long CollisionsLastTickStep = -1;
// The simulation step is telling this object about a collision.
// Return 'true' if a collision was processed and should be sent up.
// Return 'false' if this object is not enabled/subscribed/appropriate for or has already seen this collision.
// Called at taint time from within the Step() function
public virtual bool Collide(uint collidingWith, BSPhysObject collidee,
OMV.Vector3 contactPoint, OMV.Vector3 contactNormal, float pentrationDepth)
@ -233,27 +387,35 @@ public abstract class BSPhysObject : PhysicsActor
bool ret = false;
// The following lines make IsColliding(), CollidingGround() and CollidingObj work
CollidingStep = PhysicsScene.SimulationStep;
if (collidingWith <= PhysicsScene.TerrainManager.HighestTerrainID)
CollidingStep = PhysScene.SimulationStep;
if (collidingWith <= PhysScene.TerrainManager.HighestTerrainID)
{
CollidingGroundStep = PhysicsScene.SimulationStep;
CollidingGroundStep = PhysScene.SimulationStep;
}
else
{
CollidingObjectStep = PhysicsScene.SimulationStep;
CollidingObjectStep = PhysScene.SimulationStep;
}
// prims in the same linkset cannot collide with each other
if (collidee != null && (this.Linkset.LinksetID == collidee.Linkset.LinksetID))
CollisionAccumulation++;
// For movement tests, remember if we are colliding with an object that is moving.
ColliderIsMoving = collidee != null ? (collidee.RawVelocity != OMV.Vector3.Zero) : false;
// Make a collection of the collisions that happened the last simulation tick.
// This is different than the collection created for sending up to the simulator as it is cleared every tick.
if (CollisionsLastTickStep != PhysScene.SimulationStep)
{
return ret;
CollisionsLastTick = new CollisionEventUpdate();
CollisionsLastTickStep = PhysScene.SimulationStep;
}
CollisionsLastTick.AddCollider(collidingWith, new ContactPoint(contactPoint, contactNormal, pentrationDepth));
// if someone has subscribed for collision events....
// If someone has subscribed for collision events log the collision so it will be reported up
if (SubscribedEvents()) {
CollisionCollection.AddCollider(collidingWith, new ContactPoint(contactPoint, contactNormal, pentrationDepth));
DetailLog("{0},{1}.Collison.AddCollider,call,with={2},point={3},normal={4},depth={5}",
LocalID, TypeName, collidingWith, contactPoint, contactNormal, pentrationDepth);
DetailLog("{0},{1}.Collison.AddCollider,call,with={2},point={3},normal={4},depth={5},colliderMoving={6}",
LocalID, TypeName, collidingWith, contactPoint, contactNormal, pentrationDepth, ColliderIsMoving);
ret = true;
}
@ -267,13 +429,14 @@ public abstract class BSPhysObject : PhysicsActor
public virtual bool SendCollisions()
{
bool ret = true;
// If the 'no collision' call, force it to happen right now so quick collision_end
bool force = (CollisionCollection.Count == 0);
bool force = (CollisionCollection.Count == 0 && CollisionsLastReported.Count != 0);
// throttle the collisions to the number of milliseconds specified in the subscription
if (force || (PhysicsScene.SimulationNowTime >= NextCollisionOkTime))
if (force || (PhysScene.SimulationNowTime >= NextCollisionOkTime))
{
NextCollisionOkTime = PhysicsScene.SimulationNowTime + SubscribedEventsMs;
NextCollisionOkTime = PhysScene.SimulationNowTime + SubscribedEventsMs;
// We are called if we previously had collisions. If there are no collisions
// this time, send up one last empty event so OpenSim can sense collision end.
@ -283,12 +446,15 @@ public abstract class BSPhysObject : PhysicsActor
ret = false;
}
// DetailLog("{0},{1}.SendCollisionUpdate,call,numCollisions={2}", LocalID, TypeName, CollisionCollection.Count);
DetailLog("{0},{1}.SendCollisionUpdate,call,numCollisions={2}", LocalID, TypeName, CollisionCollection.Count);
base.SendCollisionUpdate(CollisionCollection);
// Remember the collisions from this tick for some collision specific processing.
CollisionsLastReported = CollisionCollection;
// The CollisionCollection instance is passed around in the simulator.
// Make sure we don't have a handle to that one and that a new one is used for next time.
// This fixes an interesting 'gotcha'. If we call CollisionCollection.Clear() here,
// This fixes an interesting 'gotcha'. If we call CollisionCollection.Clear() here,
// a race condition is created for the other users of this instance.
CollisionCollection = new CollisionEventUpdate();
}
@ -305,10 +471,10 @@ public abstract class BSPhysObject : PhysicsActor
// make sure first collision happens
NextCollisionOkTime = Util.EnvironmentTickCountSubtract(SubscribedEventsMs);
PhysicsScene.TaintedObject(TypeName+".SubscribeEvents", delegate()
PhysScene.TaintedObject(TypeName+".SubscribeEvents", delegate()
{
if (PhysBody.HasPhysicalBody)
CurrentCollisionFlags = PhysicsScene.PE.AddToCollisionFlags(PhysBody, CollisionFlags.BS_SUBSCRIBE_COLLISION_EVENTS);
CurrentCollisionFlags = PhysScene.PE.AddToCollisionFlags(PhysBody, CollisionFlags.BS_SUBSCRIBE_COLLISION_EVENTS);
});
}
else
@ -320,66 +486,53 @@ public abstract class BSPhysObject : PhysicsActor
public override void UnSubscribeEvents() {
// DetailLog("{0},{1}.UnSubscribeEvents,unsubscribing", LocalID, TypeName);
SubscribedEventsMs = 0;
PhysicsScene.TaintedObject(TypeName+".UnSubscribeEvents", delegate()
PhysScene.TaintedObject(TypeName+".UnSubscribeEvents", delegate()
{
// Make sure there is a body there because sometimes destruction happens in an un-ideal order.
if (PhysBody.HasPhysicalBody)
CurrentCollisionFlags = PhysicsScene.PE.RemoveFromCollisionFlags(PhysBody, CollisionFlags.BS_SUBSCRIBE_COLLISION_EVENTS);
CurrentCollisionFlags = PhysScene.PE.RemoveFromCollisionFlags(PhysBody, CollisionFlags.BS_SUBSCRIBE_COLLISION_EVENTS);
});
}
// Return 'true' if the simulator wants collision events
public override bool SubscribedEvents() {
return (SubscribedEventsMs > 0);
}
// Because 'CollisionScore' is called many times while sorting, it should not be recomputed
// each time called. So this is built to be light weight for each collision and to do
// all the processing when the user asks for the info.
public void ComputeCollisionScore()
{
// Scale the collision count by the time since the last collision.
// The "+1" prevents dividing by zero.
long timeAgo = PhysScene.SimulationStep - CollidingStep + 1;
CollisionScore = CollisionAccumulation / timeAgo;
}
public override float CollisionScore { get; set; }
#endregion // Collisions
#region Per Simulation Step actions
// There are some actions that must be performed for a physical object before each simulation step.
// These actions are optional so, rather than scanning all the physical objects and asking them
// if they have anything to do, a physical object registers for an event call before the step is performed.
// This bookkeeping makes it easy to add, remove and clean up after all these registrations.
private Dictionary<string, BSScene.PreStepAction> RegisteredActions = new Dictionary<string, BSScene.PreStepAction>();
protected void RegisterPreStepAction(string op, uint id, BSScene.PreStepAction actn)
public BSActorCollection PhysicalActors;
// When an update to the physical properties happens, this event is fired to let
// different actors to modify the update before it is passed around
public delegate void PreUpdatePropertyAction(ref EntityProperties entprop);
public event PreUpdatePropertyAction OnPreUpdateProperty;
protected void TriggerPreUpdatePropertyAction(ref EntityProperties entprop)
{
string identifier = op + "-" + id.ToString();
RegisteredActions[identifier] = actn;
PhysicsScene.BeforeStep += actn;
DetailLog("{0},BSPhysObject.RegisterPreStepAction,id={1}", LocalID, identifier);
PreUpdatePropertyAction actions = OnPreUpdateProperty;
if (actions != null)
actions(ref entprop);
}
// Unregister a pre step action. Safe to call if the action has not been registered.
protected void UnRegisterPreStepAction(string op, uint id)
{
string identifier = op + "-" + id.ToString();
bool removed = false;
if (RegisteredActions.ContainsKey(identifier))
{
PhysicsScene.BeforeStep -= RegisteredActions[identifier];
RegisteredActions.Remove(identifier);
removed = true;
}
DetailLog("{0},BSPhysObject.UnRegisterPreStepAction,id={1},removed={2}", LocalID, identifier, removed);
}
protected void UnRegisterAllPreStepActions()
{
foreach (KeyValuePair<string, BSScene.PreStepAction> kvp in RegisteredActions)
{
PhysicsScene.BeforeStep -= kvp.Value;
}
RegisteredActions.Clear();
DetailLog("{0},BSPhysObject.UnRegisterAllPreStepActions,", LocalID);
}
#endregion // Per Simulation Step actions
// High performance detailed logging routine used by the physical objects.
protected void DetailLog(string msg, params Object[] args)
{
if (PhysicsScene.PhysicsLogging.Enabled)
PhysicsScene.DetailLog(msg, args);
if (PhysScene.PhysicsLogging.Enabled)
PhysScene.DetailLog(msg, args);
}
}

View File

@ -59,7 +59,7 @@ public class BSPlugin : IPhysicsPlugin
{
if (_mScene == null)
{
_mScene = new BSScene(sceneIdentifier);
_mScene = new BSScene(GetName(), sceneIdentifier);
}
return (_mScene);
}

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,165 @@
/*
* Copyright (c) Contributors, http://opensimulator.org/
* See CONTRIBUTORS.TXT for a full list of copyright holders.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the OpenSimulator Project nor the
* names of its contributors may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE DEVELOPERS ``AS IS'' AND ANY
* EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE CONTRIBUTORS BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
* The quotations from http://wiki.secondlife.com/wiki/Linden_Vehicle_Tutorial
* are Copyright (c) 2009 Linden Research, Inc and are used under their license
* of Creative Commons Attribution-Share Alike 3.0
* (http://creativecommons.org/licenses/by-sa/3.0/).
*/
using System;
using System.Collections.Generic;
using System.Reflection;
using System.Runtime.InteropServices;
using OpenMetaverse;
using OpenSim.Framework;
using OpenSim.Region.Physics.Manager;
using OMV = OpenMetaverse;
namespace OpenSim.Region.Physics.BulletSPlugin
{
public class BSPrimDisplaced : BSPrim
{
// The purpose of this module is to do any mapping between what the simulator thinks
// the prim position and orientation is and what the physical position/orientation.
// This difference happens because Bullet assumes the center-of-mass is the <0,0,0>
// of the prim/linkset. The simulator tracks the location of the prim/linkset by
// the location of the root prim. So, if center-of-mass is anywhere but the origin
// of the root prim, the physical origin is displaced from the simulator origin.
//
// This routine works by capturing the Force* setting of position/orientation/... and
// adjusting the simulator values (being set) into the physical values.
// The conversion is also done in the opposite direction (physical origin -> simulator origin).
//
// The updateParameter call is also captured and the values from the physics engine
// are converted into simulator origin values before being passed to the base
// class.
public virtual OMV.Vector3 PositionDisplacement { get; set; }
public virtual OMV.Quaternion OrientationDisplacement { get; set; }
public BSPrimDisplaced(uint localID, String primName, BSScene parent_scene, OMV.Vector3 pos, OMV.Vector3 size,
OMV.Quaternion rotation, PrimitiveBaseShape pbs, bool pisPhysical)
: base(localID, primName, parent_scene, pos, size, rotation, pbs, pisPhysical)
{
ClearDisplacement();
}
public void ClearDisplacement()
{
PositionDisplacement = OMV.Vector3.Zero;
OrientationDisplacement = OMV.Quaternion.Identity;
}
// Set this sets and computes the displacement from the passed prim to the center-of-mass.
// A user set value for center-of-mass overrides whatever might be passed in here.
// The displacement is in local coordinates (relative to root prim in linkset oriented coordinates).
public virtual void SetEffectiveCenterOfMassDisplacement(Vector3 centerOfMassDisplacement)
{
Vector3 comDisp;
if (UserSetCenterOfMassDisplacement.HasValue)
comDisp = (OMV.Vector3)UserSetCenterOfMassDisplacement;
else
comDisp = centerOfMassDisplacement;
DetailLog("{0},BSPrimDisplaced.SetEffectiveCenterOfMassDisplacement,userSet={1},comDisp={2}",
LocalID, UserSetCenterOfMassDisplacement.HasValue, comDisp);
if (comDisp == Vector3.Zero)
{
// If there is no diplacement. Things get reset.
PositionDisplacement = OMV.Vector3.Zero;
OrientationDisplacement = OMV.Quaternion.Identity;
}
else
{
// Remember the displacement from root as well as the origional rotation of the
// new center-of-mass.
PositionDisplacement = comDisp;
OrientationDisplacement = OMV.Quaternion.Identity;
}
}
public override Vector3 ForcePosition
{
get { return base.ForcePosition; }
set
{
if (PositionDisplacement != OMV.Vector3.Zero)
{
OMV.Vector3 displacedPos = value - (PositionDisplacement * RawOrientation);
DetailLog("{0},BSPrimDisplaced.ForcePosition,val={1},disp={2},newPos={3}", LocalID, value, PositionDisplacement, displacedPos);
base.ForcePosition = displacedPos;
}
else
{
base.ForcePosition = value;
}
}
}
public override Quaternion ForceOrientation
{
get { return base.ForceOrientation; }
set
{
// TODO:
base.ForceOrientation = value;
}
}
// TODO: decide if this is the right place for these variables.
// Somehow incorporate the optional settability by the user.
// Is this used?
public override OMV.Vector3 CenterOfMass
{
get { return RawPosition; }
}
// Is this used?
public override OMV.Vector3 GeometricCenter
{
get { return RawPosition; }
}
public override void UpdateProperties(EntityProperties entprop)
{
// Undo any center-of-mass displacement that might have been done.
if (PositionDisplacement != OMV.Vector3.Zero || OrientationDisplacement != OMV.Quaternion.Identity)
{
// Correct for any rotation around the center-of-mass
// TODO!!!
OMV.Vector3 displacedPos = entprop.Position + (PositionDisplacement * entprop.Rotation);
DetailLog("{0},BSPrimDisplaced.ForcePosition,physPos={1},disp={2},newPos={3}", LocalID, entprop.Position, PositionDisplacement, displacedPos);
entprop.Position = displacedPos;
// entprop.Rotation = something;
}
base.UpdateProperties(entprop);
}
}
}

View File

@ -0,0 +1,192 @@
/*
* Copyright (c) Contributors, http://opensimulator.org/
* See CONTRIBUTORS.TXT for a full list of copyright holders.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyrightD
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the OpenSimulator Project nor the
* names of its contributors may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE DEVELOPERS ``AS IS'' AND ANY
* EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE CONTRIBUTORS BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
using OpenSim.Framework;
using OMV = OpenMetaverse;
namespace OpenSim.Region.Physics.BulletSPlugin
{
public class BSPrimLinkable : BSPrimDisplaced
{
public BSLinkset Linkset { get; set; }
// The index of this child prim.
public int LinksetChildIndex { get; set; }
public BSLinksetInfo LinksetInfo { get; set; }
public BSPrimLinkable(uint localID, String primName, BSScene parent_scene, OMV.Vector3 pos, OMV.Vector3 size,
OMV.Quaternion rotation, PrimitiveBaseShape pbs, bool pisPhysical)
: base(localID, primName, parent_scene, pos, size, rotation, pbs, pisPhysical)
{
Linkset = BSLinkset.Factory(PhysScene, this);
PhysScene.TaintedObject("BSPrimLinksetCompound.Refresh", delegate()
{
Linkset.Refresh(this);
});
}
public override void Destroy()
{
Linkset = Linkset.RemoveMeFromLinkset(this);
base.Destroy();
}
public override void link(Manager.PhysicsActor obj)
{
BSPrimLinkable parent = obj as BSPrimLinkable;
if (parent != null)
{
BSPhysObject parentBefore = Linkset.LinksetRoot;
int childrenBefore = Linkset.NumberOfChildren;
Linkset = parent.Linkset.AddMeToLinkset(this);
DetailLog("{0},BSPrimLinkset.link,call,parentBefore={1}, childrenBefore=={2}, parentAfter={3}, childrenAfter={4}",
LocalID, parentBefore.LocalID, childrenBefore, Linkset.LinksetRoot.LocalID, Linkset.NumberOfChildren);
}
return;
}
public override void delink()
{
// TODO: decide if this parent checking needs to happen at taint time
// Race condition here: if link() and delink() in same simulation tick, the delink will not happen
BSPhysObject parentBefore = Linkset.LinksetRoot;
int childrenBefore = Linkset.NumberOfChildren;
Linkset = Linkset.RemoveMeFromLinkset(this);
DetailLog("{0},BSPrimLinkset.delink,parentBefore={1},childrenBefore={2},parentAfter={3},childrenAfter={4}, ",
LocalID, parentBefore.LocalID, childrenBefore, Linkset.LinksetRoot.LocalID, Linkset.NumberOfChildren);
return;
}
// When simulator changes position, this might be moving a child of the linkset.
public override OMV.Vector3 Position
{
get { return base.Position; }
set
{
base.Position = value;
PhysScene.TaintedObject("BSPrimLinkset.setPosition", delegate()
{
Linkset.UpdateProperties(UpdatedProperties.Position, this);
});
}
}
// When simulator changes orientation, this might be moving a child of the linkset.
public override OMV.Quaternion Orientation
{
get { return base.Orientation; }
set
{
base.Orientation = value;
PhysScene.TaintedObject("BSPrimLinkset.setOrientation", delegate()
{
Linkset.UpdateProperties(UpdatedProperties.Orientation, this);
});
}
}
public override float TotalMass
{
get { return Linkset.LinksetMass; }
}
public override void UpdatePhysicalParameters()
{
base.UpdatePhysicalParameters();
// Recompute any linkset parameters.
// When going from non-physical to physical, this re-enables the constraints that
// had been automatically disabled when the mass was set to zero.
// For compound based linksets, this enables and disables interactions of the children.
if (Linkset != null) // null can happen during initialization
Linkset.Refresh(this);
}
protected override void MakeDynamic(bool makeStatic)
{
base.MakeDynamic(makeStatic);
if (makeStatic)
Linkset.MakeStatic(this);
else
Linkset.MakeDynamic(this);
}
// Body is being taken apart. Remove physical dependencies and schedule a rebuild.
protected override void RemoveDependencies()
{
Linkset.RemoveDependencies(this);
base.RemoveDependencies();
}
public override void UpdateProperties(EntityProperties entprop)
{
if (Linkset.IsRoot(this))
{
// Properties are only updated for the roots of a linkset.
// TODO: this will have to change when linksets are articulated.
base.UpdateProperties(entprop);
}
/*
else
{
// For debugging, report the movement of children
DetailLog("{0},BSPrim.UpdateProperties,child,pos={1},orient={2},vel={3},accel={4},rotVel={5}",
LocalID, entprop.Position, entprop.Rotation, entprop.Velocity,
entprop.Acceleration, entprop.RotationalVelocity);
}
*/
// The linkset might like to know about changing locations
Linkset.UpdateProperties(UpdatedProperties.EntPropUpdates, this);
}
public override bool Collide(uint collidingWith, BSPhysObject collidee,
OMV.Vector3 contactPoint, OMV.Vector3 contactNormal, float pentrationDepth)
{
// prims in the same linkset cannot collide with each other
BSPrimLinkable convCollidee = collidee as BSPrimLinkable;
if (convCollidee != null && (this.Linkset.LinksetID == convCollidee.Linkset.LinksetID))
{
return false;
}
// TODO: handle collisions of other objects with with children of linkset.
// This is a problem for LinksetCompound since the children are packed into the root.
return base.Collide(collidingWith, collidee, contactPoint, contactNormal, pentrationDepth);
}
}
}

View File

@ -26,6 +26,7 @@
*/
using System;
using System.Collections.Generic;
using System.Linq;
using System.Reflection;
using System.Runtime.InteropServices;
using System.Text;
@ -81,14 +82,13 @@ public sealed class BSScene : PhysicsScene, IPhysicsParameters
internal long m_simulationStep = 0;
internal float NominalFrameRate { get; set; }
public long SimulationStep { get { return m_simulationStep; } }
internal int m_taintsToProcessPerStep;
internal float LastTimeStep { get; private set; }
// Physical objects can register for prestep or poststep events
public delegate void PreStepAction(float timeStep);
public delegate void PostStepAction(float timeStep);
public event PreStepAction BeforeStep;
public event PreStepAction AfterStep;
public event PostStepAction AfterStep;
// A value of the time now so all the collision and update routines do not have to get their own
// Set to 'now' just before all the prims and actors are called for collisions and updates
@ -161,17 +161,22 @@ public sealed class BSScene : PhysicsScene, IPhysicsParameters
private int m_physicsLoggingFileMinutes;
private bool m_physicsLoggingDoFlush;
private bool m_physicsPhysicalDumpEnabled;
public float PhysicsMetricDumpFrames { get; set; }
public int PhysicsMetricDumpFrames { get; set; }
// 'true' of the vehicle code is to log lots of details
public bool VehicleLoggingEnabled { get; private set; }
public bool VehiclePhysicalLoggingEnabled { get; private set; }
#region Construction and Initialization
public BSScene(string identifier)
public BSScene(string engineType, string identifier)
{
m_initialized = false;
// we are passed the name of the region we're working for.
// The name of the region we're working for is passed to us. Keep for identification.
RegionName = identifier;
// Set identifying variables in the PhysicsScene interface.
EngineType = engineType;
Name = EngineType + "/" + RegionName;
}
public override void Initialise(IMesher meshmerizer, IConfigSource config)
@ -311,6 +316,10 @@ public sealed class BSScene : PhysicsScene, IPhysicsParameters
break;
case "bulletxna":
ret = new BSAPIXNA(engineName, this);
// Disable some features that are not implemented in BulletXNA
m_log.InfoFormat("{0} Disabling some physics features not implemented by BulletXNA", LogHeader);
BSParam.ShouldUseBulletHACD = false;
BSParam.ShouldUseSingleConvexHullForPrims = false;
break;
}
@ -382,12 +391,14 @@ public sealed class BSScene : PhysicsScene, IPhysicsParameters
if (!m_initialized) return null;
BSCharacter actor = new BSCharacter(localID, avName, this, position, size, isFlying);
lock (PhysObjects) PhysObjects.Add(localID, actor);
lock (PhysObjects)
PhysObjects.Add(localID, actor);
// TODO: Remove kludge someday.
// We must generate a collision for avatars whether they collide or not.
// This is required by OpenSim to update avatar animations, etc.
lock (m_avatars) m_avatars.Add(actor);
lock (m_avatars)
m_avatars.Add(actor);
return actor;
}
@ -403,9 +414,11 @@ public sealed class BSScene : PhysicsScene, IPhysicsParameters
{
try
{
lock (PhysObjects) PhysObjects.Remove(actor.LocalID);
lock (PhysObjects)
PhysObjects.Remove(bsactor.LocalID);
// Remove kludge someday
lock (m_avatars) m_avatars.Remove(bsactor);
lock (m_avatars)
m_avatars.Remove(bsactor);
}
catch (Exception e)
{
@ -414,13 +427,18 @@ public sealed class BSScene : PhysicsScene, IPhysicsParameters
bsactor.Destroy();
// bsactor.dispose();
}
else
{
m_log.ErrorFormat("{0}: Requested to remove avatar that is not a BSCharacter. ID={1}, type={2}",
LogHeader, actor.LocalID, actor.GetType().Name);
}
}
public override void RemovePrim(PhysicsActor prim)
{
if (!m_initialized) return;
BSPrim bsprim = prim as BSPrim;
BSPhysObject bsprim = prim as BSPhysObject;
if (bsprim != null)
{
DetailLog("{0},RemovePrim,call", bsprim.LocalID);
@ -449,9 +467,9 @@ public sealed class BSScene : PhysicsScene, IPhysicsParameters
if (!m_initialized) return null;
DetailLog("{0},AddPrimShape,call", localID);
// DetailLog("{0},BSScene.AddPrimShape,call", localID);
BSPrim prim = new BSPrim(localID, primName, this, position, size, rotation, pbs, isPhysical);
BSPhysObject prim = new BSPrimLinkable(localID, primName, this, position, size, rotation, pbs, isPhysical);
lock (PhysObjects) PhysObjects.Add(localID, prim);
return prim;
}
@ -486,6 +504,7 @@ public sealed class BSScene : PhysicsScene, IPhysicsParameters
ProcessTaints();
// Some of the physical objects requre individual, pre-step calls
// (vehicles and avatar movement, in particular)
TriggerPreStepEvent(timeStep);
// the prestep actions might have added taints
@ -527,7 +546,7 @@ public sealed class BSScene : PhysicsScene, IPhysicsParameters
collidersCount = 0;
}
if ((m_simulationStep % PhysicsMetricDumpFrames) == 0)
if (PhysicsMetricDumpFrames != 0 && ((m_simulationStep % PhysicsMetricDumpFrames) == 0))
PE.DumpPhysicsStatistics(World);
// Get a value for 'now' so all the collision and update routines don't have to get their own.
@ -543,8 +562,9 @@ public sealed class BSScene : PhysicsScene, IPhysicsParameters
uint cB = m_collisionArray[ii].bID;
Vector3 point = m_collisionArray[ii].point;
Vector3 normal = m_collisionArray[ii].normal;
SendCollision(cA, cB, point, normal, 0.01f);
SendCollision(cB, cA, point, -normal, 0.01f);
float penetration = m_collisionArray[ii].penetration;
SendCollision(cA, cB, point, normal, penetration);
SendCollision(cB, cA, point, -normal, penetration);
}
}
@ -682,7 +702,21 @@ public sealed class BSScene : PhysicsScene, IPhysicsParameters
public override Dictionary<uint, float> GetTopColliders()
{
return new Dictionary<uint, float>();
Dictionary<uint, float> topColliders;
lock (PhysObjects)
{
foreach (KeyValuePair<uint, BSPhysObject> kvp in PhysObjects)
{
kvp.Value.ComputeCollisionScore();
}
List<BSPhysObject> orderedPrims = new List<BSPhysObject>(PhysObjects.Values);
orderedPrims.OrderByDescending(p => p.CollisionScore);
topColliders = orderedPrims.Take(25).ToDictionary(p => p.LocalID, p => p.CollisionScore);
}
return topColliders;
}
public override bool IsThreaded { get { return false; } }
@ -694,8 +728,8 @@ public sealed class BSScene : PhysicsScene, IPhysicsParameters
// TriggerPreStepEvent
// DoOneTimeTaints
// Step()
// ProcessAndForwardCollisions
// ProcessAndForwardPropertyUpdates
// ProcessAndSendToSimulatorCollisions
// ProcessAndSendToSimulatorPropertyUpdates
// TriggerPostStepEvent
// Calls to the PhysicsActors can't directly call into the physics engine
@ -733,7 +767,7 @@ public sealed class BSScene : PhysicsScene, IPhysicsParameters
private void TriggerPostStepEvent(float timeStep)
{
PreStepAction actions = AfterStep;
PostStepAction actions = AfterStep;
if (actions != null)
actions(timeStep);
@ -825,15 +859,13 @@ public sealed class BSScene : PhysicsScene, IPhysicsParameters
{
DetailLog("{0},BSScene.AssertInTaintTime,NOT IN TAINT TIME,Region={1},Where={2}", DetailLogZero, RegionName, whereFrom);
m_log.ErrorFormat("{0} NOT IN TAINT TIME!! Region={1}, Where={2}", LogHeader, RegionName, whereFrom);
Util.PrintCallStack(DetailLog);
// Util.PrintCallStack(DetailLog);
}
return InTaintTime;
}
#endregion // Taints
#region INI and command line parameter processing
#region IPhysicsParameters
// Get the list of parameters this physics engine supports
public PhysParameterEntry[] GetParameterList()
@ -848,64 +880,65 @@ public sealed class BSScene : PhysicsScene, IPhysicsParameters
// will use the next time since it's pinned and shared memory.
// Some of the values require calling into the physics engine to get the new
// value activated ('terrainFriction' for instance).
public bool SetPhysicsParameter(string parm, float val, uint localID)
public bool SetPhysicsParameter(string parm, string val, uint localID)
{
bool ret = false;
BSParam.ParameterDefn theParam;
BSParam.ParameterDefnBase theParam;
if (BSParam.TryGetParameter(parm, out theParam))
{
theParam.setter(this, parm, localID, val);
// Set the value in the C# code
theParam.SetValue(this, val);
// Optionally set the parameter in the unmanaged code
if (theParam.HasSetOnObject)
{
// update all the localIDs specified
// If the local ID is APPLY_TO_NONE, just change the default value
// If the localID is APPLY_TO_ALL change the default value and apply the new value to all the lIDs
// If the localID is a specific object, apply the parameter change to only that object
List<uint> objectIDs = new List<uint>();
switch (localID)
{
case PhysParameterEntry.APPLY_TO_NONE:
// This will cause a call into the physical world if some operation is specified (SetOnObject).
objectIDs.Add(TERRAIN_ID);
TaintedUpdateParameter(parm, objectIDs, val);
break;
case PhysParameterEntry.APPLY_TO_ALL:
lock (PhysObjects) objectIDs = new List<uint>(PhysObjects.Keys);
TaintedUpdateParameter(parm, objectIDs, val);
break;
default:
// setting only one localID
objectIDs.Add(localID);
TaintedUpdateParameter(parm, objectIDs, val);
break;
}
}
ret = true;
}
return ret;
}
// update all the localIDs specified
// If the local ID is APPLY_TO_NONE, just change the default value
// If the localID is APPLY_TO_ALL change the default value and apply the new value to all the lIDs
// If the localID is a specific object, apply the parameter change to only that object
internal delegate void AssignVal(float x);
internal void UpdateParameterObject(AssignVal setDefault, string parm, uint localID, float val)
{
List<uint> objectIDs = new List<uint>();
switch (localID)
{
case PhysParameterEntry.APPLY_TO_NONE:
setDefault(val); // setting only the default value
// This will cause a call into the physical world if some operation is specified (SetOnObject).
objectIDs.Add(TERRAIN_ID);
TaintedUpdateParameter(parm, objectIDs, val);
break;
case PhysParameterEntry.APPLY_TO_ALL:
setDefault(val); // setting ALL also sets the default value
lock (PhysObjects) objectIDs = new List<uint>(PhysObjects.Keys);
TaintedUpdateParameter(parm, objectIDs, val);
break;
default:
// setting only one localID
objectIDs.Add(localID);
TaintedUpdateParameter(parm, objectIDs, val);
break;
}
}
// schedule the actual updating of the paramter to when the phys engine is not busy
private void TaintedUpdateParameter(string parm, List<uint> lIDs, float val)
private void TaintedUpdateParameter(string parm, List<uint> lIDs, string val)
{
float xval = val;
string xval = val;
List<uint> xlIDs = lIDs;
string xparm = parm;
TaintedObject("BSScene.UpdateParameterSet", delegate() {
BSParam.ParameterDefn thisParam;
BSParam.ParameterDefnBase thisParam;
if (BSParam.TryGetParameter(xparm, out thisParam))
{
if (thisParam.onObject != null)
if (thisParam.HasSetOnObject)
{
foreach (uint lID in xlIDs)
{
BSPhysObject theObject = null;
PhysObjects.TryGetValue(lID, out theObject);
thisParam.onObject(this, theObject, xval);
if (PhysObjects.TryGetValue(lID, out theObject))
thisParam.SetOnObject(this, theObject);
}
}
}
@ -914,14 +947,14 @@ public sealed class BSScene : PhysicsScene, IPhysicsParameters
// Get parameter.
// Return 'false' if not able to get the parameter.
public bool GetPhysicsParameter(string parm, out float value)
public bool GetPhysicsParameter(string parm, out string value)
{
float val = 0f;
string val = String.Empty;
bool ret = false;
BSParam.ParameterDefn theParam;
BSParam.ParameterDefnBase theParam;
if (BSParam.TryGetParameter(parm, out theParam))
{
val = theParam.getter(this);
val = theParam.GetValue(this);
ret = true;
}
value = val;
@ -930,8 +963,6 @@ public sealed class BSScene : PhysicsScene, IPhysicsParameters
#endregion IPhysicsParameters
#endregion Runtime settable parameters
// Invoke the detailed logger and output something if it's enabled.
public void DetailLog(string msg, params Object[] args)
{

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -68,7 +68,7 @@ public sealed class BSTerrainHeightmap : BSTerrainPhys
// This minCoords and maxCoords passed in give the size of the terrain (min and max Z
// are the high and low points of the heightmap).
public BSTerrainHeightmap(BSScene physicsScene, Vector3 regionBase, uint id, float[] initialMap,
public BSTerrainHeightmap(BSScene physicsScene, Vector3 regionBase, uint id, float[] initialMap,
Vector3 minCoords, Vector3 maxCoords)
: base(physicsScene, regionBase, id)
{
@ -92,7 +92,7 @@ public sealed class BSTerrainHeightmap : BSTerrainPhys
private void BuildHeightmapTerrain()
{
// Create the terrain shape from the mapInfo
m_mapInfo.terrainShape = PhysicsScene.PE.CreateTerrainShape( m_mapInfo.ID,
m_mapInfo.terrainShape = m_physicsScene.PE.CreateTerrainShape( m_mapInfo.ID,
new Vector3(m_mapInfo.sizeX, m_mapInfo.sizeY, 0), m_mapInfo.minZ, m_mapInfo.maxZ,
m_mapInfo.heightMap, 1f, BSParam.TerrainCollisionMargin);
@ -103,26 +103,26 @@ public sealed class BSTerrainHeightmap : BSTerrainPhys
centerPos.Y = m_mapInfo.minCoords.Y + (m_mapInfo.sizeY / 2f);
centerPos.Z = m_mapInfo.minZ + ((m_mapInfo.maxZ - m_mapInfo.minZ) / 2f);
m_mapInfo.terrainBody = PhysicsScene.PE.CreateBodyWithDefaultMotionState(m_mapInfo.terrainShape,
m_mapInfo.terrainBody = m_physicsScene.PE.CreateBodyWithDefaultMotionState(m_mapInfo.terrainShape,
m_mapInfo.ID, centerPos, Quaternion.Identity);
// Set current terrain attributes
PhysicsScene.PE.SetFriction(m_mapInfo.terrainBody, BSParam.TerrainFriction);
PhysicsScene.PE.SetHitFraction(m_mapInfo.terrainBody, BSParam.TerrainHitFraction);
PhysicsScene.PE.SetRestitution(m_mapInfo.terrainBody, BSParam.TerrainRestitution);
PhysicsScene.PE.SetCollisionFlags(m_mapInfo.terrainBody, CollisionFlags.CF_STATIC_OBJECT);
m_physicsScene.PE.SetFriction(m_mapInfo.terrainBody, BSParam.TerrainFriction);
m_physicsScene.PE.SetHitFraction(m_mapInfo.terrainBody, BSParam.TerrainHitFraction);
m_physicsScene.PE.SetRestitution(m_mapInfo.terrainBody, BSParam.TerrainRestitution);
m_physicsScene.PE.SetCollisionFlags(m_mapInfo.terrainBody, CollisionFlags.CF_STATIC_OBJECT);
// Return the new terrain to the world of physical objects
PhysicsScene.PE.AddObjectToWorld(PhysicsScene.World, m_mapInfo.terrainBody);
m_physicsScene.PE.AddObjectToWorld(m_physicsScene.World, m_mapInfo.terrainBody);
// redo its bounding box now that it is in the world
PhysicsScene.PE.UpdateSingleAabb(PhysicsScene.World, m_mapInfo.terrainBody);
m_physicsScene.PE.UpdateSingleAabb(m_physicsScene.World, m_mapInfo.terrainBody);
m_mapInfo.terrainBody.collisionType = CollisionType.Terrain;
m_mapInfo.terrainBody.ApplyCollisionMask(PhysicsScene);
m_mapInfo.terrainBody.ApplyCollisionMask(m_physicsScene);
// Make it so the terrain will not move or be considered for movement.
PhysicsScene.PE.ForceActivationState(m_mapInfo.terrainBody, ActivationState.DISABLE_SIMULATION);
m_physicsScene.PE.ForceActivationState(m_mapInfo.terrainBody, ActivationState.DISABLE_SIMULATION);
return;
}
@ -134,9 +134,9 @@ public sealed class BSTerrainHeightmap : BSTerrainPhys
{
if (m_mapInfo.terrainBody.HasPhysicalBody)
{
PhysicsScene.PE.RemoveObjectFromWorld(PhysicsScene.World, m_mapInfo.terrainBody);
m_physicsScene.PE.RemoveObjectFromWorld(m_physicsScene.World, m_mapInfo.terrainBody);
// Frees both the body and the shape.
PhysicsScene.PE.DestroyObject(PhysicsScene.World, m_mapInfo.terrainBody);
m_physicsScene.PE.DestroyObject(m_physicsScene.World, m_mapInfo.terrainBody);
}
}
m_mapInfo = null;
@ -155,7 +155,7 @@ public sealed class BSTerrainHeightmap : BSTerrainPhys
catch
{
// Sometimes they give us wonky values of X and Y. Give a warning and return something.
PhysicsScene.Logger.WarnFormat("{0} Bad request for terrain height. terrainBase={1}, pos={2}",
m_physicsScene.Logger.WarnFormat("{0} Bad request for terrain height. terrainBase={1}, pos={2}",
LogHeader, m_mapInfo.terrainRegionBase, pos);
ret = BSTerrainManager.HEIGHT_GETHEIGHT_RET;
}
@ -165,7 +165,7 @@ public sealed class BSTerrainHeightmap : BSTerrainPhys
// The passed position is relative to the base of the region.
public override float GetWaterLevelAtXYZ(Vector3 pos)
{
return PhysicsScene.SimpleWaterLevel;
return m_physicsScene.SimpleWaterLevel;
}
}
}

View File

@ -50,14 +50,14 @@ public abstract class BSTerrainPhys : IDisposable
Mesh = 1
}
public BSScene PhysicsScene { get; private set; }
protected BSScene m_physicsScene { get; private set; }
// Base of the region in world coordinates. Coordinates inside the region are relative to this.
public Vector3 TerrainBase { get; private set; }
public uint ID { get; private set; }
public BSTerrainPhys(BSScene physicsScene, Vector3 regionBase, uint id)
{
PhysicsScene = physicsScene;
m_physicsScene = physicsScene;
TerrainBase = regionBase;
ID = id;
}
@ -86,7 +86,7 @@ public sealed class BSTerrainManager : IDisposable
public Vector3 DefaultRegionSize = new Vector3(Constants.RegionSize, Constants.RegionSize, Constants.RegionHeight);
// The scene that I am part of
private BSScene PhysicsScene { get; set; }
private BSScene m_physicsScene { get; set; }
// The ground plane created to keep thing from falling to infinity.
private BulletBody m_groundPlane;
@ -113,7 +113,7 @@ public sealed class BSTerrainManager : IDisposable
public BSTerrainManager(BSScene physicsScene)
{
PhysicsScene = physicsScene;
m_physicsScene = physicsScene;
m_terrains = new Dictionary<Vector3,BSTerrainPhys>();
// Assume one region of default size
@ -132,32 +132,37 @@ public sealed class BSTerrainManager : IDisposable
// safe to call Bullet in real time. We hope no one is moving prims around yet.
public void CreateInitialGroundPlaneAndTerrain()
{
DetailLog("{0},BSTerrainManager.CreateInitialGroundPlaneAndTerrain,region={1}", BSScene.DetailLogZero, m_physicsScene.RegionName);
// The ground plane is here to catch things that are trying to drop to negative infinity
BulletShape groundPlaneShape = PhysicsScene.PE.CreateGroundPlaneShape(BSScene.GROUNDPLANE_ID, 1f, BSParam.TerrainCollisionMargin);
m_groundPlane = PhysicsScene.PE.CreateBodyWithDefaultMotionState(groundPlaneShape,
BulletShape groundPlaneShape = m_physicsScene.PE.CreateGroundPlaneShape(BSScene.GROUNDPLANE_ID, 1f, BSParam.TerrainCollisionMargin);
m_groundPlane = m_physicsScene.PE.CreateBodyWithDefaultMotionState(groundPlaneShape,
BSScene.GROUNDPLANE_ID, Vector3.Zero, Quaternion.Identity);
PhysicsScene.PE.AddObjectToWorld(PhysicsScene.World, m_groundPlane);
PhysicsScene.PE.UpdateSingleAabb(PhysicsScene.World, m_groundPlane);
m_physicsScene.PE.AddObjectToWorld(m_physicsScene.World, m_groundPlane);
m_physicsScene.PE.UpdateSingleAabb(m_physicsScene.World, m_groundPlane);
// Ground plane does not move
PhysicsScene.PE.ForceActivationState(m_groundPlane, ActivationState.DISABLE_SIMULATION);
m_physicsScene.PE.ForceActivationState(m_groundPlane, ActivationState.DISABLE_SIMULATION);
// Everything collides with the ground plane.
m_groundPlane.collisionType = CollisionType.Groundplane;
m_groundPlane.ApplyCollisionMask(PhysicsScene);
m_groundPlane.ApplyCollisionMask(m_physicsScene);
// Build an initial terrain and put it in the world. This quickly gets replaced by the real region terrain.
BSTerrainPhys initialTerrain = new BSTerrainHeightmap(PhysicsScene, Vector3.Zero, BSScene.TERRAIN_ID, DefaultRegionSize);
m_terrains.Add(Vector3.Zero, initialTerrain);
BSTerrainPhys initialTerrain = new BSTerrainHeightmap(m_physicsScene, Vector3.Zero, BSScene.TERRAIN_ID, DefaultRegionSize);
lock (m_terrains)
{
// Build an initial terrain and put it in the world. This quickly gets replaced by the real region terrain.
m_terrains.Add(Vector3.Zero, initialTerrain);
}
}
// Release all the terrain structures we might have allocated
public void ReleaseGroundPlaneAndTerrain()
{
DetailLog("{0},BSTerrainManager.ReleaseGroundPlaneAndTerrain,region={1}", BSScene.DetailLogZero, m_physicsScene.RegionName);
if (m_groundPlane.HasPhysicalBody)
{
if (PhysicsScene.PE.RemoveObjectFromWorld(PhysicsScene.World, m_groundPlane))
if (m_physicsScene.PE.RemoveObjectFromWorld(m_physicsScene.World, m_groundPlane))
{
PhysicsScene.PE.DestroyObject(PhysicsScene.World, m_groundPlane);
m_physicsScene.PE.DestroyObject(m_physicsScene.World, m_groundPlane);
}
m_groundPlane.Clear();
}
@ -183,7 +188,7 @@ public sealed class BSTerrainManager : IDisposable
float[] localHeightMap = heightMap;
// If there are multiple requests for changes to the same terrain between ticks,
// only do that last one.
PhysicsScene.PostTaintObject("TerrainManager.SetTerrain-"+ m_worldOffset.ToString(), 0, delegate()
m_physicsScene.PostTaintObject("TerrainManager.SetTerrain-"+ m_worldOffset.ToString(), 0, delegate()
{
if (m_worldOffset != Vector3.Zero && MegaRegionParentPhysicsScene != null)
{
@ -193,11 +198,9 @@ public sealed class BSTerrainManager : IDisposable
// the terrain is added to our parent
if (MegaRegionParentPhysicsScene is BSScene)
{
DetailLog("{0},SetTerrain.ToParent,offset={1},worldMax={2}",
BSScene.DetailLogZero, m_worldOffset, m_worldMax);
((BSScene)MegaRegionParentPhysicsScene).TerrainManager.UpdateTerrain(
BSScene.CHILDTERRAIN_ID, localHeightMap,
m_worldOffset, m_worldOffset + DefaultRegionSize, true);
DetailLog("{0},SetTerrain.ToParent,offset={1},worldMax={2}", BSScene.DetailLogZero, m_worldOffset, m_worldMax);
((BSScene)MegaRegionParentPhysicsScene).TerrainManager.AddMegaRegionChildTerrain(
BSScene.CHILDTERRAIN_ID, localHeightMap, m_worldOffset, m_worldOffset + DefaultRegionSize);
}
}
else
@ -205,26 +208,36 @@ public sealed class BSTerrainManager : IDisposable
// If not doing the mega-prim thing, just change the terrain
DetailLog("{0},SetTerrain.Existing", BSScene.DetailLogZero);
UpdateTerrain(BSScene.TERRAIN_ID, localHeightMap,
m_worldOffset, m_worldOffset + DefaultRegionSize, true);
UpdateTerrain(BSScene.TERRAIN_ID, localHeightMap, m_worldOffset, m_worldOffset + DefaultRegionSize);
}
});
}
// If called with no mapInfo for the terrain, this will create a new mapInfo and terrain
// Another region is calling this region and passing a terrain.
// A region that is not the mega-region root will pass its terrain to the root region so the root region
// physics engine will have all the terrains.
private void AddMegaRegionChildTerrain(uint id, float[] heightMap, Vector3 minCoords, Vector3 maxCoords)
{
// Since we are called by another region's thread, the action must be rescheduled onto our processing thread.
m_physicsScene.PostTaintObject("TerrainManager.AddMegaRegionChild" + minCoords.ToString(), id, delegate()
{
UpdateTerrain(id, heightMap, minCoords, maxCoords);
});
}
// If called for terrain has has not been previously allocated, a new terrain will be built
// based on the passed information. The 'id' should be either the terrain id or
// BSScene.CHILDTERRAIN_ID. If the latter, a new child terrain ID will be allocated and used.
// The latter feature is for creating child terrains for mega-regions.
// If called with a mapInfo in m_heightMaps and there is an existing terrain body, a new
// If there is an existing terrain body, a new
// terrain shape is created and added to the body.
// This call is most often used to update the heightMap and parameters of the terrain.
// (The above does suggest that some simplification/refactoring is in order.)
// Called during taint-time.
private void UpdateTerrain(uint id, float[] heightMap,
Vector3 minCoords, Vector3 maxCoords, bool inTaintTime)
private void UpdateTerrain(uint id, float[] heightMap, Vector3 minCoords, Vector3 maxCoords)
{
DetailLog("{0},BSTerrainManager.UpdateTerrain,call,minC={1},maxC={2},inTaintTime={3}",
BSScene.DetailLogZero, minCoords, maxCoords, inTaintTime);
DetailLog("{0},BSTerrainManager.UpdateTerrain,call,id={1},minC={2},maxC={3}",
BSScene.DetailLogZero, id, minCoords, maxCoords);
// Find high and low points of passed heightmap.
// The min and max passed in is usually the area objects can be in (maximum
@ -253,7 +266,7 @@ public sealed class BSTerrainManager : IDisposable
if (m_terrains.TryGetValue(terrainRegionBase, out terrainPhys))
{
// There is already a terrain in this spot. Free the old and build the new.
DetailLog("{0},UpdateTerrain:UpdateExisting,call,id={1},base={2},minC={3},maxC={4}",
DetailLog("{0},BSTErrainManager.UpdateTerrain:UpdateExisting,call,id={1},base={2},minC={3},maxC={4}",
BSScene.DetailLogZero, id, terrainRegionBase, minCoords, minCoords);
// Remove old terrain from the collection
@ -263,6 +276,7 @@ public sealed class BSTerrainManager : IDisposable
if (MegaRegionParentPhysicsScene == null)
{
// This terrain is not part of the mega-region scheme. Create vanilla terrain.
BSTerrainPhys newTerrainPhys = BuildPhysicalTerrain(terrainRegionBase, id, heightMap, minCoords, maxCoords);
m_terrains.Add(terrainRegionBase, newTerrainPhys);
@ -291,8 +305,8 @@ public sealed class BSTerrainManager : IDisposable
if (newTerrainID >= BSScene.CHILDTERRAIN_ID)
newTerrainID = ++m_terrainCount;
DetailLog("{0},UpdateTerrain:NewTerrain,taint,newID={1},minCoord={2},maxCoord={3}",
BSScene.DetailLogZero, newTerrainID, minCoords, minCoords);
DetailLog("{0},BSTerrainManager.UpdateTerrain:NewTerrain,taint,newID={1},minCoord={2},maxCoord={3}",
BSScene.DetailLogZero, newTerrainID, minCoords, maxCoords);
BSTerrainPhys newTerrainPhys = BuildPhysicalTerrain(terrainRegionBase, id, heightMap, minCoords, maxCoords);
m_terrains.Add(terrainRegionBase, newTerrainPhys);
@ -304,26 +318,26 @@ public sealed class BSTerrainManager : IDisposable
// TODO: redo terrain implementation selection to allow other base types than heightMap.
private BSTerrainPhys BuildPhysicalTerrain(Vector3 terrainRegionBase, uint id, float[] heightMap, Vector3 minCoords, Vector3 maxCoords)
{
PhysicsScene.Logger.DebugFormat("{0} Terrain for {1}/{2} created with {3}",
LogHeader, PhysicsScene.RegionName, terrainRegionBase,
m_physicsScene.Logger.DebugFormat("{0} Terrain for {1}/{2} created with {3}",
LogHeader, m_physicsScene.RegionName, terrainRegionBase,
(BSTerrainPhys.TerrainImplementation)BSParam.TerrainImplementation);
BSTerrainPhys newTerrainPhys = null;
switch ((int)BSParam.TerrainImplementation)
{
case (int)BSTerrainPhys.TerrainImplementation.Heightmap:
newTerrainPhys = new BSTerrainHeightmap(PhysicsScene, terrainRegionBase, id,
newTerrainPhys = new BSTerrainHeightmap(m_physicsScene, terrainRegionBase, id,
heightMap, minCoords, maxCoords);
break;
case (int)BSTerrainPhys.TerrainImplementation.Mesh:
newTerrainPhys = new BSTerrainMesh(PhysicsScene, terrainRegionBase, id,
newTerrainPhys = new BSTerrainMesh(m_physicsScene, terrainRegionBase, id,
heightMap, minCoords, maxCoords);
break;
default:
PhysicsScene.Logger.ErrorFormat("{0} Bad terrain implementation specified. Type={1}/{2},Region={3}/{4}",
LogHeader,
(int)BSParam.TerrainImplementation,
m_physicsScene.Logger.ErrorFormat("{0} Bad terrain implementation specified. Type={1}/{2},Region={3}/{4}",
LogHeader,
(int)BSParam.TerrainImplementation,
BSParam.TerrainImplementation,
PhysicsScene.RegionName, terrainRegionBase);
m_physicsScene.RegionName, terrainRegionBase);
break;
}
return newTerrainPhys;
@ -337,6 +351,53 @@ public sealed class BSTerrainManager : IDisposable
return GetTerrainPhysicalAtXYZ(pos, out physTerrain, out terrainBaseXYZ);
}
// Return a new position that is over known terrain if the position is outside our terrain.
public Vector3 ClampPositionIntoKnownTerrain(Vector3 pPos)
{
Vector3 ret = pPos;
// First, base addresses are never negative so correct for that possible problem.
if (ret.X < 0f || ret.Y < 0f)
{
ret.X = Util.Clamp<float>(ret.X, 0f, 1000000f);
ret.Y = Util.Clamp<float>(ret.Y, 0f, 1000000f);
DetailLog("{0},BSTerrainManager.ClampPositionToKnownTerrain,zeroingNegXorY,oldPos={1},newPos={2}",
BSScene.DetailLogZero, pPos, ret);
}
// Can't do this function if we don't know about any terrain.
if (m_terrains.Count == 0)
return ret;
int loopPrevention = 10;
Vector3 terrainBaseXYZ;
BSTerrainPhys physTerrain;
while (!GetTerrainPhysicalAtXYZ(ret, out physTerrain, out terrainBaseXYZ))
{
// The passed position is not within a known terrain area.
// NOTE that GetTerrainPhysicalAtXYZ will set 'terrainBaseXYZ' to the base of the unfound region.
// Must be off the top of a region. Find an adjacent region to move into.
Vector3 adjacentTerrainBase = FindAdjacentTerrainBase(terrainBaseXYZ);
ret.X = Math.Min(ret.X, adjacentTerrainBase.X + (ret.X % DefaultRegionSize.X));
ret.Y = Math.Min(ret.Y, adjacentTerrainBase.Y + (ret.X % DefaultRegionSize.Y));
DetailLog("{0},BSTerrainManager.ClampPositionToKnownTerrain,findingAdjacentRegion,adjacentRegBase={1},oldPos={2},newPos={3}",
BSScene.DetailLogZero, adjacentTerrainBase, pPos, ret);
if (loopPrevention-- < 0f)
{
// The 'while' is a little dangerous so this prevents looping forever if the
// mapping of the terrains ever gets messed up (like nothing at <0,0>) or
// the list of terrains is in transition.
DetailLog("{0},BSTerrainManager.ClampPositionToKnownTerrain,suppressingFindAdjacentRegionLoop", BSScene.DetailLogZero);
break;
}
}
return ret;
}
// Given an X and Y, find the height of the terrain.
// Since we could be handling multiple terrains for a mega-region,
// the base of the region is calcuated assuming all regions are
@ -368,8 +429,8 @@ public sealed class BSTerrainManager : IDisposable
}
else
{
PhysicsScene.Logger.ErrorFormat("{0} GetTerrainHeightAtXY: terrain not found: region={1}, x={2}, y={3}",
LogHeader, PhysicsScene.RegionName, tX, tY);
m_physicsScene.Logger.ErrorFormat("{0} GetTerrainHeightAtXY: terrain not found: region={1}, x={2}, y={3}",
LogHeader, m_physicsScene.RegionName, tX, tY);
DetailLog("{0},BSTerrainManager.GetTerrainHeightAtXYZ,terrainNotFound,pos={1},base={2}",
BSScene.DetailLogZero, pos, terrainBaseXYZ);
}
@ -390,8 +451,8 @@ public sealed class BSTerrainManager : IDisposable
}
else
{
PhysicsScene.Logger.ErrorFormat("{0} GetWaterHeightAtXY: terrain not found: pos={1}, terrainBase={2}, height={3}",
LogHeader, PhysicsScene.RegionName, pos, terrainBaseXYZ, ret);
m_physicsScene.Logger.ErrorFormat("{0} GetWaterHeightAtXY: terrain not found: pos={1}, terrainBase={2}, height={3}",
LogHeader, m_physicsScene.RegionName, pos, terrainBaseXYZ, ret);
}
return ret;
}
@ -400,18 +461,69 @@ public sealed class BSTerrainManager : IDisposable
// the descriptor class and the 'base' fo the addresses therein.
private bool GetTerrainPhysicalAtXYZ(Vector3 pos, out BSTerrainPhys outPhysTerrain, out Vector3 outTerrainBase)
{
int offsetX = ((int)(pos.X / (int)DefaultRegionSize.X)) * (int)DefaultRegionSize.X;
int offsetY = ((int)(pos.Y / (int)DefaultRegionSize.Y)) * (int)DefaultRegionSize.Y;
Vector3 terrainBaseXYZ = new Vector3(offsetX, offsetY, 0f);
bool ret = false;
Vector3 terrainBaseXYZ = Vector3.Zero;
if (pos.X < 0f || pos.Y < 0f)
{
// We don't handle negative addresses so just make up a base that will not be found.
terrainBaseXYZ = new Vector3(-DefaultRegionSize.X, -DefaultRegionSize.Y, 0f);
}
else
{
int offsetX = ((int)(pos.X / (int)DefaultRegionSize.X)) * (int)DefaultRegionSize.X;
int offsetY = ((int)(pos.Y / (int)DefaultRegionSize.Y)) * (int)DefaultRegionSize.Y;
terrainBaseXYZ = new Vector3(offsetX, offsetY, 0f);
}
BSTerrainPhys physTerrain = null;
lock (m_terrains)
{
m_terrains.TryGetValue(terrainBaseXYZ, out physTerrain);
ret = m_terrains.TryGetValue(terrainBaseXYZ, out physTerrain);
}
outTerrainBase = terrainBaseXYZ;
outPhysTerrain = physTerrain;
return (physTerrain != null);
return ret;
}
// Given a terrain base, return a terrain base for a terrain that is closer to <0,0> than
// this one. Usually used to return an out of bounds object to a known place.
private Vector3 FindAdjacentTerrainBase(Vector3 pTerrainBase)
{
Vector3 ret = pTerrainBase;
// Can't do this function if we don't know about any terrain.
if (m_terrains.Count == 0)
return ret;
// Just some sanity
ret.X = Util.Clamp<float>(ret.X, 0f, 1000000f);
ret.Y = Util.Clamp<float>(ret.Y, 0f, 1000000f);
ret.Z = 0f;
lock (m_terrains)
{
// Once down to the <0,0> region, we have to be done.
while (ret.X > 0f || ret.Y > 0f)
{
if (ret.X > 0f)
{
ret.X = Math.Max(0f, ret.X - DefaultRegionSize.X);
DetailLog("{0},BSTerrainManager.FindAdjacentTerrainBase,reducingX,terrainBase={1}", BSScene.DetailLogZero, ret);
if (m_terrains.ContainsKey(ret))
break;
}
if (ret.Y > 0f)
{
ret.Y = Math.Max(0f, ret.Y - DefaultRegionSize.Y);
DetailLog("{0},BSTerrainManager.FindAdjacentTerrainBase,reducingY,terrainBase={1}", BSScene.DetailLogZero, ret);
if (m_terrains.ContainsKey(ret))
break;
}
}
}
return ret;
}
// Although no one seems to check this, I do support combining.
@ -452,7 +564,7 @@ public sealed class BSTerrainManager : IDisposable
private void DetailLog(string msg, params Object[] args)
{
PhysicsScene.PhysicsLogging.Write(msg, args);
m_physicsScene.PhysicsLogging.Write(msg, args);
}
}
}

View File

@ -51,7 +51,7 @@ public sealed class BSTerrainMesh : BSTerrainPhys
BulletShape m_terrainShape;
BulletBody m_terrainBody;
public BSTerrainMesh(BSScene physicsScene, Vector3 regionBase, uint id, Vector3 regionSize)
public BSTerrainMesh(BSScene physicsScene, Vector3 regionBase, uint id, Vector3 regionSize)
: base(physicsScene, regionBase, id)
{
}
@ -62,7 +62,7 @@ public sealed class BSTerrainMesh : BSTerrainPhys
}
// Create terrain mesh from a heightmap.
public BSTerrainMesh(BSScene physicsScene, Vector3 regionBase, uint id, float[] initialMap,
public BSTerrainMesh(BSScene physicsScene, Vector3 regionBase, uint id, float[] initialMap,
Vector3 minCoords, Vector3 maxCoords)
: base(physicsScene, regionBase, id)
{
@ -76,27 +76,43 @@ public sealed class BSTerrainMesh : BSTerrainPhys
m_sizeX = (int)(maxCoords.X - minCoords.X);
m_sizeY = (int)(maxCoords.Y - minCoords.Y);
if (!BSTerrainMesh.ConvertHeightmapToMesh(PhysicsScene, initialMap,
m_sizeX, m_sizeY,
(float)m_sizeX, (float)m_sizeY,
Vector3.Zero, 1.0f,
out indicesCount, out indices, out verticesCount, out vertices))
bool meshCreationSuccess = false;
if (BSParam.TerrainMeshMagnification == 1)
{
// If a magnification of one, use the old routine that is tried and true.
meshCreationSuccess = BSTerrainMesh.ConvertHeightmapToMesh(m_physicsScene,
initialMap, m_sizeX, m_sizeY, // input size
Vector3.Zero, // base for mesh
out indicesCount, out indices, out verticesCount, out vertices);
}
else
{
// Other magnifications use the newer routine
meshCreationSuccess = BSTerrainMesh.ConvertHeightmapToMesh2(m_physicsScene,
initialMap, m_sizeX, m_sizeY, // input size
BSParam.TerrainMeshMagnification,
physicsScene.TerrainManager.DefaultRegionSize,
Vector3.Zero, // base for mesh
out indicesCount, out indices, out verticesCount, out vertices);
}
if (!meshCreationSuccess)
{
// DISASTER!!
PhysicsScene.DetailLog("{0},BSTerrainMesh.create,failedConversionOfHeightmap", ID);
PhysicsScene.Logger.ErrorFormat("{0} Failed conversion of heightmap to mesh! base={1}", LogHeader, TerrainBase);
m_physicsScene.DetailLog("{0},BSTerrainMesh.create,failedConversionOfHeightmap,id={1}", BSScene.DetailLogZero, ID);
m_physicsScene.Logger.ErrorFormat("{0} Failed conversion of heightmap to mesh! base={1}", LogHeader, TerrainBase);
// Something is very messed up and a crash is in our future.
return;
}
PhysicsScene.DetailLog("{0},BSTerrainMesh.create,meshed,indices={1},indSz={2},vertices={3},vertSz={4}",
ID, indicesCount, indices.Length, verticesCount, vertices.Length);
m_terrainShape = PhysicsScene.PE.CreateMeshShape(PhysicsScene.World, indicesCount, indices, verticesCount, vertices);
m_physicsScene.DetailLog("{0},BSTerrainMesh.create,meshed,id={1},indices={2},indSz={3},vertices={4},vertSz={5}",
BSScene.DetailLogZero, ID, indicesCount, indices.Length, verticesCount, vertices.Length);
m_terrainShape = m_physicsScene.PE.CreateMeshShape(m_physicsScene.World, indicesCount, indices, verticesCount, vertices);
if (!m_terrainShape.HasPhysicalShape)
{
// DISASTER!!
PhysicsScene.DetailLog("{0},BSTerrainMesh.create,failedCreationOfShape", ID);
physicsScene.Logger.ErrorFormat("{0} Failed creation of terrain mesh! base={1}", LogHeader, TerrainBase);
m_physicsScene.DetailLog("{0},BSTerrainMesh.create,failedCreationOfShape,id={1}", BSScene.DetailLogZero, ID);
m_physicsScene.Logger.ErrorFormat("{0} Failed creation of terrain mesh! base={1}", LogHeader, TerrainBase);
// Something is very messed up and a crash is in our future.
return;
}
@ -104,44 +120,54 @@ public sealed class BSTerrainMesh : BSTerrainPhys
Vector3 pos = regionBase;
Quaternion rot = Quaternion.Identity;
m_terrainBody = PhysicsScene.PE.CreateBodyWithDefaultMotionState(m_terrainShape, ID, pos, rot);
m_terrainBody = m_physicsScene.PE.CreateBodyWithDefaultMotionState(m_terrainShape, ID, pos, rot);
if (!m_terrainBody.HasPhysicalBody)
{
// DISASTER!!
physicsScene.Logger.ErrorFormat("{0} Failed creation of terrain body! base={1}", LogHeader, TerrainBase);
m_physicsScene.Logger.ErrorFormat("{0} Failed creation of terrain body! base={1}", LogHeader, TerrainBase);
// Something is very messed up and a crash is in our future.
return;
}
physicsScene.PE.SetShapeCollisionMargin(m_terrainShape, BSParam.TerrainCollisionMargin);
// Set current terrain attributes
PhysicsScene.PE.SetFriction(m_terrainBody, BSParam.TerrainFriction);
PhysicsScene.PE.SetHitFraction(m_terrainBody, BSParam.TerrainHitFraction);
PhysicsScene.PE.SetRestitution(m_terrainBody, BSParam.TerrainRestitution);
PhysicsScene.PE.SetCollisionFlags(m_terrainBody, CollisionFlags.CF_STATIC_OBJECT);
m_physicsScene.PE.SetFriction(m_terrainBody, BSParam.TerrainFriction);
m_physicsScene.PE.SetHitFraction(m_terrainBody, BSParam.TerrainHitFraction);
m_physicsScene.PE.SetRestitution(m_terrainBody, BSParam.TerrainRestitution);
m_physicsScene.PE.SetContactProcessingThreshold(m_terrainBody, BSParam.TerrainContactProcessingThreshold);
m_physicsScene.PE.SetCollisionFlags(m_terrainBody, CollisionFlags.CF_STATIC_OBJECT);
// Static objects are not very massive.
PhysicsScene.PE.SetMassProps(m_terrainBody, 0f, Vector3.Zero);
m_physicsScene.PE.SetMassProps(m_terrainBody, 0f, Vector3.Zero);
// Put the new terrain to the world of physical objects
PhysicsScene.PE.AddObjectToWorld(PhysicsScene.World, m_terrainBody);
m_physicsScene.PE.AddObjectToWorld(m_physicsScene.World, m_terrainBody);
// Redo its bounding box now that it is in the world
PhysicsScene.PE.UpdateSingleAabb(PhysicsScene.World, m_terrainBody);
m_physicsScene.PE.UpdateSingleAabb(m_physicsScene.World, m_terrainBody);
m_terrainBody.collisionType = CollisionType.Terrain;
m_terrainBody.ApplyCollisionMask(PhysicsScene);
m_terrainBody.ApplyCollisionMask(m_physicsScene);
if (BSParam.UseSingleSidedMeshes)
{
m_physicsScene.DetailLog("{0},BSTerrainMesh.settingCustomMaterial,id={1}", BSScene.DetailLogZero, id);
m_physicsScene.PE.AddToCollisionFlags(m_terrainBody, CollisionFlags.CF_CUSTOM_MATERIAL_CALLBACK);
}
// Make it so the terrain will not move or be considered for movement.
PhysicsScene.PE.ForceActivationState(m_terrainBody, ActivationState.DISABLE_SIMULATION);
m_physicsScene.PE.ForceActivationState(m_terrainBody, ActivationState.DISABLE_SIMULATION);
}
public override void Dispose()
{
if (m_terrainBody.HasPhysicalBody)
{
PhysicsScene.PE.RemoveObjectFromWorld(PhysicsScene.World, m_terrainBody);
m_physicsScene.PE.RemoveObjectFromWorld(m_physicsScene.World, m_terrainBody);
// Frees both the body and the shape.
PhysicsScene.PE.DestroyObject(PhysicsScene.World, m_terrainBody);
m_physicsScene.PE.DestroyObject(m_physicsScene.World, m_terrainBody);
m_terrainBody.Clear();
m_terrainShape.Clear();
}
}
@ -159,7 +185,7 @@ public sealed class BSTerrainMesh : BSTerrainPhys
catch
{
// Sometimes they give us wonky values of X and Y. Give a warning and return something.
PhysicsScene.Logger.WarnFormat("{0} Bad request for terrain height. terrainBase={1}, pos={2}",
m_physicsScene.Logger.WarnFormat("{0} Bad request for terrain height. terrainBase={1}, pos={2}",
LogHeader, TerrainBase, pos);
ret = BSTerrainManager.HEIGHT_GETHEIGHT_RET;
}
@ -169,17 +195,14 @@ public sealed class BSTerrainMesh : BSTerrainPhys
// The passed position is relative to the base of the region.
public override float GetWaterLevelAtXYZ(Vector3 pos)
{
return PhysicsScene.SimpleWaterLevel;
return m_physicsScene.SimpleWaterLevel;
}
// Convert the passed heightmap to mesh information suitable for CreateMeshShape2().
// Return 'true' if successfully created.
public static bool ConvertHeightmapToMesh(
BSScene physicsScene,
public static bool ConvertHeightmapToMesh( BSScene physicsScene,
float[] heightMap, int sizeX, int sizeY, // parameters of incoming heightmap
float extentX, float extentY, // zero based range for output vertices
Vector3 extentBase, // base to be added to all vertices
float magnification, // number of vertices to create between heightMap coords
out int indicesCountO, out int[] indicesO,
out int verticesCountO, out float[] verticesO)
{
@ -200,16 +223,15 @@ public sealed class BSTerrainMesh : BSTerrainPhys
// of the heightmap.
try
{
// One vertice per heightmap value plus the vertices off the top and bottom edge.
// One vertice per heightmap value plus the vertices off the side and bottom edge.
int totalVertices = (sizeX + 1) * (sizeY + 1);
vertices = new float[totalVertices * 3];
int totalIndices = sizeX * sizeY * 6;
indices = new int[totalIndices];
float magX = (float)sizeX / extentX;
float magY = (float)sizeY / extentY;
physicsScene.DetailLog("{0},BSTerrainMesh.ConvertHeightMapToMesh,totVert={1},totInd={2},extentBase={3},magX={4},magY={5}",
BSScene.DetailLogZero, totalVertices, totalIndices, extentBase, magX, magY);
if (physicsScene != null)
physicsScene.DetailLog("{0},BSTerrainMesh.ConvertHeightMapToMesh,totVert={1},totInd={2},extentBase={3}",
BSScene.DetailLogZero, totalVertices, totalIndices, extentBase);
float minHeight = float.MaxValue;
// Note that sizeX+1 vertices are created since there is land between this and the next region.
for (int yy = 0; yy <= sizeY; yy++)
@ -222,8 +244,8 @@ public sealed class BSTerrainMesh : BSTerrainPhys
if (xx == sizeX) offset -= 1;
float height = heightMap[offset];
minHeight = Math.Min(minHeight, height);
vertices[verticesCount + 0] = (float)xx * magX + extentBase.X;
vertices[verticesCount + 1] = (float)yy * magY + extentBase.Y;
vertices[verticesCount + 0] = (float)xx + extentBase.X;
vertices[verticesCount + 1] = (float)yy + extentBase.Y;
vertices[verticesCount + 2] = height + extentBase.Z;
verticesCount += 3;
}
@ -250,7 +272,161 @@ public sealed class BSTerrainMesh : BSTerrainPhys
}
catch (Exception e)
{
physicsScene.Logger.ErrorFormat("{0} Failed conversion of heightmap to mesh. For={1}/{2}, e={3}",
if (physicsScene != null)
physicsScene.Logger.ErrorFormat("{0} Failed conversion of heightmap to mesh. For={1}/{2}, e={3}",
LogHeader, physicsScene.RegionName, extentBase, e);
}
indicesCountO = indicesCount;
indicesO = indices;
verticesCountO = verticesCount;
verticesO = vertices;
return ret;
}
private class HeightMapGetter
{
private float[] m_heightMap;
private int m_sizeX;
private int m_sizeY;
public HeightMapGetter(float[] pHeightMap, int pSizeX, int pSizeY)
{
m_heightMap = pHeightMap;
m_sizeX = pSizeX;
m_sizeY = pSizeY;
}
// The heightmap is extended as an infinite plane at the last height
public float GetHeight(int xx, int yy)
{
int offset = 0;
// Extend the height with the height from the last row or column
if (yy >= m_sizeY)
if (xx >= m_sizeX)
offset = (m_sizeY - 1) * m_sizeX + (m_sizeX - 1);
else
offset = (m_sizeY - 1) * m_sizeX + xx;
else
if (xx >= m_sizeX)
offset = yy * m_sizeX + (m_sizeX - 1);
else
offset = yy * m_sizeX + xx;
return m_heightMap[offset];
}
}
// Convert the passed heightmap to mesh information suitable for CreateMeshShape2().
// Version that handles magnification.
// Return 'true' if successfully created.
public static bool ConvertHeightmapToMesh2( BSScene physicsScene,
float[] heightMap, int sizeX, int sizeY, // parameters of incoming heightmap
int magnification, // number of vertices per heighmap step
Vector3 extent, // dimensions of the output mesh
Vector3 extentBase, // base to be added to all vertices
out int indicesCountO, out int[] indicesO,
out int verticesCountO, out float[] verticesO)
{
bool ret = false;
int indicesCount = 0;
int verticesCount = 0;
int[] indices = new int[0];
float[] vertices = new float[0];
HeightMapGetter hmap = new HeightMapGetter(heightMap, sizeX, sizeY);
// The vertices dimension of the output mesh
int meshX = sizeX * magnification;
int meshY = sizeY * magnification;
// The output size of one mesh step
float meshXStep = extent.X / meshX;
float meshYStep = extent.Y / meshY;
// Create an array of vertices that is meshX+1 by meshY+1 (note the loop
// from zero to <= meshX). The triangle indices are then generated as two triangles
// per heightmap point. There are meshX by meshY of these squares. The extra row and
// column of vertices are used to complete the triangles of the last row and column
// of the heightmap.
try
{
// Vertices for the output heightmap plus one on the side and bottom to complete triangles
int totalVertices = (meshX + 1) * (meshY + 1);
vertices = new float[totalVertices * 3];
int totalIndices = meshX * meshY * 6;
indices = new int[totalIndices];
if (physicsScene != null)
physicsScene.DetailLog("{0},BSTerrainMesh.ConvertHeightMapToMesh2,inSize={1},outSize={2},totVert={3},totInd={4},extentBase={5}",
BSScene.DetailLogZero, new Vector2(sizeX, sizeY), new Vector2(meshX, meshY),
totalVertices, totalIndices, extentBase);
float minHeight = float.MaxValue;
// Note that sizeX+1 vertices are created since there is land between this and the next region.
// Loop through the output vertices and compute the mediun height in between the input vertices
for (int yy = 0; yy <= meshY; yy++)
{
for (int xx = 0; xx <= meshX; xx++) // Hint: the "<=" means we go around sizeX + 1 times
{
float offsetY = (float)yy * (float)sizeY / (float)meshY; // The Y that is closest to the mesh point
int stepY = (int)offsetY;
float fractionalY = offsetY - (float)stepY;
float offsetX = (float)xx * (float)sizeX / (float)meshX; // The X that is closest to the mesh point
int stepX = (int)offsetX;
float fractionalX = offsetX - (float)stepX;
// physicsScene.DetailLog("{0},BSTerrainMesh.ConvertHeightMapToMesh2,xx={1},yy={2},offX={3},stepX={4},fractX={5},offY={6},stepY={7},fractY={8}",
// BSScene.DetailLogZero, xx, yy, offsetX, stepX, fractionalX, offsetY, stepY, fractionalY);
// get the four corners of the heightmap square the mesh point is in
float heightUL = hmap.GetHeight(stepX , stepY );
float heightUR = hmap.GetHeight(stepX + 1, stepY );
float heightLL = hmap.GetHeight(stepX , stepY + 1);
float heightLR = hmap.GetHeight(stepX + 1, stepY + 1);
// bilinear interplolation
float height = heightUL * (1 - fractionalX) * (1 - fractionalY)
+ heightUR * fractionalX * (1 - fractionalY)
+ heightLL * (1 - fractionalX) * fractionalY
+ heightLR * fractionalX * fractionalY;
// physicsScene.DetailLog("{0},BSTerrainMesh.ConvertHeightMapToMesh2,heightUL={1},heightUR={2},heightLL={3},heightLR={4},heightMap={5}",
// BSScene.DetailLogZero, heightUL, heightUR, heightLL, heightLR, height);
minHeight = Math.Min(minHeight, height);
vertices[verticesCount + 0] = (float)xx * meshXStep + extentBase.X;
vertices[verticesCount + 1] = (float)yy * meshYStep + extentBase.Y;
vertices[verticesCount + 2] = height + extentBase.Z;
verticesCount += 3;
}
}
// The number of vertices generated
verticesCount /= 3;
// Loop through all the heightmap squares and create indices for the two triangles for that square
for (int yy = 0; yy < meshY; yy++)
{
for (int xx = 0; xx < meshX; xx++)
{
int offset = yy * (meshX + 1) + xx;
// Each vertices is presumed to be the upper left corner of a box of two triangles
indices[indicesCount + 0] = offset;
indices[indicesCount + 1] = offset + 1;
indices[indicesCount + 2] = offset + meshX + 1; // accounting for the extra column
indices[indicesCount + 3] = offset + 1;
indices[indicesCount + 4] = offset + meshX + 2;
indices[indicesCount + 5] = offset + meshX + 1;
indicesCount += 6;
}
}
ret = true;
}
catch (Exception e)
{
if (physicsScene != null)
physicsScene.Logger.ErrorFormat("{0} Failed conversion of heightmap to mesh. For={1}/{2}, e={3}",
LogHeader, physicsScene.RegionName, extentBase, e);
}

View File

@ -104,18 +104,20 @@ public class BulletShape
{
public BulletShape()
{
type = BSPhysicsShapeType.SHAPE_UNKNOWN;
shapeType = BSPhysicsShapeType.SHAPE_UNKNOWN;
shapeKey = (System.UInt64)FixedShapeKey.KEY_NONE;
isNativeShape = false;
}
public BSPhysicsShapeType type;
public BSPhysicsShapeType shapeType;
public System.UInt64 shapeKey;
public bool isNativeShape;
public virtual void Clear() { }
public virtual bool HasPhysicalShape { get { return false; } }
// Make another reference to this physical object.
public virtual BulletShape Clone() { return new BulletShape(); }
// Return 'true' if this and other refer to the same physical object
public virtual bool ReferenceSame(BulletShape xx) { return false; }
@ -131,7 +133,7 @@ public class BulletShape
buff.Append("<p=");
buff.Append(AddrString);
buff.Append(",s=");
buff.Append(type.ToString());
buff.Append(shapeType.ToString());
buff.Append(",k=");
buff.Append(shapeKey.ToString("X"));
buff.Append(",n=");
@ -215,45 +217,49 @@ public static class BulletSimData
{
// Map of collisionTypes to flags for collision groups and masks.
// An object's 'group' is the collison groups this object belongs to
// An object's 'filter' is the groups another object has to belong to in order to collide with me
// A collision happens if ((obj1.group & obj2.filter) != 0) || ((obj2.group & obj1.filter) != 0)
//
// As mentioned above, don't use the CollisionFilterGroups definitions directly in the code
// but, instead, use references to this dictionary. Finding and debugging
// collision flag problems will be made easier.
public static Dictionary<CollisionType, CollisionTypeFilterGroup> CollisionTypeMasks
public static Dictionary<CollisionType, CollisionTypeFilterGroup> CollisionTypeMasks
= new Dictionary<CollisionType, CollisionTypeFilterGroup>()
{
{ CollisionType.Avatar,
new CollisionTypeFilterGroup(CollisionType.Avatar,
(uint)CollisionFilterGroups.BCharacterGroup,
{ CollisionType.Avatar,
new CollisionTypeFilterGroup(CollisionType.Avatar,
(uint)CollisionFilterGroups.BCharacterGroup,
(uint)CollisionFilterGroups.BAllGroup)
},
{ CollisionType.Groundplane,
new CollisionTypeFilterGroup(CollisionType.Groundplane,
(uint)CollisionFilterGroups.BGroundPlaneGroup,
{ CollisionType.Groundplane,
new CollisionTypeFilterGroup(CollisionType.Groundplane,
(uint)CollisionFilterGroups.BGroundPlaneGroup,
(uint)CollisionFilterGroups.BAllGroup)
},
{ CollisionType.Terrain,
new CollisionTypeFilterGroup(CollisionType.Terrain,
(uint)CollisionFilterGroups.BTerrainGroup,
{ CollisionType.Terrain,
new CollisionTypeFilterGroup(CollisionType.Terrain,
(uint)CollisionFilterGroups.BTerrainGroup,
(uint)(CollisionFilterGroups.BAllGroup & ~CollisionFilterGroups.BStaticGroup))
},
{ CollisionType.Static,
new CollisionTypeFilterGroup(CollisionType.Static,
(uint)CollisionFilterGroups.BStaticGroup,
{ CollisionType.Static,
new CollisionTypeFilterGroup(CollisionType.Static,
(uint)CollisionFilterGroups.BStaticGroup,
(uint)(CollisionFilterGroups.BCharacterGroup | CollisionFilterGroups.BSolidGroup))
},
{ CollisionType.Dynamic,
new CollisionTypeFilterGroup(CollisionType.Dynamic,
(uint)CollisionFilterGroups.BSolidGroup,
{ CollisionType.Dynamic,
new CollisionTypeFilterGroup(CollisionType.Dynamic,
(uint)CollisionFilterGroups.BSolidGroup,
(uint)(CollisionFilterGroups.BAllGroup))
},
{ CollisionType.VolumeDetect,
new CollisionTypeFilterGroup(CollisionType.VolumeDetect,
(uint)CollisionFilterGroups.BSensorTrigger,
{ CollisionType.VolumeDetect,
new CollisionTypeFilterGroup(CollisionType.VolumeDetect,
(uint)CollisionFilterGroups.BSensorTrigger,
(uint)(~CollisionFilterGroups.BSensorTrigger))
},
{ CollisionType.LinksetChild,
new CollisionTypeFilterGroup(CollisionType.LinksetChild,
(uint)CollisionFilterGroups.BLinksetChildGroup,
new CollisionTypeFilterGroup(CollisionType.LinksetChild,
(uint)CollisionFilterGroups.BLinksetChildGroup,
(uint)(CollisionFilterGroups.BNoneGroup))
// (uint)(CollisionFilterGroups.BCharacterGroup | CollisionFilterGroups.BSolidGroup))
},

View File

@ -1,68 +1,113 @@
PROBLEMS TO LOOK INTO
=================================================
Nebadon vehicle ride, get up, ride again. Second time vehicle does not act correctly.
Have to rez new vehicle and delete the old to fix situation.
Hitting RESET on Nebadon's vehicle while riding causes vehicle to get into odd
position state where it will not settle onto ground properly, etc
Two of Nebadon vehicles in a sim max the CPU. This is new.
A sitting, active vehicle bobs up and down a small amount.
CURRENT PRIORITIES
=================================================
Redo BulletSimAPI to allow native C# implementation of Bullet option.
Avatar movement
flying into a wall doesn't stop avatar who keeps appearing to move through the obstacle
walking up stairs is not calibrated correctly (stairs out of Kepler cabin)
avatar capsule rotation completed
llMoveToTarget
Use the HACD convex hull routine in Bullet rather than the C# version.
Speed up hullifying large meshes.
Enable vehicle border crossings (at least as poorly as ODE)
Terrain skirts
Avatar created in previous region and not new region when crossing border
Vehicle recreated in new sim at small Z value (offset from root value?) (DONE)
Vehicle movement on terrain smoothness
Deleting a linkset while standing on the root will leave the physical shape of the root behind.
Not sure if it is because standing on it. Done with large prim linksets.
Linkset child rotations.
Nebadon spiral tube has middle sections which are rotated wrong.
Select linked spiral tube. Delink and note where the middle section ends up.
Refarb compound linkset creation to create a pseudo-root for center-of-mass
Let children change their shape to physical indendently and just add shapes to compound
Vehicle angular vertical attraction
vehicle angular banking
Center-of-gravity
Vehicle angular deflection
Preferred orientation angular correction fix
when should angular and linear motor targets be zeroed? when selected?
Need a vehicle.clear()? Or an 'else' in prestep if not physical.
Teravus llMoveToTarget script debug
Mixing of hover, buoyancy/gravity, moveToTarget, into one force
Setting hover height to zero disables hover even if hover flags are on (from SL wiki)
limitMotorUp calibration (more down?)
llRotLookAt
llLookAt
Avatars walking up stairs (HALF DONE)
Avatar movement
flying into a wall doesn't stop avatar who keeps appearing to move through the obstacle (DONE)
walking up stairs is not calibrated correctly (stairs out of Kepler cabin) (DONE)
avatar capsule rotation completed (NOT DONE - Bullet's capsule shape is not the solution)
Vehicle script tuning/debugging
Avanti speed script
Weapon shooter script
limitMotorUp calibration (more down?)
Boats float low in the water
Move material definitions (friction, ...) into simulator.
Add material densities to the material types.
CRASHES
=================================================
20121129.1411: editting/moving phys object across region boundries causes crash
getPos-> btRigidBody::upcast -> getBodyType -> BOOM
20121128.1600: mesh object not rezzing (no physics mesh).
Causes many errors. Doesn't stop after first error with box shape.
Eventually crashes when deleting the object.
20121206.1434: rez Sam-pan into OSGrid BulletSim11 region
Immediate simulator crash. Mono does not output any stacktrace and
log just stops after reporting taint-time linking of the linkset.
One sided meshes? Should terrain be built into a closed shape?
When meshes get partially wedged into the terrain, they cannot push themselves out.
It is possible that Bullet processes collisions whether entering or leaving a mesh.
Ref: http://bulletphysics.org/Bullet/phpBB3/viewtopic.php?t=4869
VEHICLES TODO LIST:
=================================================
Angular motor direction is global coordinates rather than local coordinates
LINEAR_MOTOR_DIRECTION values should be clamped to reasonable numbers.
What are the limits in SL?
Same for other velocity settings.
UBit improvements to remove rubber-banding of avatars sitting on vehicle child prims:
https://github.com/UbitUmarov/Ubit-opensim
Border crossing with linked vehicle causes crash
20121129.1411: editting/moving phys object across region boundries causes crash
getPos-> btRigidBody::upcast -> getBodyType -> BOOM
Vehicles (Move smoothly)
Add vehicle collisions so IsColliding is properly reported.
Needed for banking, limitMotorUp, movementLimiting, ...
VehicleAddForce is not scaled by the simulation step but it is only
applied for one step. Should it be scaled?
Some vehicles should not be able to turn if no speed or off ground.
What to do if vehicle and prim buoyancy differ?
Cannot edit/move a vehicle being ridden: it jumps back to the origional position.
Neb car jiggling left and right
Happens on terrain and any other mesh object. Flat cubes are much smoother.
This has been reduced but not eliminated.
Implement referenceFrame for all the motion routines.
Angular motion around Z moves the vehicle in world Z and not vehicle Z in ODE.
Verify that angular motion specified around Z moves in the vehicle coordinates.
For limitMotorUp, use raycast down to find if vehicle is in the air.
Verify llGetVel() is returning a smooth and good value for vehicle movement.
llGetVel() should return the root's velocity if requested in a child prim.
Implement function efficiency for lineaar and angular motion.
After getting off a vehicle, the root prim is phantom (can be walked through)
Need to force a position update for the root prim after compound shape destruction
Linkset explosion after three "rides" on Nebadon lite vehicle (LinksetConstraint)
For limitMotorUp, use raycast down to find if vehicle is in the air.
Remove vehicle angular velocity zeroing in BSPrim.UpdateProperties().
A kludge that isn't fixing the real problem of Bullet adding extra motion.
Incorporate inter-relationship of angular corrections. For instance, angularDeflection
and angularMotorUp will compute same X or Y correction. When added together
creates over-correction and over-shoot and wabbling.
Vehicle attributes are not restored when a vehicle is rezzed on region creation
Create vehicle, setup vehicle properties, restart region, vehicle is not reinitialized.
BULLETSIM TODO LIST:
GENERAL TODO LIST:
=================================================
Explore btGImpactMeshShape as alternative to convex hulls for simplified physical objects.
Regular triangle meshes don't do physical collisions.
Resitution of a prim works on another prim but not on terrain.
The dropped prim doesn't bounce properly on the terrain.
Add a sanity check for PIDTarget location.
Level-of-detail for mesh creation. Prims with circular interiors require lod of 32.
Is much saved with lower LODs? At the moment, all set to 32.
Collisions are inconsistant: arrows are supposed to hit and report collision. Often don't.
If arrow show at prim, collision reported about 1/3 of time. If collision reported,
both arrow and prim report it. The arrow bounces off the prim 9 out of 10 times.
Shooting 5m sphere "arrows" at 60m/s.
llMoveToTarget objects are not effected by gravity until target is removed.
Compute CCD parameters based on body size
Can solver iterations be changed per body/shape? Can be for constraints but what
about regular vehicles?
Implement llSetPhysicalMaterial.
extend it with Center-of-mass, rolling friction, density
Implement llSetForceAndTorque.
Change BSPrim.moveToTarget to used forces rather than changing position
Changing position allows one to move through walls
Implement an avatar mesh shape. The Bullet capsule is way too limited.
Consider just hand creating a vertex/index array in a new BSShapeAvatar.
Verify/fix phantom, volume-detect objects do not fall to infinity. Should stop at terrain.
Revisit CollisionMargin. Builders notice the 0.04 spacing between prims.
Duplicating a physical prim causes old prim to jump away
Dup a phys prim and the original become unselected and thus interacts w/ selected prim.
@ -86,6 +131,8 @@ setForce should set a constant force. Different than AddImpulse.
Implement raycast.
Implement ShapeCollection.Dispose()
Implement water as a plain so raycasting and collisions can happen with same.
Add collision penetration return
Add field passed back by BulletSim.dll and fill with info in ManifoldConstact.GetDistance()
Add osGetPhysicsEngineName() so scripters can tell whether BulletSim or ODE
Also osGetPhysicsEngineVerion() maybe.
Linkset.Position and Linkset.Orientation requre rewrite to properly return
@ -107,6 +154,12 @@ Physical and phantom will drop through the terrain
LINKSETS
======================================================
Child prims do not report collisions
Allow children of a linkset to be phantom:
http://opensim-dev.2196679.n2.nabble.com/Setting-a-single-child-prim-to-Phantom-tp7578513.html
Add OS_STATUS_PHANTOM_PRIM to llSetLinkPrimitaveParamsFast.
Editing a child of a linkset causes the child to go phantom
Move a child prim once when it is physical and can never move it again without it going phantom
Offset the center of the linkset to be the geometric center of all the prims
Not quite the same as the center-of-gravity
Linksets should allow collisions to individual children
@ -117,11 +170,9 @@ LinksetCompound: when one of the children changes orientation (like tires
Verify/think through scripts in children of linksets. What do they reference
and return when getting position, velocity, ...
Confirm constraint linksets still work after making all the changes for compound linksets.
Use PostTaint callback to do rebuilds for constraint linksets to reduce rebuilding
Add 'changed' flag or similar to reduce the number of times a linkset is rebuilt.
For compound linksets, add ability to remove or reposition individual child shapes.
Disable activity of passive linkset children.
Since the linkset is a compound object, the old prims are left lying
around and need to be phantomized so they don't collide, ...
Speed up creation of large physical linksets
For instance, sitting in Neb's car (130 prims) takes several seconds to become physical.
REALLY bad for very large physical linksets (freezes the sim for many seconds).
@ -131,25 +182,28 @@ Eliminate collisions between objects in a linkset. (LinksetConstraint)
MORE
======================================================
Test avatar walking up stairs. How does compare with SL.
Radius of the capsule affects ability to climb edges.
Compute avatar size and scale correctly. Now it is a bit off from the capsule size.
Create tests for different interface components
Have test objects/scripts measure themselves and turn color if correct/bad
Test functions in SL and calibrate correctness there
Create auto rezzer and tracker to run through the tests
Do we need to do convex hulls all the time? Can complex meshes be left meshes?
There is some problem with meshes and collisions
Hulls are not as detailed as meshes. Hulled vehicles insides are different shape.
Debounce avatar contact so legs don't keep folding up when standing.
Implement LSL physics controls. Like STATUS_ROTATE_X.
Add border extensions to terrain to help region crossings and objects leaving region.
Use a different capsule shape for avatar when sitting
LL uses a pyrimidal shape scaled by the avatar's bounding box
http://wiki.secondlife.com/wiki/File:Avmeshforms.png
Performance test with lots of avatars. Can BulletSim support a thousand?
Optimize collisions in C++: only send up to the object subscribed to collisions.
Use collision subscription and remove the collsion(A,B) and collision(B,A)
Check whether SimMotionState needs large if statement (see TODO).
Implement 'top colliders' info.
Avatar jump
Performance measurement and changes to make quicker.
Implement detailed physics stats (GetStats()).
Measure performance improvement from hulls
Test not using ghost objects for volume detect implementation.
Performance of closures and delegates for taint processing
@ -157,9 +211,7 @@ Performance of closures and delegates for taint processing
Is any slowdown introduced by the existing implementation significant?
Is there are more efficient method of implementing pre and post step actions?
See http://www.codeproject.com/Articles/29922/Weak-Events-in-C
Physics Arena central pyramid: why is one side permiable?
In SL, perfect spheres don't seem to have rolling friction. Add special case.
Enforce physical parameter min/max:
Gravity: [-1, 28]
@ -168,9 +220,12 @@ Enforce physical parameter min/max:
Restitution [0, 1]
http://wiki.secondlife.com/wiki/Physics_Material_Settings_test
Avatar attachments have no mass? http://forums-archive.secondlife.com/54/f0/31796/1.html
Keep avatar scaling correct. http://pennycow.blogspot.fr/2011/07/matter-of-scale.html
INTERNAL IMPROVEMENT/CLEANUP
=================================================
Can the 'inTaintTime' flag be cleaned up and used? For instance, a call to
BSScene.TaintedObject() could immediately execute the callback if already in taint time.
Create the physical wrapper classes (BulletBody, BulletShape) by methods on
BSAPITemplate and make their actual implementation Bullet engine specific.
For the short term, just call the existing functions in ShapeCollection.
@ -190,22 +245,19 @@ Generalize Dynamics and PID with standardized motors.
Generalize Linkset and vehicles into PropertyManagers
Methods for Refresh, RemoveBodyDependencies, RestoreBodyDependencies
Potentially add events for shape destruction, etc.
Complete implemention of preStepActions
Replace vehicle step call with prestep event.
Is there a need for postStepActions? postStepTaints?
Better mechanism for resetting linkset set and vehicle parameters when body rebuilt.
BSPrim.CreateGeomAndObject is kludgy with the callbacks, etc.
Implement linkset by setting position of children when root updated. (LinksetManual)
Linkset implementation using manual prim movement.
LinkablePrim class? Would that simplify/centralize the linkset logic?
BSScene.UpdateParameterSet() is broken. How to set params on objects?
Remove HeightmapInfo from terrain specification
Since C++ code does not need terrain height, this structure et al are not needed.
Add floating motor for BS_FLOATS_ON_WATER so prim and avatar will
bob at the water level. BSPrim.PositionSanityCheck().
bob at the water level. BSPrim.PositionSanityCheck()
Should taints check for existance or activeness of target?
When destroying linksets/etc, taints can be generated for objects that are
actually gone when the taint happens. Crashes don't happen because the taint closure
keeps the object from being freed, but that is just an accident.
Possibly have and 'active' flag that is checked by the taint processor?
Possibly have an 'active' flag that is checked by the taint processor?
Parameters for physics logging should be moved from BSScene to BSParam (at least boolean ones)
Can some of the physical wrapper classes (BulletBody, BulletWorld, BulletShape) be 'sealed'?
There are TOO MANY interfaces from BulletSim core to Bullet itself
@ -270,3 +322,43 @@ llSetBuoyancy() (DONE)
(Resolution: Bullet resets object gravity when added to world. Moved set gravity)
Avatar density is WAY off. Compare and calibrate with what's in SL. (DONE)
(Resolution: set default density to 3.5 (from 60) which is closer to SL)
Redo BulletSimAPI to allow native C# implementation of Bullet option (DONE)
(Resolution: added BSAPITemplate and then interfaces for C++ Bullet and C# BulletXNA
Meshes rendering as bounding boxes (DONE)
(Resolution: Added test for mesh/sculpties in native shapes so it didn't think it was a box)
llMoveToTarget (Resolution: added simple motor to update the position.)
Angular motor direction is global coordinates rather than local coordinates (DONE)
Add vehicle collisions so IsColliding is properly reported. (DONE)
Needed for banking, limitMotorUp, movementLimiting, ...
(Resolution: added CollisionFlags.BS_VEHICLE_COLLISION and code to use it)
VehicleAddForce is not scaled by the simulation step but it is only
applied for one step. Should it be scaled? (DONE)
(Resolution: use force for timed things, Impulse for immediate, non-timed things)
Complete implemention of preStepActions (DONE)
Replace vehicle step call with prestep event.
Is there a need for postStepActions? postStepTaints?
Disable activity of passive linkset children. (DONE)
Since the linkset is a compound object, the old prims are left lying
around and need to be phantomized so they don't collide, ...
Remove HeightmapInfo from terrain specification (DONE)
Since C++ code does not need terrain height, this structure et al are not needed.
Surfboard go wonky when turning (DONE)
Angular motor direction is global coordinates rather than local coordinates?
(Resolution: made angular motor direction correct coordinate system)
Mantis 6040 script http://opensimulator.org/mantis/view.php?id=6040 (DONE)
Msg Kayaker on OSGrid when working
(Resolution: LINEAR_DIRECTION is in vehicle coords. Test script does the
same in SL as in OS/BulletSim)
Boats float low in the water (DONE)
Boats floating at proper level (DONE)
When is force introduced by SetForce removed? The prestep action could go forever. (DONE)
(Resolution: setForce registers a prestep action which keeps applying the force)
Child movement in linkset (don't rebuild linkset) (DONE 20130122))
Avatar standing on a moving object should start to move with the object. (DONE 20130125)
Angular motion around Z moves the vehicle in world Z and not vehicle Z in ODE.
Verify that angular motion specified around Z moves in the vehicle coordinates.
DONE 20130120: BulletSim properly applies force in vehicle relative coordinates.
Nebadon vehicles turning funny in arena (DONE)
Lock axis (DONE 20130401)
Terrain detail: double terrain mesh detail (DONE)

View File

@ -29,5 +29,5 @@ using System.Runtime.InteropServices;
// Build Number
// Revision
//
[assembly: AssemblyVersion("0.7.5.*")]
[assembly: AssemblyFileVersion("1.0.0.0")]
[assembly: AssemblyVersion("0.7.6.*")]

Binary file not shown.

BIN
bin/lib32/libBulletSim.dylib Executable file

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.