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:
Diffstat (limited to 'source/gameengine/Physics/Sumo/Fuzzics/include')
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/include/SM_Callback.h10
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/include/SM_ClientObjectInfo.h15
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/include/SM_FhObject.h36
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/include/SM_MotionState.h36
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/include/SM_Object.h280
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/include/SM_Props.h60
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/include/SM_Scene.h129
7 files changed, 566 insertions, 0 deletions
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Callback.h b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Callback.h
new file mode 100644
index 00000000000..a43ddbec483
--- /dev/null
+++ b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Callback.h
@@ -0,0 +1,10 @@
+#ifndef SM_CALLBACK_H
+#define SM_CALLBACK_H
+
+class SM_Callback {
+public:
+ virtual void do_me() = 0;
+};
+
+#endif
+
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_ClientObjectInfo.h b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_ClientObjectInfo.h
new file mode 100644
index 00000000000..2063892e671
--- /dev/null
+++ b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_ClientObjectInfo.h
@@ -0,0 +1,15 @@
+#ifndef __SM_CLIENTOBJECT_INFO_H
+#define __SM_CLIENTOBJECT_INFO_H
+
+/**
+ * Client Type and Additional Info. This structure can be use instead of a bare void* pointer, for safeness, and additional info for callbacks
+ */
+
+struct SM_ClientObjectInfo
+{
+ int m_type;
+ void* m_clientobject;
+ void* m_auxilary_info;
+};
+
+#endif //__SM_CLIENTOBJECT_INFO_H
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_FhObject.h b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_FhObject.h
new file mode 100644
index 00000000000..4aac43f6712
--- /dev/null
+++ b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_FhObject.h
@@ -0,0 +1,36 @@
+#ifndef SM_FHOBJECT_H
+#define SM_FHOBJECT_H
+
+#include "SM_Object.h"
+
+class SM_FhObject : public SM_Object {
+public:
+ SM_FhObject() {}
+ SM_FhObject(const MT_Vector3& ray, SM_Object *client_object) :
+ SM_Object(DT_Ray(ray[0], ray[1], ray[2]), 0, 0, 0),
+ m_ray(ray),
+ m_ray_direction(ray.normalized()),
+ m_client_object(client_object) {}
+
+ const MT_Vector3& getRay() const { return m_ray; }
+ MT_Point3 getSpot() const { return m_pos + m_ray; }
+ const MT_Vector3& getRayDirection() const { return m_ray_direction; }
+ SM_Object *getClientObject() const { return m_client_object; }
+
+ static void ray_hit(void *client_data,
+ void *object1,
+ void *object2,
+ const DT_CollData *coll_data);
+
+private:
+ MT_Vector3 m_ray;
+ MT_Vector3 m_ray_direction;
+ SM_Object *m_client_object;
+};
+
+#endif
+
+
+
+
+
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_MotionState.h b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_MotionState.h
new file mode 100644
index 00000000000..9c6a9ddaec2
--- /dev/null
+++ b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_MotionState.h
@@ -0,0 +1,36 @@
+#ifndef SM_MOTIONSTATE_H
+#define SM_MOTIONSTATE_H
+
+#include "MT_Transform.h"
+
+class SM_MotionState {
+public:
+ SM_MotionState() :
+ m_pos(0.0, 0.0, 0.0),
+ m_orn(0.0, 0.0, 0.0, 1.0),
+ m_lin_vel(0.0, 0.0, 0.0),
+ m_ang_vel(0.0, 0.0, 0.0)
+ {}
+
+ void setPosition(const MT_Point3& pos) { m_pos = pos; }
+ void setOrientation(const MT_Quaternion& orn) { m_orn = orn; }
+ void setLinearVelocity(const MT_Vector3& lin_vel) { m_lin_vel = lin_vel; }
+ void setAngularVelocity(const MT_Vector3& ang_vel) { m_ang_vel = ang_vel; }
+
+ const MT_Point3& getPosition() const { return m_pos; }
+ const MT_Quaternion& getOrientation() const { return m_orn; }
+ const MT_Vector3& getLinearVelocity() const { return m_lin_vel; }
+ const MT_Vector3& getAngularVelocity() const { return m_ang_vel; }
+
+ virtual MT_Transform getTransform() const {
+ return MT_Transform(m_pos, m_orn);
+ }
+
+protected:
+ MT_Point3 m_pos;
+ MT_Quaternion m_orn;
+ MT_Vector3 m_lin_vel;
+ MT_Vector3 m_ang_vel;
+};
+
+#endif
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Object.h b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Object.h
new file mode 100644
index 00000000000..670da6e71db
--- /dev/null
+++ b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Object.h
@@ -0,0 +1,280 @@
+#ifndef SM_OBJECT_H
+#define SM_OBJECT_H
+
+#include <vector>
+
+#include "solid.h"
+
+#include "SM_Callback.h"
+#include "SM_MotionState.h"
+#include <stdio.h>
+
+
+class SM_FhObject;
+
+
+// Properties of dynamic objects
+struct SM_ShapeProps {
+ MT_Scalar m_mass; // Total mass
+ MT_Scalar 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)
+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?
+};
+
+
+class SM_Object : public SM_MotionState {
+public:
+ SM_Object() ;
+ SM_Object(
+ DT_ShapeHandle shape,
+ const SM_MaterialProps *materialProps,
+ const SM_ShapeProps *shapeProps,
+ SM_Object *dynamicParent
+ );
+
+ virtual ~SM_Object();
+
+ bool isDynamic() const;
+
+ /* nzc experimental. There seem to be two places where kinematics
+ * are evaluated: proceedKinematic (called from SM_Scene) and
+ * proceed() in this object. I'll just try and bunge these out for
+ * now. */
+
+ void suspend(void);
+ void resume(void);
+
+ void suspendDynamics();
+
+ void restoreDynamics();
+
+ bool isGhost() const;
+
+ void suspendMaterial();
+
+ void restoreMaterial();
+
+ SM_FhObject *getFhObject() const;
+
+ void registerCallback(SM_Callback& callback);
+
+ void calcXform();
+ void notifyClient();
+
+ // Save the current state information for use in the
+ // velocity computation in the next frame.
+
+ void proceedKinematic(MT_Scalar timeStep);
+
+ void saveReactionForce(MT_Scalar timeStep) ;
+
+ void clearForce() ;
+
+ void clearMomentum() ;
+
+ void setMargin(MT_Scalar margin) ;
+
+ MT_Scalar getMargin() const ;
+
+ const SM_MaterialProps *getMaterialProps() const ;
+
+ const SM_ShapeProps *getShapeProps() const ;
+
+ void setPosition(const MT_Point3& pos);
+ void setOrientation(const MT_Quaternion& orn);
+ void setScaling(const MT_Vector3& scaling);
+
+
+ /**
+ * set an external velocity. This velocity complements
+ * the physics velocity. So setting it does not override the
+ * physics velocity. It is your responsibility to clear
+ * 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);
+
+ /**
+ * Set an external angular velocity. This velocity complemetns
+ * the physics angular velocity so does not override it. It is
+ * 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
+ ) ;
+
+
+
+ MT_Scalar getInvMass() const;
+
+ MT_Scalar getInvInertia() const ;
+
+ void applyForceField(const MT_Vector3& accel) ;
+
+ void applyCenterForce(const MT_Vector3& force) ;
+
+ void applyTorque(const MT_Vector3& torque) ;
+
+ void applyImpulse(const MT_Point3& attach, const MT_Vector3& impulse) ;
+
+ void applyCenterImpulse(const MT_Vector3& impulse);
+
+ void applyAngularImpulse(const MT_Vector3& impulse);
+
+ MT_Point3 getWorldCoord(const MT_Point3& local) const;
+
+ MT_Vector3 getVelocity(const MT_Point3& local) const;
+
+
+ const MT_Vector3& getReactionForce() const ;
+
+ void getMatrix(double *m) const ;
+
+ const double *getMatrix() const ;
+
+ // Still need this???
+ const MT_Transform& getScaledTransform() const;
+
+ DT_ObjectHandle getObjectHandle() const ;
+ DT_ShapeHandle getShapeHandle() const ;
+
+ void setClientObject(void *clientobj) ;
+ void *getClientObject() ;
+
+ SM_Object *getDynamicParent() ;
+
+ void integrateForces(MT_Scalar timeStep);
+ void integrateMomentum(MT_Scalar timeSteo);
+
+ void setRigidBody(bool is_rigid_body) ;
+
+ bool isRigidBody() const ;
+
+
+ // This is the callback for handling collisions of dynamic objects
+ static
+ void
+ boing(
+ void *client_data,
+ void *object1,
+ void *object2,
+ const DT_CollData *coll_data
+ );
+
+private:
+
+ // return the actual linear_velocity of this object this
+ // is the addition of m_combined_lin_vel and m_lin_vel.
+
+ const
+ MT_Vector3
+ actualLinVelocity(
+ ) const ;
+
+ const
+ MT_Vector3
+ actualAngVelocity(
+ ) const ;
+
+ typedef std::vector<SM_Callback *> T_CallbackList;
+
+
+ T_CallbackList m_callbackList; // Each object can have multiple callbacks from the client (=game engine)
+ SM_Object *m_dynamicParent; // Collisions between parent and children are ignored
+
+ // as the collision callback now has only information
+ // on an SM_Object, there must be a way that the SM_Object client
+ // can identify it's clientdata after a collision
+ void *m_client_object;
+
+ DT_ShapeHandle m_shape; // Shape for collision detection
+
+ // Material and shape properties are not owned by this class.
+
+ const SM_MaterialProps *m_materialProps;
+ const SM_MaterialProps *m_materialPropsBackup; // Backup in case the object temporarily becomes a ghost.
+ const SM_ShapeProps *m_shapeProps;
+ const SM_ShapeProps *m_shapePropsBackup; // Backup in case the object's dynamics is temporarily suspended
+ DT_ObjectHandle m_object; // A handle to the corresponding object in SOLID.
+ MT_Scalar m_margin; // Offset for the object's shape (also for collision detection)
+ MT_Vector3 m_scaling; // Non-uniform scaling of the object's shape
+
+ double m_ogl_matrix[16]; // An OpenGL-type 4x4 matrix
+ MT_Transform m_xform; // The object's local coordinate system
+ MT_Transform m_prev_xform; // The object's local coordinate system in the previous frame
+ SM_MotionState m_prev_state; // The object's motion state in the previous frame
+ MT_Scalar m_timeStep; // The duration of the last frame
+
+ MT_Vector3 m_reaction_impulse; // The accumulated impulse resulting from collisions
+ MT_Vector3 m_reaction_force; // The reaction force derived from the reaction impulse
+
+ unsigned int m_kinematic : 1; // Have I been displaced (translated, rotated, scaled) in this frame?
+ unsigned int m_prev_kinematic : 1; // Have I been displaced (translated, rotated, scaled) in the previous frame?
+ unsigned int m_is_rigid_body : 1; // Should friction give me a change in angular momentum?
+
+ MT_Vector3 m_lin_mom; // Linear momentum (linear velocity times mass)
+ MT_Vector3 m_ang_mom; // Angular momentum (angualr velocity times inertia)
+ MT_Vector3 m_force; // Force on center of mass (afffects linear momentum)
+ MT_Vector3 m_torque; // Torque around center of mass (affects angualr momentum)
+
+ // Here are the values of externally set linear and angular
+ // velocity. These are updated from the outside
+ // (actuators and python) each frame and combined with the
+ // physics values. At the end of each frame (at the end of a
+ // call to proceed) they are set to zero. This allows the
+ // outside world to contribute to the velocity of an object
+ // but still have it react to physics.
+
+ MT_Vector3 m_combined_lin_vel;
+ MT_Vector3 m_combined_ang_vel;
+
+ // The force and torque are the accumulated forces and torques applied by the client (game logic, python).
+
+ SM_FhObject *m_fh_object; // The ray object used for Fh
+ bool m_suspended; // Is this object frozen?
+};
+
+#endif
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Props.h b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Props.h
new file mode 100644
index 00000000000..0b2efacac2a
--- /dev/null
+++ b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Props.h
@@ -0,0 +1,60 @@
+/**
+ * $Id$
+ *
+ * ***** BEGIN GPL/BL DUAL LICENSE BLOCK *****
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License
+ * as published by the Free Software Foundation; either version 2
+ * of the License, or (at your option) any later version. The Blender
+ * Foundation also sells licenses for use in proprietary software under
+ * the Blender License. See http://www.blender.org/BL/ for information
+ * about this.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software Foundation,
+ * Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA.
+ *
+ * The Original Code is Copyright (C) 2001-2002 by NaN Holding BV.
+ * All rights reserved.
+ *
+ * The Original Code is: all of this file.
+ *
+ * Contributor(s): none yet.
+ *
+ * ***** END GPL/BL DUAL LICENSE BLOCK *****
+ */
+#ifndef SM_PROPSH
+#define SM_PROPSH
+
+#include <MT_Scalar.h>
+
+// Properties of dynamic objects
+struct SM_ShapeProps {
+ MT_Scalar m_mass; // Total mass
+ MT_Scalar 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)
+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?
+};
+
+#endif //SM_PROPSH
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Scene.h b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Scene.h
new file mode 100644
index 00000000000..761e6c7c449
--- /dev/null
+++ b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Scene.h
@@ -0,0 +1,129 @@
+/**
+ * $Id$
+ * Copyright (C) 2001 NaN Technologies B.V.
+ * The physics scene.
+ */
+
+#ifndef SM_SCENE_H
+#define SM_SCENE_H
+
+#pragma warning (disable : 4786)
+
+#include <vector>
+#include <set>
+#include <utility> //needed for pair
+
+#include "solid.h"
+
+#include "MT_Vector3.h"
+#include "MT_Point3.h"
+
+class SM_Object;
+
+class SM_Scene {
+public:
+ SM_Scene() :
+ m_scene(DT_CreateScene()),
+ m_respTable(DT_CreateRespTable()),
+ m_secondaryRespTable(0),
+ m_forceField(0.0, 0.0, 0.0)
+ {}
+
+ ~SM_Scene() {
+ DT_DeleteRespTable(m_respTable);
+ DT_DeleteScene(m_scene);
+ }
+
+ DT_RespTableHandle getRespTableHandle() const {
+ return m_respTable;
+ }
+
+ const MT_Vector3& getForceField() const {
+ return m_forceField;
+ }
+
+ MT_Vector3& getForceField() {
+ return m_forceField;
+ }
+
+ void setForceField(const MT_Vector3& forceField) {
+ m_forceField = forceField;
+ }
+
+ void add(SM_Object& object);
+ void remove(SM_Object& object);
+
+ void addPair(SM_Object *obj1, SM_Object *obj2) {
+ m_pairList.insert(std::make_pair(obj1, obj2));
+ }
+
+ void clearPairs() {
+ m_pairList.clear();
+ }
+
+ void setSecondaryRespTable(DT_RespTableHandle secondaryRespTable) {
+ m_secondaryRespTable = secondaryRespTable;
+ }
+
+
+ // Perform an integration step of duration 'timeStep'.
+ // 'subSampling' is the maximum duration of a substep, i.e.,
+ // The maximum time interval between two collision checks.
+ // 'subSampling' can be used to control aliasing effects
+ // (fast moving objects traversing through walls and such).
+ void proceed(MT_Scalar timeStep, MT_Scalar subSampling);
+
+ /**
+ * Test whether any objects lie on the line defined by from and
+ * to. The search returns the first such bject starting at from,
+ * or NULL if there was none.
+ * @returns A reference to the object, or NULL if there was none.
+ * @param ignore_client Do not look for collisions with this
+ * object. This can be useful to avoid self-hits if
+ * starting from the location of an object.
+ * @param from The start point, in world coordinates, of the search.
+ * @param to The end point, in world coordinates, of the search.
+ * @param result A store to return the point where intersection
+ * took place (if there was an intersection).
+ * @param normal A store to return the normal of the hit object on
+ * the location of the intersection, if it took place.
+ */
+ SM_Object *rayTest(void *ignore_client,
+ const MT_Point3& from, const MT_Point3& to,
+ MT_Point3& result, MT_Vector3& normal) const;
+
+private:
+
+ // Clear the user set velocities.
+ void clearObjectCombinedVelocities();
+
+ /** internal type */
+ typedef std::vector<SM_Object *> T_ObjectList;
+ /** internal type */
+ typedef std::set<std::pair<SM_Object *, SM_Object *> > T_PairList;
+
+ /** Handle to the scene in SOLID */
+ DT_SceneHandle m_scene;
+ /** Following response table contains the callbacks for the dynmics */
+ DT_RespTableHandle m_respTable;
+ /**
+ * Following response table contains callbacks for the client (=
+ * game engine) */
+ DT_RespTableHandle m_secondaryRespTable; // Handle
+
+ /** The acceleration from the force field */
+ MT_Vector3 m_forceField;
+
+ /**
+ * The list of objects that receive motion updates and do
+ * collision tests. */
+ T_ObjectList m_objectList;
+
+ /**
+ * A list with pairs of objects that collided the previous
+ * timestep. The list is built during the proceed(). During that
+ * time, it is not valid. */
+ T_PairList m_pairList;
+};
+
+#endif