Welcome to mirror list, hosted at ThFree Co, Russian Federation.

git.blender.org/blender.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorKester Maddock <Christopher.Maddock.1@uni.massey.ac.nz>2004-04-24 10:40:15 +0400
committerKester Maddock <Christopher.Maddock.1@uni.massey.ac.nz>2004-04-24 10:40:15 +0400
commit63048b6cf4358dc9231e0704e03e0f8d5729a174 (patch)
tree33a1047d2d9007021a78ab2c2fbb8fc5d06727c5 /source/gameengine/Physics/Sumo
parenta46f456e92b14d986022b301757a7bad3c4c76b5 (diff)
Synchronise game engine with Tuhopuu2 tree.
Diffstat (limited to 'source/gameengine/Physics/Sumo')
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/include/SM_Object.h62
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/src/SM_Object.cpp151
-rw-r--r--source/gameengine/Physics/Sumo/SumoPhysicsController.cpp2
-rw-r--r--source/gameengine/Physics/Sumo/SumoPhysicsController.h57
4 files changed, 163 insertions, 109 deletions
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Object.h b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Object.h
index c90dfb7296c..a0475c39bbb 100644
--- a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Object.h
+++ b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Object.h
@@ -42,33 +42,37 @@
class SM_FhObject;
-
-// Properties of dynamic objects
+/** Properties of dynamic objects */
struct SM_ShapeProps {
- MT_Scalar m_mass; // Total mass
- MT_Scalar m_radius; // Bound sphere size
- MT_Vector3 m_inertia; // Inertia, should be a tensor some time
- MT_Scalar m_lin_drag; // Linear drag (air, water) 0 = concrete, 1 = vacuum
- MT_Scalar m_ang_drag; // Angular drag
- MT_Scalar m_friction_scaling[3]; // Scaling for anisotropic friction. Component in range [0, 1]
- bool m_do_anisotropic; // Should I do anisotropic friction?
- bool m_do_fh; // Should the object have a linear Fh spring?
- bool m_do_rot_fh; // Should the object have an angular Fh spring?
+ MT_Scalar m_mass; ///< Total mass
+ MT_Scalar m_radius; ///< Bound sphere size
+ MT_Vector3 m_inertia; ///< Inertia, should be a tensor some time
+ MT_Scalar m_lin_drag; ///< Linear drag (air, water) 0 = concrete, 1 = vacuum
+ MT_Scalar m_ang_drag; ///< Angular drag
+ MT_Scalar m_friction_scaling[3]; ///< Scaling for anisotropic friction. Component in range [0, 1]
+ bool m_do_anisotropic; ///< Should I do anisotropic friction?
+ bool m_do_fh; ///< Should the object have a linear Fh spring?
+ bool m_do_rot_fh; ///< Should the object have an angular Fh spring?
};
-// Properties of collidable objects (non-ghost objects)
+/** Properties of collidable objects (non-ghost objects) */
struct SM_MaterialProps {
- MT_Scalar m_restitution; // restitution of energie after a collision 0 = inelastic, 1 = elastic
- MT_Scalar m_friction; // Coulomb friction (= ratio between the normal en maximum friction force)
- MT_Scalar m_fh_spring; // Spring constant (both linear and angular)
- MT_Scalar m_fh_damping; // Damping factor (linear and angular) in range [0, 1]
- MT_Scalar m_fh_distance; // The range above the surface where Fh is active.
- bool m_fh_normal; // Should the object slide off slopes?
+ MT_Scalar m_restitution; ///< restitution of energy after a collision 0 = inelastic, 1 = elastic
+ MT_Scalar m_friction; ///< Coulomb friction (= ratio between the normal en maximum friction force)
+ MT_Scalar m_fh_spring; ///< Spring constant (both linear and angular)
+ MT_Scalar m_fh_damping; ///< Damping factor (linear and angular) in range [0, 1]
+ MT_Scalar m_fh_distance; ///< The range above the surface where Fh is active.
+ bool m_fh_normal; ///< Should the object slide off slopes?
};
-
+/**
+ * SM_Object is an internal part of the Sumo physics engine.
+ *
+ * It encapsulates an object in the physics scene, and is responsible
+ * for calculating the collision response of objects.
+ */
class SM_Object : public SM_MotionState {
public:
SM_Object() ;
@@ -140,13 +144,10 @@ public:
* this external velocity. This velocity is not subject to
* friction or damping.
*/
-
-
void setExternalLinearVelocity(const MT_Vector3& lin_vel) ;
void addExternalLinearVelocity(const MT_Vector3& lin_vel) ;
/** Override the physics velocity */
-
void addLinearVelocity(const MT_Vector3& lin_vel);
void setLinearVelocity(const MT_Vector3& lin_vel);
@@ -156,24 +157,20 @@ public:
* your responsibility to clear this velocity. This velocity
* is not subject to friction or damping.
*/
-
void setExternalAngularVelocity(const MT_Vector3& ang_vel) ;
void addExternalAngularVelocity(const MT_Vector3& ang_vel);
/** Override the physics angular velocity */
-
void addAngularVelocity(const MT_Vector3& ang_vel);
void setAngularVelocity(const MT_Vector3& ang_vel);
/** Clear the external velocities */
-
void clearCombinedVelocities();
/**
* Tell the physics system to combine the external velocity
* with the physics velocity.
*/
-
void resolveCombinedVelocities(
const MT_Vector3 & lin_vel,
const MT_Vector3 & ang_vel
@@ -193,10 +190,21 @@ public:
void applyTorque(const MT_Vector3& torque) ;
+ /**
+ * Apply an impulse to the object. The impulse will be split into
+ * angular and linear components.
+ * @param attach point to apply the impulse to (in world coordinates)
+ */
void applyImpulse(const MT_Point3& attach, const MT_Vector3& impulse) ;
+ /**
+ * Applies an impulse through the centre of this object. (ie the angular
+ * velocity will not change.
+ */
void applyCenterImpulse(const MT_Vector3& impulse);
-
+ /**
+ * Applies an angular impulse.
+ */
void applyAngularImpulse(const MT_Vector3& impulse);
MT_Point3 getWorldCoord(const MT_Point3& local) const;
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/src/SM_Object.cpp b/source/gameengine/Physics/Sumo/Fuzzics/src/SM_Object.cpp
index f6b0f50219e..9751a4cafe0 100644
--- a/source/gameengine/Physics/Sumo/Fuzzics/src/SM_Object.cpp
+++ b/source/gameengine/Physics/Sumo/Fuzzics/src/SM_Object.cpp
@@ -168,6 +168,17 @@ integrateMomentum(
}
}
+/**
+ * dynamicCollision computes the response to a collision.
+ *
+ * @param local2 the contact point in local coordinates.
+ * @param normal the contact normal.
+ * @param dist the penetration depth of the contact. (unused)
+ * @param rel_vel the relative velocity of the objects
+ * @param restitution the amount of momentum conserved in the collision. Range: 0.0 - 1.0
+ * @param friction_factor the amount of friction between the two surfaces.
+ * @param invMass the inverse mass of the collision objects (1.0 / mass)
+ */
void SM_Object::dynamicCollision(const MT_Point3 &local2,
const MT_Vector3 &normal,
MT_Scalar dist,
@@ -177,10 +188,19 @@ void SM_Object::dynamicCollision(const MT_Point3 &local2,
MT_Scalar invMass
)
{
- // This should look familiar....
+ /**
+ * rel_vel_normal is the relative velocity in the contact normal direction.
+ */
MT_Scalar rel_vel_normal = normal.dot(rel_vel);
- if (rel_vel_normal < -MT_EPSILON) {
+ /**
+ * if rel_vel_normal > 0, the objects are moving apart!
+ */
+ if (rel_vel_normal < 0.) {
+ /**
+ * if rel_vel_normal < ImpulseThreshold, scale the restitution down.
+ * This should improve the simulation where the object is stacked.
+ */
restitution *= MT_min(MT_Scalar(1.0), rel_vel_normal/ImpulseThreshold);
MT_Scalar impulse = -(1.0 + restitution) * rel_vel_normal;
@@ -189,18 +209,20 @@ void SM_Object::dynamicCollision(const MT_Point3 &local2,
{
MT_Vector3 temp = getInvInertiaTensor() * local2.cross(normal);
impulse /= invMass + normal.dot(temp.cross(local2));
+
+ /**
+ * Apply impulse at the collision point.
+ * Take rotational inertia into account.
+ */
applyImpulse(local2 + m_pos, impulse * normal);
} else {
+ /**
+ * Apply impulse through object centre. (no rotation.)
+ */
impulse /= invMass;
applyCenterImpulse( impulse * normal );
}
- // The friction part starts here!!!!!!!!
-
- // Compute the lateral component of the relative velocity
- // lateral actually points in the opposite direction, i.e.,
- // into the direction of the friction force.
-
#if 0
// test - only do friction on the physics part of the
// velocity.
@@ -211,30 +233,37 @@ void SM_Object::dynamicCollision(const MT_Point3 &local2,
rel_vel = vel2 - vel1;
rel_vel_normal = normal.dot(rel_vel);
#endif
-
+ /**
+ * The friction part starts here!!!!!!!!
+ *
+ * Compute the lateral component of the relative velocity
+ * lateral actually points in the opposite direction, i.e.,
+ * into the direction of the friction force.
+ */
MT_Vector3 lateral = rel_vel - normal * rel_vel_normal;
- //printf(" lateral = { %0.5f, %0.5f, %0.5f } (%0.5f)\n",
- // lateral[0], lateral[1], lateral[2], lateral.length());
-
- //const SM_ShapeProps *shapeProps = obj2->getShapeProps();
-
if (m_shapeProps->m_do_anisotropic) {
- // For anisotropic friction we scale the lateral component,
- // rather than compute a direction-dependent fricition
- // factor. For this the lateral component is transformed to
- // local coordinates.
+ /**
+ * For anisotropic friction we scale the lateral component,
+ * rather than compute a direction-dependent fricition
+ * factor. For this the lateral component is transformed to
+ * local coordinates.
+ */
MT_Matrix3x3 lcs(m_orn);
- // We cannot use m_xform.getBasis() for the matrix, since
- // it might contain a non-uniform scaling.
- // OPT: it's a bit daft to compute the matrix since the
- // quaternion itself can be used to do the transformation.
-
+
+ /**
+ * We cannot use m_xform.getBasis() for the matrix, since
+ * it might contain a non-uniform scaling.
+ * OPT: it's a bit daft to compute the matrix since the
+ * quaternion itself can be used to do the transformation.
+ */
MT_Vector3 loc_lateral = lateral * lcs;
- // lcs is orthogonal so lcs.inversed() == lcs.transposed(),
- // and lcs.transposed() * lateral == lateral * lcs.
-
+
+ /**
+ * lcs is orthogonal so lcs.inversed() == lcs.transposed(),
+ * and lcs.transposed() * lateral == lateral * lcs.
+ */
const MT_Vector3& friction_scaling =
m_shapeProps->m_friction_scaling;
@@ -246,23 +275,23 @@ void SM_Object::dynamicCollision(const MT_Point3 &local2,
lateral = lcs * loc_lateral;
}
- // A tiny Coulomb friction primer:
- // The Coulomb friction law states that the magnitude of the
- // maximum possible friction force depends linearly on the
- // magnitude of the normal force.
- //
- // F_max_friction = friction_factor * F_normal
- //
- // (NB: independent of the contact area!!)
- //
- // The friction factor depends on the material.
- // We use impulses rather than forces but let us not be
- // bothered by this.
-
-
+ /**
+ * A tiny Coulomb friction primer:
+ * The Coulomb friction law states that the magnitude of the
+ * maximum possible friction force depends linearly on the
+ * magnitude of the normal force.
+ *
+ * \f[
+ F_max_friction = friction_factor * F_normal
+ \f]
+ *
+ * (NB: independent of the contact area!!)
+ *
+ * The friction factor depends on the material.
+ * We use impulses rather than forces but let us not be
+ * bothered by this.
+ */
MT_Scalar rel_vel_lateral = lateral.length();
- //printf("rel_vel = { %0.05f, %0.05f, %0.05f}\n", rel_vel[0], rel_vel[1], rel_vel[2]);
- //printf("n.l = %0.15f\n", normal.dot(lateral)); /* Should be 0.0 */
if (rel_vel_lateral > MT_EPSILON) {
lateral /= rel_vel_lateral;
@@ -275,17 +304,21 @@ void SM_Object::dynamicCollision(const MT_Point3 &local2,
assert(impulse >= 0.0);
- // Here's the trick. We compute the impulse to make the
- // lateral velocity zero. (Make the objects stick together
- // at the contact point. If this impulse is larger than
- // the maximum possible friction impulse, then shrink its
- // magnitude to the maximum friction.
+ /**
+ * Here's the trick. We compute the impulse to make the
+ * lateral velocity zero. (Make the objects stick together
+ * at the contact point. If this impulse is larger than
+ * the maximum possible friction impulse, then shrink its
+ * magnitude to the maximum friction.
+ */
if (isRigidBody()) {
- // For rigid bodies we take the inertia into account,
- // since the friction impulse is going to change the
- // angular momentum as well.
+ /**
+ * For rigid bodies we take the inertia into account,
+ * since the friction impulse is going to change the
+ * angular momentum as well.
+ */
MT_Vector3 temp = getInvInertiaTensor() * local2.cross(lateral);
MT_Scalar impulse_lateral = rel_vel_lateral /
(invMass + lateral.dot(temp.cross(local2)));
@@ -303,8 +336,8 @@ void SM_Object::dynamicCollision(const MT_Point3 &local2,
}
- calcXform();
- notifyClient();
+ //calcXform();
+ //notifyClient();
}
}
@@ -353,7 +386,8 @@ DT_Bool SM_Object::boing(
if (dist < MT_EPSILON)
return DT_CONTINUE;
- local1 -= obj1->m_pos, local2 -= obj2->m_pos;
+ local1 -= obj1->m_pos;
+ local2 -= obj2->m_pos;
// Calculate collision parameters
MT_Vector3 rel_vel = obj1->getVelocity(local1) - obj2->getVelocity(local2);
@@ -377,8 +411,6 @@ DT_Bool SM_Object::boing(
if (obj2->isDynamic())
obj2->dynamicCollision(local2, -normal, dist, -rel_vel, restitution, friction_factor, invMass);
- //fix(client_data, (void*) obj1, (void*) obj2, coll_data);
-
return DT_CONTINUE;
}
@@ -428,26 +460,26 @@ DT_Bool SM_Object::fix(
obj2->m_error -= error;
// Remove the velocity component in the normal direction
// Calculate collision parameters
- MT_Vector3 rel_vel = obj1->getLinearVelocity() - obj2->getLinearVelocity();
+ /*MT_Vector3 rel_vel = obj1->getLinearVelocity() - obj2->getLinearVelocity();
if (normal.length() > FixThreshold && rel_vel.length() < FixVelocity) {
normal.normalize();
MT_Scalar rel_vel_normal = 0.49*(normal.dot(rel_vel));
obj1->addLinearVelocity(-rel_vel_normal*normal);
obj2->addLinearVelocity(rel_vel_normal*normal);
- }
+ }*/
}
else {
// Same again but now obj1 is non-dynamic
obj2->m_error -= normal;
- MT_Vector3 rel_vel = obj2->getLinearVelocity();
+ /*MT_Vector3 rel_vel = obj2->getLinearVelocity();
if (normal.length() > FixThreshold && rel_vel.length() < FixVelocity) {
// Calculate collision parameters
normal.normalize();
MT_Scalar rel_vel_normal = -0.99*(normal.dot(rel_vel));
obj2->addLinearVelocity(rel_vel_normal*normal);
- }
+ }*/
}
return DT_CONTINUE;
@@ -496,7 +528,6 @@ SM_Object::SM_Object() :
m_fh_object(0)
{
// warning no initialization of variables done by moto.
- std::cout << "SM_Object::SM_Object()" << std::endl;
}
SM_Object::
diff --git a/source/gameengine/Physics/Sumo/SumoPhysicsController.cpp b/source/gameengine/Physics/Sumo/SumoPhysicsController.cpp
index 42a3c23b55e..9780b151775 100644
--- a/source/gameengine/Physics/Sumo/SumoPhysicsController.cpp
+++ b/source/gameengine/Physics/Sumo/SumoPhysicsController.cpp
@@ -1,5 +1,5 @@
/**
- * $Id$
+ * @file $Id$
*
* ***** BEGIN GPL/BL DUAL LICENSE BLOCK *****
*
diff --git a/source/gameengine/Physics/Sumo/SumoPhysicsController.h b/source/gameengine/Physics/Sumo/SumoPhysicsController.h
index a48ef013fab..26ff52600f3 100644
--- a/source/gameengine/Physics/Sumo/SumoPhysicsController.h
+++ b/source/gameengine/Physics/Sumo/SumoPhysicsController.h
@@ -1,5 +1,5 @@
/**
- * $Id$
+ * @file $Id$
*
* ***** BEGIN GPL/BL DUAL LICENSE BLOCK *****
*
@@ -37,12 +37,13 @@
#include "SM_Callback.h"
/**
- Sumo Physics Controller, a special kind of a PhysicsController.
- A Physics Controller is a special kind of Scene Graph Transformation Controller.
- Each time the scene graph get's updated, the controller get's a chance
- in the 'Update' method to reflect changes.
-*/
-
+ * Sumo Physics Controller, a special kind of a PhysicsController.
+ * A Physics Controller is a special kind of Scene Graph Transformation Controller.
+ * Each time the scene graph get's updated, the controller get's a chance
+ * in the 'Update' method to reflect changes.
+ *
+ * Sumo uses the SOLID library for collision detection.
+ */
class SumoPhysicsController : public PHY_IPhysicsController , public SM_Callback
@@ -58,15 +59,26 @@ public:
virtual ~SumoPhysicsController();
- // kinematic methods
+ /**
+ * @name Kinematic Methods.
+ */
+ /*@{*/
virtual void RelativeTranslate(float dlocX,float dlocY,float dlocZ,bool local);
+ /**
+ * @param drot a 3x4 matrix. This will treated as a 3x3 rotation matrix.
+ * @warning RelativeRotate expects a 3x4 matrix. The fourth column is padding.
+ */
virtual void RelativeRotate(const float drot[12],bool local);
virtual void getOrientation(float &quatImag0,float &quatImag1,float &quatImag2,float &quatReal);
virtual void setOrientation(float quatImag0,float quatImag1,float quatImag2,float quatReal);
virtual void setPosition(float posX,float posY,float posZ);
virtual void setScaling(float scaleX,float scaleY,float scaleZ);
+ /*@}*/
- // physics methods
+ /**
+ * @name Physics Methods
+ */
+ /*@{*/
virtual void ApplyTorque(float torqueX,float torqueY,float torqueZ,bool local);
virtual void ApplyForce(float forceX,float forceY,float forceZ,bool local);
virtual void SetAngularVelocity(float ang_velX,float ang_velY,float ang_velZ,bool local);
@@ -76,15 +88,16 @@ public:
virtual void SetActive(bool active){};
virtual void SuspendDynamics();
virtual void RestoreDynamics();
+ /*@}*/
/**
- reading out information from physics
- */
+ * reading out information from physics
+ */
virtual void GetLinearVelocity(float& linvX,float& linvY,float& linvZ);
/**
- GetVelocity parameters are in geometric coordinates (Origin is not center of mass!).
- */
+ * GetVelocity parameters are in geometric coordinates (Origin is not center of mass!).
+ */
virtual void GetVelocity(const float posX,const float posY,const float posZ,float& linvX,float& linvY,float& linvZ);
virtual float getMass();
virtual void getReactionForce(float& forceX,float& forceY,float& forceZ);
@@ -93,28 +106,27 @@ public:
virtual void PostProcessReplica(class PHY_IMotionState* motionstate,class PHY_IPhysicsController* parentctrl);
- // todo: remove next line !
+ // TODO: remove next line !
virtual void SetSimulatedTime(float time);
-
virtual void WriteDynamicsToMotionState() {};
virtual void WriteMotionStateToDynamics(bool nondynaonly);
/**
- call from Scene Graph Node to 'update'.
- */
+ * call from Scene Graph Node to 'update'.
+ */
virtual bool SynchronizeMotionStates(float time);
- // clientinfo for raycasts for example
+ // clientinfo for raycasts for example
virtual void* getClientInfo() { return m_clientInfo;}
virtual void setClientInfo(void* clientinfo) {m_clientInfo = clientinfo;};
- void* m_clientInfo;
-
float getFriction() { return m_friction;}
float getRestitution() { return m_restitution;}
- // sumo callback
+ /**
+ * Sumo callback
+ */
virtual void do_me();
class SM_Object* GetSumoObject ()
@@ -161,6 +173,9 @@ private:
class PHY_IMotionState* m_MotionState;
+ void* m_clientInfo;
+
+
};
#endif //__SUMO_PHYSICSCONTROLLER_H