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')
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/Makefile34
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/include/SM_Callback.h11
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/include/SM_ClientObjectInfo.h16
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/include/SM_Debug.h26
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/include/SM_FhObject.h56
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/include/SM_MotionState.h77
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/include/SM_Object.h393
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/include/SM_Props.h58
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/include/SM_Scene.h172
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/sample/Makefile25
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/sample/particle.cpp709
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/sample/particle0.cpp695
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/src/Makefile14
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/src/SM_FhObject.cpp180
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/src/SM_MotionState.cpp100
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/src/SM_Object.cpp1298
-rw-r--r--source/gameengine/Physics/Sumo/Fuzzics/src/SM_Scene.cpp378
17 files changed, 0 insertions, 4242 deletions
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/Makefile b/source/gameengine/Physics/Sumo/Fuzzics/Makefile
deleted file mode 100644
index 5ed2c31a1d0..00000000000
--- a/source/gameengine/Physics/Sumo/Fuzzics/Makefile
+++ /dev/null
@@ -1,34 +0,0 @@
-#
-# $Id$
-#
-# ***** BEGIN GPL 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.
-#
-# 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 LICENSE BLOCK *****
-#
-# Bounces make to subdirectories.
-
-SOURCEDIR = source/gameengine/Physics/Sumo/Fuzzics
-DIRS = src
-
-include nan_subdirs.mk
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Callback.h b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Callback.h
deleted file mode 100644
index 42b5ab48ab6..00000000000
--- a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Callback.h
+++ /dev/null
@@ -1,11 +0,0 @@
-#ifndef SM_CALLBACK_H
-#define SM_CALLBACK_H
-
-class SM_Callback {
-public:
- virtual void do_me() = 0;
- virtual ~SM_Callback() {}
-};
-
-#endif
-
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_ClientObjectInfo.h b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_ClientObjectInfo.h
deleted file mode 100644
index 6749e7957ec..00000000000
--- a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_ClientObjectInfo.h
+++ /dev/null
@@ -1,16 +0,0 @@
-#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_clientobject1;
- void* m_auxilary_info;
-};
-
-#endif //__SM_CLIENTOBJECT_INFO_H
-
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Debug.h b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Debug.h
deleted file mode 100644
index 48d5906e53d..00000000000
--- a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Debug.h
+++ /dev/null
@@ -1,26 +0,0 @@
-
-
-#ifndef __SM_DEBUG_H__
-#define __SM_DEBUG_H__
-
-/* Comment this to disable all SUMO debugging printfs */
-
-#define SM_DEBUG
-
-#ifdef SM_DEBUG
-
-#include <stdio.h>
-
-/* Uncomment this to printf all ray casts */
-//#define SM_DEBUG_RAYCAST
-
-/* Uncomment this to printf collision callbacks */
-//#define SM_DEBUG_BOING
-
-/* Uncomment this to printf Xform matrix calculations */
-//#define SM_DEBUG_XFORM
-
-#endif /* SM_DEBUG */
-
-#endif /* __SM_DEBUG_H__ */
-
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_FhObject.h b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_FhObject.h
deleted file mode 100644
index b03612ed15e..00000000000
--- a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_FhObject.h
+++ /dev/null
@@ -1,56 +0,0 @@
-/**
- * $Id$
- *
- * ***** BEGIN GPL 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.
- *
- * 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 LICENSE BLOCK *****
- */
-#ifndef SM_FHOBJECT_H
-#define SM_FHOBJECT_H
-
-#include "SM_Object.h"
-
-class SM_FhObject : public SM_Object {
-public:
- virtual ~SM_FhObject();
- SM_FhObject(DT_ShapeHandle rayshape, MT_Vector3 ray, SM_Object *parent_object);
-
- const MT_Vector3& getRay() const { return m_ray; }
- MT_Point3 getSpot() const { return getPosition() + m_ray; }
- const MT_Vector3& getRayDirection() const { return m_ray_direction; }
- SM_Object *getParentObject() const { return m_parent_object; }
-
- static DT_Bool 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_parent_object;
-};
-
-#endif
-
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_MotionState.h b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_MotionState.h
deleted file mode 100644
index fdc45af5225..00000000000
--- a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_MotionState.h
+++ /dev/null
@@ -1,77 +0,0 @@
-/**
- * $Id$
- *
- * ***** BEGIN GPL 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.
- *
- * 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 LICENSE BLOCK *****
- */
-#ifndef SM_MOTIONSTATE_H
-#define SM_MOTIONSTATE_H
-
-#include "MT_Transform.h"
-
-class SM_MotionState {
-public:
- SM_MotionState() :
- m_time(0.0),
- 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; }
- void setTime(MT_Scalar time) { m_time = time; }
-
- 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; }
-
- MT_Scalar getTime() const { return m_time; }
-
- void integrateMidpoint(MT_Scalar timeStep, const SM_MotionState &prev_state, const MT_Vector3 &velocity, const MT_Quaternion& ang_vel);
- void integrateBackward(MT_Scalar timeStep, const MT_Vector3 &velocity, const MT_Quaternion& ang_vel);
- void integrateForward(MT_Scalar timeStep, const SM_MotionState &prev_state);
-
- void lerp(const SM_MotionState &prev, const SM_MotionState &next);
- void lerp(MT_Scalar t, const SM_MotionState &other);
-
- virtual MT_Transform getTransform() const {
- return MT_Transform(m_pos, m_orn);
- }
-
-protected:
- MT_Scalar m_time;
- 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
deleted file mode 100644
index 2d748a0f251..00000000000
--- a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Object.h
+++ /dev/null
@@ -1,393 +0,0 @@
-/**
- * $Id$
- *
- * ***** BEGIN GPL 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.
- *
- * 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 LICENSE BLOCK *****
- */
-#ifndef SM_OBJECT_H
-#define SM_OBJECT_H
-
-#include <vector>
-
-#include <SOLID/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_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) */
-struct SM_MaterialProps {
- 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?
-};
-
-class SM_ClientObject
-{
-public:
- SM_ClientObject() {}
- virtual ~SM_ClientObject() {}
-
- virtual bool hasCollisionCallback() = 0;
-};
-
-/**
- * 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_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();
- void updateInvInertiaTensor();
-
-
- // 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;
-
- const MT_Vector3& getInvInertia() const ;
-
- const MT_Matrix3x3& getInvInertiaTensor() const;
-
- void applyForceField(const MT_Vector3& accel) ;
-
- void applyCenterForce(const MT_Vector3& force) ;
-
- 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 center 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;
- MT_Point3 getLocalCoord(const MT_Point3& world) 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 ;
-
- 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
- DT_Bool
- boing(
- void *client_data,
- void *object1,
- void *object2,
- const DT_CollData *coll_data
- );
-
- static
- DT_Bool
- fix(
- void *client_data,
- void *object1,
- void *object2,
- const DT_CollData *coll_data
- );
-
-
- SM_ClientObject *getClientObject() { return m_client_object; }
- void setClientObject(SM_ClientObject *client_object) { m_client_object = client_object; }
- void setPhysicsClientObject(void* physicsClientObject)
- {
- m_physicsClientObject = physicsClientObject;
- }
- void* getPhysicsClientObject() {
- return m_physicsClientObject;
- }
- void relax();
-
- SM_MotionState &getCurrentFrame();
- SM_MotionState &getPreviousFrame();
- SM_MotionState &getNextFrame();
-
- const SM_MotionState &getCurrentFrame() const;
- const SM_MotionState &getPreviousFrame() const;
- const SM_MotionState &getNextFrame() const;
-
- // Motion state functions
- const MT_Point3& getPosition() const;
- const MT_Quaternion& getOrientation() const;
- const MT_Vector3& getLinearVelocity() const;
- const MT_Vector3& getAngularVelocity() const;
-
- MT_Scalar getTime() const;
-
- void setTime(MT_Scalar time);
-
- void interpolate(MT_Scalar timeStep);
- void endFrame();
-
-private:
- friend class Contact;
- // Tweak parameters
- static MT_Scalar ImpulseThreshold;
-
- // 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 ;
-
- void dynamicCollision(const MT_Point3 &local2,
- const MT_Vector3 &normal,
- MT_Scalar dist,
- const MT_Vector3 &rel_vel,
- MT_Scalar restitution,
- MT_Scalar friction_factor,
- MT_Scalar invMass
- );
-
- 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
- SM_ClientObject *m_client_object;
-
- void* m_physicsClientObject;
-
- 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
-
- 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 angular momentum)
-
- SM_MotionState m_frames[3];
-
- MT_Vector3 m_error; // Error in position:- amount object must be moved to prevent intersection with scene
-
- // 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?
-
- // Mass properties
- MT_Scalar m_inv_mass; // 1/mass
- MT_Vector3 m_inv_inertia; // [1/inertia_x, 1/inertia_y, 1/inertia_z]
- MT_Matrix3x3 m_inv_inertia_tensor; // Inverse Inertia Tensor
-
- bool m_kinematic; // Have I been displaced (translated, rotated, scaled) in this frame?
- bool m_prev_kinematic; // Have I been displaced (translated, rotated, scaled) in the previous frame?
- bool m_is_rigid_body; // Should friction give me a change in angular momentum?
- int m_static; // temporarily static.
-
-};
-
-#endif
-
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Props.h b/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Props.h
deleted file mode 100644
index 81b4cb55b45..00000000000
--- a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Props.h
+++ /dev/null
@@ -1,58 +0,0 @@
-/**
- * $Id$
- *
- * ***** BEGIN GPL 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.
- *
- * 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 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
deleted file mode 100644
index 3d8eef2bae0..00000000000
--- a/source/gameengine/Physics/Sumo/Fuzzics/include/SM_Scene.h
+++ /dev/null
@@ -1,172 +0,0 @@
-/**
- * $Id$
- * Copyright (C) 2001 NaN Technologies B.V.
- * The physics scene.
- *
- * ***** BEGIN GPL 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.
- *
- * 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 LICENSE BLOCK *****
- */
-#ifndef SM_SCENE_H
-#define SM_SCENE_H
-
-#ifdef WIN32
-#pragma warning (disable : 4786)
-#endif
-
-#include <vector>
-#include <set>
-#include <utility> //needed for pair
-
-#include <SOLID/SOLID.h>
-
-#include "MT_Vector3.h"
-#include "MT_Point3.h"
-
-#include "SM_Object.h"
-
-enum
-{
- FH_RESPONSE,
- SENSOR_RESPONSE, /* Touch Sensors */
- CAMERA_RESPONSE, /* Visibility Culling */
- OBJECT_RESPONSE, /* Object Dynamic Geometry Response */
- STATIC_RESPONSE, /* Static Geometry Response */
-
- NUM_RESPONSE
-};
-
-class SM_Scene {
-public:
- SM_Scene();
-
- ~SM_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 addTouchCallback(int response_class, DT_ResponseCallback callback, void *user);
-
- void addSensor(SM_Object& object);
- void add(SM_Object& object);
- void remove(SM_Object& object);
-
- void notifyCollision(SM_Object *obj1, SM_Object *obj2);
-
- void setSecondaryRespTable(DT_RespTableHandle secondaryRespTable);
- DT_RespTableHandle getSecondaryRespTable() { return m_secondaryRespTable; }
-
- void requestCollisionCallback(SM_Object &object);
-
- void beginFrame();
- void endFrame();
-
- // 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).
- bool proceed(MT_Scalar curtime, MT_Scalar ticrate);
- void proceed(MT_Scalar subStep);
-
- /**
- * 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();
- // This is the callback for handling collisions of dynamic objects
- static
- DT_Bool
- boing(
- void *client_data,
- void *object1,
- void *object2,
- const DT_CollData *coll_data
- );
-
- /** internal type */
- typedef std::vector<SM_Object *> T_ObjectList;
-
- /** Handle to the scene in SOLID */
- DT_SceneHandle m_scene;
- /** Following response table contains the callbacks for the dynmics */
- DT_RespTableHandle m_respTable;
- DT_ResponseClass m_ResponseClass[NUM_RESPONSE];
- /**
- * Following response table contains callbacks for the client (=
- * game engine) */
- DT_RespTableHandle m_secondaryRespTable; // Handle
- DT_ResponseClass m_secondaryResponseClass[NUM_RESPONSE];
-
- /**
- * Following resposne table contains callbacks for fixing the simulation
- * ie making sure colliding objects do not intersect.
- */
- DT_RespTableHandle m_fixRespTable;
- DT_ResponseClass m_fixResponseClass[NUM_RESPONSE];
-
- /** 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;
-
- unsigned int m_frames;
-};
-
-#endif
-
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/sample/Makefile b/source/gameengine/Physics/Sumo/Fuzzics/sample/Makefile
deleted file mode 100644
index 672dff39028..00000000000
--- a/source/gameengine/Physics/Sumo/Fuzzics/sample/Makefile
+++ /dev/null
@@ -1,25 +0,0 @@
-#
-# $Id$
-# Copyright (C) 2001 NaN Technologies B.V.
-
-DIR = $(OCGDIR)/sumo
-ALLTARGETS = $(OBJS) $(DIR)/$(DEBUG_DIR)particle $(DIR)/$(DEBUG_DIR)particle0
-
-include nan_compile.mk
-
-CPPFLAGS = -I../../include -I../include -I$(NAN_MOTO)/include
-CPPFLAGS += -I$(OPENGL_HEADERS)
-
-clean::
- @$(RM) $(DIR)/particle $(DIR)/particle0
- @$(RM) $(DIR)/debug/particle $(DIR)/debug/particle0
-
-LDFLAGS = -L$(DIR) -L/usr/X11R6/lib
-OGL_LDLIBS = -lglut -lGLU -lGL -pthread
-LDLIBS = -lfuzzics -lsolid $(NAN_MOTO)/lib/libmoto.a $(OGL_LDLIBS)
-
-$(DIR)/$(DEBUG_DIR)particle: particle.o $(DIR)/$(DEBUG_DIR)libfuzzics.a $(DIR)/$(DEBUG_DIR)libsolid.a
- $(CCC) $(CCFLAGS) $(CPPFLAGS) $(LDFLAGS) $< -o $@ $(LDLIBS)
-
-$(DIR)/$(DEBUG_DIR)particle0: particle0.o $(DIR)/$(DEBUG_DIR)libfuzzics.a $(DIR)/$(DEBUG_DIR)libsolid.a
- $(CCC) $(CCFLAGS) $(CPPFLAGS) $(LDFLAGS) $< -o $@ $(LDLIBS)
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/sample/particle.cpp b/source/gameengine/Physics/Sumo/Fuzzics/sample/particle.cpp
deleted file mode 100644
index d7aca326b42..00000000000
--- a/source/gameengine/Physics/Sumo/Fuzzics/sample/particle.cpp
+++ /dev/null
@@ -1,709 +0,0 @@
-//#define FAKE_IT
-#define USE_COMPLEX
-#define QUADS
-
-#include <algorithm>
-#include <new>
-#include <GL/glut.h>
-
-#include "MT_MinMax.h"
-#include "MT_Point3.h"
-#include "MT_Vector3.h"
-#include "MT_Quaternion.h"
-#include "MT_Matrix3x3.h"
-#include "MT_Transform.h"
-
-#include "SM_Object.h"
-#include "SM_FhObject.h"
-#include "SM_Scene.h"
-
-#include <SOLID/SOLID.h>
-
-#ifdef HAVE_CONFIG_H
-#include <config.h>
-#endif
-
-const MT_Scalar bowl_curv = 0.10;
-const MT_Scalar timeStep = 0.02;
-const MT_Scalar ground_margin = 0.0;
-const MT_Scalar sphere_radius = 0.5;
-
-const MT_Vector3 gravity(0, -9.8, 0);
-
-static MT_Scalar DISTANCE = 5;
-
-static MT_Scalar ele = 0, azi = 0;
-static MT_Point3 eye(0, 0, DISTANCE);
-static MT_Point3 center(0, 0, 0);
-
-inline double irnd() { return 2 * MT_random() - 1; }
-
-static const double SCALE_BOTTOM = 0.5;
-static const double SCALE_FACTOR = 2.0;
-
-SM_ShapeProps g_shapeProps = {
- 1.0, // mass
- 1.0, // inertia
- 0.1, // linear drag
- 0.1, // angular drag
- { 1.0, 0.0, 0.0 }, // anisotropic friction
- false, // do anisotropic friction?
- true, // do fh?
- true // do rot fh?
-};
-
-SM_MaterialProps g_materialProps = {
- 0.7, // restitution
- 0.0, // friction
- 10.0, // Fh spring constant
- 1.0, // Fh damping
- 0.5, // Fh distance
- true // Fh leveling
-};
-
-
-void toggleIdle();
-
-
-void newRandom();
-
-void coordSystem() {
- glDisable(GL_LIGHTING);
- glBegin(GL_LINES);
- glColor3f(1, 0, 0);
- glVertex3d(0, 0, 0);
- glVertex3d(10, 0, 0);
- glColor3f(0, 1, 0);
- glVertex3d(0, 0, 0);
- glVertex3d(0, 10, 0);
- glColor3f(0, 0, 1);
- glVertex3d(0, 0, 0);
- glVertex3d(0, 0, 10);
- glEnd();
- glEnable(GL_LIGHTING);
-}
-
-
-void display_bbox(const MT_Point3& min, const MT_Point3& max) {
- glDisable(GL_DEPTH_TEST);
- glDisable(GL_LIGHTING);
- glColor3f(0, 1, 1);
- glPolygonMode(GL_FRONT_AND_BACK, GL_LINE);
- glBegin(GL_QUAD_STRIP);
- glVertex3d(min[0], min[1], min[2]);
- glVertex3d(min[0], min[1], max[2]);
- glVertex3d(max[0], min[1], min[2]);
- glVertex3d(max[0], min[1], max[2]);
- glVertex3d(max[0], max[1], min[2]);
- glVertex3d(max[0], max[1], max[2]);
- glVertex3d(min[0], max[1], min[2]);
- glVertex3d(min[0], max[1], max[2]);
- glVertex3d(min[0], min[1], min[2]);
- glVertex3d(min[0], min[1], max[2]);
- glEnd();
- glPolygonMode(GL_FRONT_AND_BACK, GL_FILL);
- glEnable(GL_LIGHTING);
- glEnable(GL_DEPTH_TEST);
-}
-
-
-
-
-class GLShape {
-public:
- virtual void paint(GLdouble *m) const = 0;
-};
-
-
-class GLSphere : public GLShape {
- MT_Scalar radius;
-public:
- GLSphere(MT_Scalar r) : radius(r) {}
-
- void paint(GLdouble *m) const {
- glPushMatrix();
- glLoadMatrixd(m);
- coordSystem();
- glutSolidSphere(radius, 20, 20);
- glPopMatrix();
- }
-};
-
-
-class GLBox : public GLShape {
- MT_Vector3 extent;
-public:
- GLBox(MT_Scalar x, MT_Scalar y, MT_Scalar z) :
- extent(x, y, z) {}
-
- void paint(GLdouble *m) const {
- glPushMatrix();
- glLoadMatrixd(m);
- coordSystem();
- glPushMatrix();
- glScaled(extent[0], extent[1], extent[2]);
- glutSolidCube(1.0);
- glPopMatrix();
- glPopMatrix();
- }
-};
-
-
-class GLCone : public GLShape {
- MT_Scalar bottomRadius;
- MT_Scalar height;
- mutable GLuint displayList;
-
-public:
- GLCone(MT_Scalar r, MT_Scalar h) :
- bottomRadius(r),
- height(h),
- displayList(0) {}
-
- void paint(GLdouble *m) const {
- glPushMatrix();
- glLoadMatrixd(m);
- coordSystem();
- if (displayList) glCallList(displayList);
- else {
- GLUquadricObj *quadObj = gluNewQuadric();
- displayList = glGenLists(1);
- glNewList(displayList, GL_COMPILE_AND_EXECUTE);
- glPushMatrix();
- glRotatef(-90.0, 1.0, 0.0, 0.0);
- glTranslatef(0.0, 0.0, -1.0);
- gluQuadricDrawStyle(quadObj, (GLenum)GLU_FILL);
- gluQuadricNormals(quadObj, (GLenum)GLU_SMOOTH);
- gluCylinder(quadObj, bottomRadius, 0, height, 15, 10);
- glPopMatrix();
- glEndList();
- }
- glPopMatrix();
- }
-};
-
-class GLCylinder : public GLShape {
- MT_Scalar radius;
- MT_Scalar height;
- mutable GLuint displayList;
-
-public:
- GLCylinder(MT_Scalar r, MT_Scalar h) :
- radius(r),
- height(h),
- displayList(0) {}
-
- void paint(GLdouble *m) const {
- glPushMatrix();
- glLoadMatrixd(m);
- coordSystem();
- if (displayList) glCallList(displayList);
- else {
- GLUquadricObj *quadObj = gluNewQuadric();
- displayList = glGenLists(1);
- glNewList(displayList, GL_COMPILE_AND_EXECUTE);
- glPushMatrix();
- glRotatef(-90.0, 1.0, 0.0, 0.0);
- glTranslatef(0.0, 0.0, -1.0);
- gluQuadricDrawStyle(quadObj, (GLenum)GLU_FILL);
- gluQuadricNormals(quadObj, (GLenum)GLU_SMOOTH);
- gluCylinder(quadObj, radius, radius, height, 15, 10);
- glPopMatrix ();
- glEndList();
- }
- glPopMatrix();
- }
-};
-
-class Object;
-
-class Callback : public SM_Callback {
-public:
- Callback(Object& object) : m_object(object) {}
-
- virtual void do_me();
-
-private:
- Object& m_object;
-};
-
-
-class Object {
-public:
- Object(GLShape *gl_shape, SM_Object& object) :
- m_gl_shape(gl_shape),
- m_object(object),
- m_callback(*this)
- {
- m_object.registerCallback(m_callback);
- }
-
- ~Object() {}
-
- void paint() {
- if (m_gl_shape) {
- m_gl_shape->paint(m);
- // display_bbox(m_bbox.lower(), m_bbox.upper());
- }
- }
-
- void print_reaction_force() const {
- std::cout << m_object.getReactionForce() << std::endl;
- }
-
- MT_Vector3 getAhead() {
- return MT_Vector3(&m[4]);
- }
-
- MT_Vector3 getUp() {
- return MT_Vector3(&m[8]);
- }
-
- void clearMomentum() {
- m_object.clearMomentum();
- }
-
- void setMargin(MT_Scalar margin) {
- m_object.setMargin(margin);
- }
-
- void setScaling(const MT_Vector3& scaling) {
- m_object.setScaling(scaling);
- }
-
- const MT_Point3& getPosition() {
- return m_object.getPosition();
- }
-
- void setPosition(const MT_Point3& pos) {
- m_object.setPosition(pos);
- }
-
- void setOrientation(const MT_Quaternion& orn) {
- m_object.setOrientation(orn);
- }
-
- void applyCenterForce(const MT_Vector3& force) {
- m_object.applyCenterForce(force);
- }
-
- void applyTorque(const MT_Vector3& torque) {
- m_object.applyTorque(torque);
- }
-
- MT_Point3 getWorldCoord(const MT_Point3& local) const {
- return m_object.getWorldCoord(local);
- }
-
- MT_Vector3 getLinearVelocity() const {
- return m_object.getLinearVelocity();
- }
-
- MT_Vector3 getAngularVelocity() const {
- return m_object.getAngularVelocity();
- }
-
- void setMatrix() {
- m_object.calcXform();
- m_object.getMatrix(m);
- }
-
- const double *getMatrix() {
- m_object.calcXform();
- return m_object.getMatrix();
- }
-
-private:
- GLShape *m_gl_shape;
- SM_Object& m_object;
- DT_Scalar m[16];
- Callback m_callback;
-};
-
-
-
-const MT_Scalar SPACE_SIZE = 2;
-
-static GLSphere gl_sphere(sphere_radius);
-static GLBox gl_ground(50.0, 0.0, 50.0);
-
-
-
-#ifdef USE_COMPLEX
-
-const int GRID_SCALE = 10;
-const MT_Scalar GRID_UNIT = 25.0 / GRID_SCALE;
-
-DT_ShapeHandle createComplex() {
- DT_ShapeHandle shape = DT_NewComplexShape();
- for (int i0 = -GRID_SCALE; i0 != GRID_SCALE; ++i0) {
- for (int j0 = -GRID_SCALE; j0 != GRID_SCALE; ++j0) {
- int i1 = i0 + 1;
- int j1 = j0 + 1;
-#ifdef QUADS
- DT_Begin();
- DT_Vertex(GRID_UNIT * i0, bowl_curv * i0*i0, GRID_UNIT * j0);
- DT_Vertex(GRID_UNIT * i0, bowl_curv * i0*i0, GRID_UNIT * j1);
- DT_Vertex(GRID_UNIT * i1, bowl_curv * i1*i1, GRID_UNIT * j1);
- DT_Vertex(GRID_UNIT * i1, bowl_curv * i1*i1, GRID_UNIT * j0);
- DT_End();
-#else
- DT_Begin();
- DT_Vertex(GRID_UNIT * i0, 0, GRID_UNIT * j0);
- DT_Vertex(GRID_UNIT * i0, 0, GRID_UNIT * j1);
- DT_Vertex(GRID_UNIT * i1, 0, GRID_UNIT * j1);
- DT_End();
-
- DT_Begin();
- DT_Vertex(GRID_UNIT * i0, 0, GRID_UNIT * j1);
- DT_Vertex(GRID_UNIT * i1, 0, GRID_UNIT * j1);
- DT_Vertex(GRID_UNIT * i1, 0, GRID_UNIT * j0);
- DT_End();
-#endif
-
- }
- }
- DT_EndComplexShape();
- return shape;
-}
-
-
-static DT_ShapeHandle ground_shape = createComplex();
-
-#else
-
-static DT_ShapeHandle ground_shape = DT_Box(50, 0, 50);
-
-#endif
-
-static SM_Object sm_ground(ground_shape, &g_materialProps, 0, 0);
-static Object ground(&gl_ground, sm_ground);
-
-static SM_Object sm_sphere(DT_Sphere(0.0), &g_materialProps, &g_shapeProps, 0);
-static Object object(&gl_sphere, sm_sphere);
-
-
-static SM_Scene g_scene;
-
-
-bool g_hit = false;
-MT_Point3 g_spot;
-MT_Vector3 g_normal;
-
-
-void Callback::do_me()
-{
- m_object.setMatrix();
- m_object.print_reaction_force();
-}
-
-void myinit(void) {
-
- GLfloat light_ambient[] = { 0.0, 0.0, 0.0, 1.0 };
- GLfloat light_diffuse[] = { 1.0, 1.0, 1.0, 1.0 };
- GLfloat light_specular[] = { 1.0, 1.0, 1.0, 1.0 };
-
- /* light_position is NOT default value */
- GLfloat light_position0[] = { 1.0, 1.0, 1.0, 0.0 };
- GLfloat light_position1[] = { -1.0, -1.0, -1.0, 0.0 };
-
- glLightfv(GL_LIGHT0, GL_AMBIENT, light_ambient);
- glLightfv(GL_LIGHT0, GL_DIFFUSE, light_diffuse);
- glLightfv(GL_LIGHT0, GL_SPECULAR, light_specular);
- glLightfv(GL_LIGHT0, GL_POSITION, light_position0);
-
- glLightfv(GL_LIGHT1, GL_AMBIENT, light_ambient);
- glLightfv(GL_LIGHT1, GL_DIFFUSE, light_diffuse);
- glLightfv(GL_LIGHT1, GL_SPECULAR, light_specular);
- glLightfv(GL_LIGHT1, GL_POSITION, light_position1);
-
-
- glEnable(GL_LIGHTING);
- glEnable(GL_LIGHT0);
- glEnable(GL_LIGHT1);
-
- glShadeModel(GL_SMOOTH);
-
- glEnable(GL_DEPTH_TEST);
- glDepthFunc(GL_LESS);
-
- // glEnable(GL_CULL_FACE);
- // glCullFace(GL_BACK);
-
- ground.setPosition(MT_Point3(0, -10, 0));
- ground.setOrientation(MT_Quaternion(0, 0, 0, 1));
- ground.setMatrix();
- center.setValue(0.0, 0.0, 0.0);
- sm_ground.setMargin(ground_margin);
-
- g_scene.setForceField(gravity);
- g_scene.add(sm_ground);
-
- object.setMargin(sphere_radius);
-
- g_scene.add(sm_sphere);
-
-
- newRandom();
-}
-
-
-//MT_Point3 cp1, cp2;
-//bool intersection;
-
-void display(void) {
- glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
-
- ground.paint();
- object.paint();
-
- if (g_hit) {
- glDisable(GL_LIGHTING);
- glColor3f(1, 0, 0);
-
- glPointSize(5);
- glBegin(GL_POINTS);
- glVertex3d(g_spot[0], g_spot[1], g_spot[2]);
- glEnd();
- glPointSize(1);
-
- glColor3f(1, 1, 0);
- glBegin(GL_LINES);
- glVertex3d(g_spot[0], g_spot[1], g_spot[2]);
- glVertex3d(g_spot[0] + g_normal[0],
- g_spot[1] + g_normal[1],
- g_spot[2] + g_normal[2]);
- glEnd();
- glEnable(GL_LIGHTING);
- }
-
-
-
-#ifdef COLLISION
- glDisable(GL_DEPTH_TEST);
- glDisable(GL_LIGHTING);
- glColor3f(1, 1, 0);
- if (intersection) {
- glPointSize(5);
- glBegin(GL_POINTS);
- glVertex3d(cp1[0], cp1[1], cp1[2]);
- glEnd();
- glPointSize(1);
- }
- else {
- glBegin(GL_LINES);
- glVertex3d(cp1[0], cp1[1], cp1[2]);
- glVertex3d(cp2[0], cp2[1], cp2[2]);
- glEnd();
- }
- glEnable(GL_LIGHTING);
- glEnable(GL_DEPTH_TEST);
-#endif
-
- glFlush();
- glutSwapBuffers();
-}
-
-
-
-
-
-void newRandom() {
- object.setPosition(MT_Point3(0, 0, 0));
- object.setOrientation(MT_Quaternion::random());
- object.clearMomentum();
- object.setMatrix();
-
- display();
-}
-
-void moveAndDisplay() {
- g_scene.proceed(timeStep, 0.01);
-
- display();
- g_hit = false;
-}
-
-
-void turn_left() {
- object.applyTorque(5.0 * object.getUp());
-}
-
-void turn_right() {
- object.applyTorque(-5.0 * object.getUp());
-}
-
-void forward() {
- object.applyCenterForce(10.0 * object.getAhead());
-}
-
-void backward() {
- object.applyCenterForce(-10.0 * object.getAhead());
-}
-
-void jump() {
- object.applyCenterForce(MT_Vector3(0.0, 200.0, 0.0));
-}
-
-
-void toggleIdle() {
- static bool idle = true;
- if (idle) {
- glutIdleFunc(moveAndDisplay);
- idle = false;
- }
- else {
- glutIdleFunc(NULL);
- idle = true;
- }
-}
-
-
-void setCamera() {
- glMatrixMode(GL_PROJECTION);
- glLoadIdentity();
- glFrustum(-1.0, 1.0, -1.0, 1.0, 1.0, 200.0);
- MT_Scalar rele = MT_radians(ele);
- MT_Scalar razi = MT_radians(azi);
- eye.setValue(DISTANCE * sin(razi) * cos(rele),
- DISTANCE * sin(rele),
- DISTANCE * cos(razi) * cos(rele));
- gluLookAt(eye[0], eye[1], eye[2],
- center[0], center[1], center[2],
- 0, 1, 0);
- glMatrixMode(GL_MODELVIEW);
- display();
-}
-
-const MT_Scalar STEPSIZE = 5;
-
-void stepLeft() { azi -= STEPSIZE; if (azi < 0) azi += 360; setCamera(); }
-void stepRight() { azi += STEPSIZE; if (azi >= 360) azi -= 360; setCamera(); }
-void stepFront() { ele += STEPSIZE; if (azi >= 360) azi -= 360; setCamera(); }
-void stepBack() { ele -= STEPSIZE; if (azi < 0) azi += 360; setCamera(); }
-void zoomIn() { DISTANCE -= 1; setCamera(); }
-void zoomOut() { DISTANCE += 1; setCamera(); }
-
-
-void myReshape(int w, int h) {
- glViewport(0, 0, w, h);
- setCamera();
-}
-
-void myKeyboard(unsigned char key, int x, int y)
-{
- switch (key)
- {
- case 'w': forward(); break;
- case 's': backward(); break;
- case 'a': turn_left(); break;
- case 'd': turn_right(); break;
- case 'e': jump(); break;
- case 'l' : stepLeft(); break;
- case 'r' : stepRight(); break;
- case 'f' : stepFront(); break;
- case 'b' : stepBack(); break;
- case 'z' : zoomIn(); break;
- case 'x' : zoomOut(); break;
- case 'i' : toggleIdle(); break;
- case ' ' : newRandom(); break;
- default:
-// std::cout << "unused key : " << key << std::endl;
- break;
- }
-}
-
-void mySpecial(int key, int x, int y)
-{
- switch (key)
- {
- case GLUT_KEY_LEFT : stepLeft(); break;
- case GLUT_KEY_RIGHT : stepRight(); break;
- case GLUT_KEY_UP : stepFront(); break;
- case GLUT_KEY_DOWN : stepBack(); break;
- case GLUT_KEY_PAGE_UP : zoomIn(); break;
- case GLUT_KEY_PAGE_DOWN : zoomOut(); break;
- case GLUT_KEY_HOME : toggleIdle(); break;
- default:
-// std::cout << "unused (special) key : " << key << std::endl;
- break;
- }
-}
-
-void goodbye( void)
-{
- g_scene.remove(sm_ground);
- g_scene.remove(sm_sphere);
-
- std::cout << "goodbye ..." << std::endl;
- exit(0);
-}
-
-void menu(int choice)
-{
-
- static int fullScreen = 0;
- static int px, py, sx, sy;
-
- switch(choice) {
- case 1:
- if (fullScreen == 1) {
- glutPositionWindow(px,py);
- glutReshapeWindow(sx,sy);
- glutChangeToMenuEntry(1,"Full Screen",1);
- fullScreen = 0;
- } else {
- px=glutGet((GLenum)GLUT_WINDOW_X);
- py=glutGet((GLenum)GLUT_WINDOW_Y);
- sx=glutGet((GLenum)GLUT_WINDOW_WIDTH);
- sy=glutGet((GLenum)GLUT_WINDOW_HEIGHT);
- glutFullScreen();
- glutChangeToMenuEntry(1,"Close Full Screen",1);
- fullScreen = 1;
- }
- break;
- case 2:
- toggleIdle();
- break;
- case 3:
- goodbye();
- break;
- default:
- break;
- }
-}
-
-void createMenu()
-{
- glutCreateMenu(menu);
- glutAddMenuEntry("Full Screen", 1);
- glutAddMenuEntry("Toggle Idle (Start/Stop)", 2);
- glutAddMenuEntry("Quit", 3);
- glutAttachMenu(GLUT_RIGHT_BUTTON);
-}
-
-int main(int argc, char **argv) {
- glutInit(&argc, argv);
- glutInitDisplayMode(GLUT_DOUBLE | GLUT_RGB | GLUT_DEPTH);
- glutInitWindowPosition(0, 0);
- glutInitWindowSize(500, 500);
- glutCreateWindow("Physics demo");
-
- myinit();
- glutKeyboardFunc(myKeyboard);
- glutSpecialFunc(mySpecial);
- glutReshapeFunc(myReshape);
- createMenu();
- glutIdleFunc(NULL);
-
- glutDisplayFunc(display);
- glutMainLoop();
- return 0;
-}
-
-
-
-
-
-
-
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/sample/particle0.cpp b/source/gameengine/Physics/Sumo/Fuzzics/sample/particle0.cpp
deleted file mode 100644
index cdf0a2d8f64..00000000000
--- a/source/gameengine/Physics/Sumo/Fuzzics/sample/particle0.cpp
+++ /dev/null
@@ -1,695 +0,0 @@
-//#define FAKE_IT
-#define USE_COMPLEX
-#define QUADS
-
-#include <algorithm>
-#include <new>
-#include <GL/glut.h>
-
-#include "MT_MinMax.h"
-#include "MT_Point3.h"
-#include "MT_Vector3.h"
-#include "MT_Quaternion.h"
-#include "MT_Matrix3x3.h"
-#include "MT_Transform.h"
-
-#include "SM_Object.h"
-#include "SM_Scene.h"
-
-#include "solid.h"
-
-#ifdef HAVE_CONFIG_H
-#include <config.h>
-#endif
-
-const MT_Scalar bowl_curv = 0.10;
-const MT_Scalar timeStep = 0.04;
-const MT_Scalar ground_margin = 0.0;
-const MT_Scalar sphere_radius = 0.5;
-
-const MT_Vector3 gravity(0, -9.8, 0);
-
-static MT_Scalar DISTANCE = 5;
-
-static MT_Scalar ele = 0, azi = 0;
-static MT_Point3 eye(0, 0, DISTANCE);
-static MT_Point3 center(0, 0, 0);
-
-inline double irnd() { return 2 * MT_random() - 1; }
-
-static const double SCALE_BOTTOM = 0.5;
-static const double SCALE_FACTOR = 2.0;
-
-SM_ShapeProps g_shapeProps = {
- 1.0, // mass
- 1.0, // inertia
- 0.9, // linear drag
- 0.9 // angular drag
-};
-
-SM_MaterialProps g_materialProps = {
- 0.7, // restitution
- 0.0, // friction
- 0.0, // spring constant
- 0.0 // damping
-};
-
-
-void toggleIdle();
-
-
-void newRandom();
-
-void coordSystem() {
- glDisable(GL_LIGHTING);
- glBegin(GL_LINES);
- glColor3f(1, 0, 0);
- glVertex3d(0, 0, 0);
- glVertex3d(10, 0, 0);
- glColor3f(0, 1, 0);
- glVertex3d(0, 0, 0);
- glVertex3d(0, 10, 0);
- glColor3f(0, 0, 1);
- glVertex3d(0, 0, 0);
- glVertex3d(0, 0, 10);
- glEnd();
- glEnable(GL_LIGHTING);
-}
-
-
-void display_bbox(const MT_Point3& min, const MT_Point3& max) {
- glDisable(GL_DEPTH_TEST);
- glDisable(GL_LIGHTING);
- glColor3f(0, 1, 1);
- glPolygonMode(GL_FRONT_AND_BACK, GL_LINE);
- glBegin(GL_QUAD_STRIP);
- glVertex3d(min[0], min[1], min[2]);
- glVertex3d(min[0], min[1], max[2]);
- glVertex3d(max[0], min[1], min[2]);
- glVertex3d(max[0], min[1], max[2]);
- glVertex3d(max[0], max[1], min[2]);
- glVertex3d(max[0], max[1], max[2]);
- glVertex3d(min[0], max[1], min[2]);
- glVertex3d(min[0], max[1], max[2]);
- glVertex3d(min[0], min[1], min[2]);
- glVertex3d(min[0], min[1], max[2]);
- glEnd();
- glPolygonMode(GL_FRONT_AND_BACK, GL_FILL);
- glEnable(GL_LIGHTING);
- glEnable(GL_DEPTH_TEST);
-}
-
-
-
-
-class GLShape {
-public:
- virtual void paint(GLdouble *m) const = 0;
-};
-
-
-class GLSphere : public GLShape {
- MT_Scalar radius;
-public:
- GLSphere(MT_Scalar r) : radius(r) {}
-
- void paint(GLdouble *m) const {
- glPushMatrix();
- glLoadMatrixd(m);
- coordSystem();
- glutSolidSphere(radius, 20, 20);
- glPopMatrix();
- }
-};
-
-
-class GLBox : public GLShape {
- MT_Vector3 extent;
-public:
- GLBox(MT_Scalar x, MT_Scalar y, MT_Scalar z) :
- extent(x, y, z) {}
-
- void paint(GLdouble *m) const {
- glPushMatrix();
- glLoadMatrixd(m);
- coordSystem();
- glPushMatrix();
- glScaled(extent[0], extent[1], extent[2]);
- glutSolidCube(1.0);
- glPopMatrix();
- glPopMatrix();
- }
-};
-
-
-class GLCone : public GLShape {
- MT_Scalar bottomRadius;
- MT_Scalar height;
- mutable GLuint displayList;
-
-public:
- GLCone(MT_Scalar r, MT_Scalar h) :
- bottomRadius(r),
- height(h),
- displayList(0) {}
-
- void paint(GLdouble *m) const {
- glPushMatrix();
- glLoadMatrixd(m);
- coordSystem();
- if (displayList) glCallList(displayList);
- else {
- GLUquadricObj *quadObj = gluNewQuadric();
- displayList = glGenLists(1);
- glNewList(displayList, GL_COMPILE_AND_EXECUTE);
- glPushMatrix();
- glRotatef(-90.0, 1.0, 0.0, 0.0);
- glTranslatef(0.0, 0.0, -1.0);
- gluQuadricDrawStyle(quadObj, (GLenum)GLU_FILL);
- gluQuadricNormals(quadObj, (GLenum)GLU_SMOOTH);
- gluCylinder(quadObj, bottomRadius, 0, height, 15, 10);
- glPopMatrix();
- glEndList();
- }
- glPopMatrix();
- }
-};
-
-class GLCylinder : public GLShape {
- MT_Scalar radius;
- MT_Scalar height;
- mutable GLuint displayList;
-
-public:
- GLCylinder(MT_Scalar r, MT_Scalar h) :
- radius(r),
- height(h),
- displayList(0) {}
-
- void paint(GLdouble *m) const {
- glPushMatrix();
- glLoadMatrixd(m);
- coordSystem();
- if (displayList) glCallList(displayList);
- else {
- GLUquadricObj *quadObj = gluNewQuadric();
- displayList = glGenLists(1);
- glNewList(displayList, GL_COMPILE_AND_EXECUTE);
- glPushMatrix();
- glRotatef(-90.0, 1.0, 0.0, 0.0);
- glTranslatef(0.0, 0.0, -1.0);
- gluQuadricDrawStyle(quadObj, (GLenum)GLU_FILL);
- gluQuadricNormals(quadObj, (GLenum)GLU_SMOOTH);
- gluCylinder(quadObj, radius, radius, height, 15, 10);
- glPopMatrix ();
- glEndList();
- }
- glPopMatrix();
- }
-};
-
-class Object;
-
-class Callback : public SM_Callback {
-public:
- Callback(Object& object) : m_object(object) {}
-
- virtual void do_me();
-
-private:
- Object& m_object;
-};
-
-
-class Object {
-public:
- Object(GLShape *gl_shape, SM_Object& object) :
- m_gl_shape(gl_shape),
- m_object(object),
- m_callback(*this)
- {
- m_object.registerCallback(m_callback);
- }
-
- ~Object() {}
-
- void paint() {
- m_gl_shape->paint(m);
- // display_bbox(m_bbox.lower(), m_bbox.upper());
- }
-
- MT_Vector3 getAhead() {
- return MT_Vector3(-m[8], -m[9], -m[10]);
- }
-
- void clearMomentum() {
- m_object.clearMomentum();
- }
-
- void setMargin(MT_Scalar margin) {
- m_object.setMargin(margin);
- }
-
- void setScaling(const MT_Vector3& scaling) {
- m_object.setScaling(scaling);
- }
-
- void setPosition(const MT_Point3& pos) {
- m_object.setPosition(pos);
- }
-
- void setOrientation(const MT_Quaternion& orn) {
- m_object.setOrientation(orn);
- }
-
- void applyCenterForce(const MT_Vector3& force) {
- m_object.applyCenterForce(force);
- }
-
- void applyTorque(const MT_Vector3& torque) {
- m_object.applyTorque(torque);
- }
-
- MT_Point3 getWorldCoord(const MT_Point3& local) const {
- return m_object.getWorldCoord(local);
- }
-
- MT_Vector3 getLinearVelocity() const {
- return m_object.getLinearVelocity();
- }
-
- void setMatrix() {
- m_object.getMatrix(m);
- }
-
-private:
- GLShape *m_gl_shape;
- SM_Object& m_object;
- DT_Scalar m[16];
- Callback m_callback;
-};
-
-
-void Callback::do_me()
-{
- m_object.setMatrix();
-}
-
-
-const MT_Scalar SPACE_SIZE = 2;
-
-static GLSphere gl_sphere(sphere_radius);
-static GLBox gl_ground(50.0, 0.0, 50.0);
-
-
-
-#ifdef USE_COMPLEX
-
-const int GRID_SCALE = 10;
-const MT_Scalar GRID_UNIT = 25.0 / GRID_SCALE;
-
-DT_ShapeHandle createComplex() {
- DT_ShapeHandle shape = DT_NewComplexShape();
- for (int i0 = -GRID_SCALE; i0 != GRID_SCALE; ++i0) {
- for (int j0 = -GRID_SCALE; j0 != GRID_SCALE; ++j0) {
- int i1 = i0 + 1;
- int j1 = j0 + 1;
-#ifdef QUADS
- DT_Begin();
- DT_Vertex(GRID_UNIT * i0, bowl_curv * i0*i0, GRID_UNIT * j0);
- DT_Vertex(GRID_UNIT * i0, bowl_curv * i0*i0, GRID_UNIT * j1);
- DT_Vertex(GRID_UNIT * i1, bowl_curv * i1*i1, GRID_UNIT * j1);
- DT_Vertex(GRID_UNIT * i1, bowl_curv * i1*i1, GRID_UNIT * j0);
- DT_End();
-#else
- DT_Begin();
- DT_Vertex(GRID_UNIT * i0, 0, GRID_UNIT * j0);
- DT_Vertex(GRID_UNIT * i0, 0, GRID_UNIT * j1);
- DT_Vertex(GRID_UNIT * i1, 0, GRID_UNIT * j1);
- DT_End();
-
- DT_Begin();
- DT_Vertex(GRID_UNIT * i0, 0, GRID_UNIT * j1);
- DT_Vertex(GRID_UNIT * i1, 0, GRID_UNIT * j1);
- DT_Vertex(GRID_UNIT * i1, 0, GRID_UNIT * j0);
- DT_End();
-#endif
-
- }
- }
- DT_EndComplexShape();
- return shape;
-}
-
-
-static DT_ShapeHandle ground_shape = createComplex();
-
-#else
-
-static DT_ShapeHandle ground_shape = DT_Box(50, 0, 50);
-
-#endif
-
-static SM_Object sm_ground(ground_shape, &g_materialProps, 0, 0);
-static Object ground(&gl_ground, sm_ground);
-
-static SM_Object sm_sphere(DT_Sphere(0.0), &g_materialProps, &g_shapeProps, 0);
-static Object object(&gl_sphere, sm_sphere);
-
-
-static SM_Object sm_ray(DT_Ray(0.0, -1.0, 0.0), 0, 0, 0);
-
-static SM_Scene g_scene;
-
-
-void myinit(void) {
-
- GLfloat light_ambient[] = { 0.0, 0.0, 0.0, 1.0 };
- GLfloat light_diffuse[] = { 1.0, 1.0, 1.0, 1.0 };
- GLfloat light_specular[] = { 1.0, 1.0, 1.0, 1.0 };
-
- /* light_position is NOT default value */
- GLfloat light_position0[] = { 1.0, 1.0, 1.0, 0.0 };
- GLfloat light_position1[] = { -1.0, -1.0, -1.0, 0.0 };
-
- glLightfv(GL_LIGHT0, GL_AMBIENT, light_ambient);
- glLightfv(GL_LIGHT0, GL_DIFFUSE, light_diffuse);
- glLightfv(GL_LIGHT0, GL_SPECULAR, light_specular);
- glLightfv(GL_LIGHT0, GL_POSITION, light_position0);
-
- glLightfv(GL_LIGHT1, GL_AMBIENT, light_ambient);
- glLightfv(GL_LIGHT1, GL_DIFFUSE, light_diffuse);
- glLightfv(GL_LIGHT1, GL_SPECULAR, light_specular);
- glLightfv(GL_LIGHT1, GL_POSITION, light_position1);
-
-
- glEnable(GL_LIGHTING);
- glEnable(GL_LIGHT0);
- glEnable(GL_LIGHT1);
-
- glShadeModel(GL_SMOOTH);
-
- glEnable(GL_DEPTH_TEST);
- glDepthFunc(GL_LESS);
-
- // glEnable(GL_CULL_FACE);
- // glCullFace(GL_BACK);
-
- g_scene.setForceField(gravity);
- g_scene.add(sm_ground);
- sm_ground.setMargin(ground_margin);
-
- new(&object) Object(&gl_sphere, sm_sphere);
-
-
- object.setMargin(sphere_radius);
-
- g_scene.add(sm_sphere);
-
- ground.setPosition(MT_Point3(0, -10, 0));
- ground.setOrientation(MT_Quaternion(0, 0, 0, 1));
- ground.setMatrix();
- center.setValue(0.0, 0.0, 0.0);
-
- newRandom();
-}
-
-
-//MT_Point3 cp1, cp2;
-//bool intersection;
-
-bool g_hit = false;
-MT_Point3 g_spot;
-MT_Vector3 g_normal;
-
-
-void display(void) {
- glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
-
- ground.paint();
- object.paint();
-
- if (g_hit) {
- glPointSize(5);
- glBegin(GL_POINTS);
- glVertex3d(g_spot[0], g_spot[1], g_spot[2]);
- glEnd();
- glPointSize(1);
- }
-
-
-
-#ifdef COLLISION
- glDisable(GL_DEPTH_TEST);
- glDisable(GL_LIGHTING);
- glColor3f(1, 1, 0);
- if (intersection) {
- glPointSize(5);
- glBegin(GL_POINTS);
- glVertex3d(cp1[0], cp1[1], cp1[2]);
- glEnd();
- glPointSize(1);
- }
- else {
- glBegin(GL_LINES);
- glVertex3d(cp1[0], cp1[1], cp1[2]);
- glVertex3d(cp2[0], cp2[1], cp2[2]);
- glEnd();
- }
- glEnable(GL_LIGHTING);
- glEnable(GL_DEPTH_TEST);
-#endif
-
- glFlush();
- glutSwapBuffers();
-}
-
-
-
-
-
-void newRandom() {
- object.setPosition(MT_Point3(0, 0, 0));
- object.clearMomentum();
- object.setMatrix();
-
- display();
-}
-
-void moveAndDisplay() {
- g_scene.proceed(timeStep, 0.01);
-
- MT_Vector3 normal(0, 1, 0);
-
- MT_Point3 from = object.getWorldCoord(MT_Point3(0, 0, 0));
- MT_Point3 to = from - normal * 10.0;
-
- g_hit = DT_ObjectRayTest(sm_ground.getObjectHandle(),
- from.getValue(),
- to.getValue(), g_spot.getValue(),
- g_normal.getValue());
-
- // Scrap
-#define DO_FH
-#ifdef DO_FH
- MT_Scalar dist = MT_distance(from, g_spot);
- if (dist < 5.0) {
- MT_Vector3 lin_vel = object.getLinearVelocity();
- MT_Scalar lin_vel_normal = lin_vel.dot(normal);
-
- MT_Scalar spring_extent = dist + lin_vel_normal * (timeStep * 0.5);
-
- MT_Scalar f_spring = (5.0 - spring_extent) * 3.0;
- object.applyCenterForce(normal * f_spring);
- object.applyCenterForce(-lin_vel_normal * normal);
- }
-
-#endif
-
-
- display();
-}
-
-
-void turn_left() {
- object.applyTorque(MT_Vector3(0.0, 10.0, 0.0));
-}
-
-void turn_right() {
- object.applyTorque(MT_Vector3(0.0, -10.0, 0.0));
-}
-
-void forward() {
- object.applyCenterForce(20.0 * object.getAhead());
-}
-
-void backward() {
- object.applyCenterForce(-20.0 * object.getAhead());
-}
-
-void jump() {
- object.applyCenterForce(MT_Vector3(0.0, 200.0, 0.0));
-}
-
-
-void toggleIdle() {
- static bool idle = true;
- if (idle) {
- glutIdleFunc(moveAndDisplay);
- idle = false;
- }
- else {
- glutIdleFunc(NULL);
- idle = true;
- }
-}
-
-
-void setCamera() {
- glMatrixMode(GL_PROJECTION);
- glLoadIdentity();
- glFrustum(-1.0, 1.0, -1.0, 1.0, 1.0, 200.0);
- MT_Scalar rele = MT_radians(ele);
- MT_Scalar razi = MT_radians(azi);
- eye.setValue(DISTANCE * sin(razi) * cos(rele),
- DISTANCE * sin(rele),
- DISTANCE * cos(razi) * cos(rele));
- gluLookAt(eye[0], eye[1], eye[2],
- center[0], center[1], center[2],
- 0, 1, 0);
- glMatrixMode(GL_MODELVIEW);
- display();
-}
-
-const MT_Scalar STEPSIZE = 5;
-
-void stepLeft() { azi -= STEPSIZE; if (azi < 0) azi += 360; setCamera(); }
-void stepRight() { azi += STEPSIZE; if (azi >= 360) azi -= 360; setCamera(); }
-void stepFront() { ele += STEPSIZE; if (azi >= 360) azi -= 360; setCamera(); }
-void stepBack() { ele -= STEPSIZE; if (azi < 0) azi += 360; setCamera(); }
-void zoomIn() { DISTANCE -= 1; setCamera(); }
-void zoomOut() { DISTANCE += 1; setCamera(); }
-
-
-void myReshape(int w, int h) {
- glViewport(0, 0, w, h);
- setCamera();
-}
-
-void myKeyboard(unsigned char key, int x, int y)
-{
- switch (key)
- {
- case 'w': forward(); break;
- case 's': backward(); break;
- case 'a': turn_left(); break;
- case 'd': turn_right(); break;
- case 'e': jump(); break;
- case 'l' : stepLeft(); break;
- case 'r' : stepRight(); break;
- case 'f' : stepFront(); break;
- case 'b' : stepBack(); break;
- case 'z' : zoomIn(); break;
- case 'x' : zoomOut(); break;
- case 'i' : toggleIdle(); break;
- case ' ' : newRandom(); break;
- default:
-// std::cout << "unused key : " << key << std::endl;
- break;
- }
-}
-
-void mySpecial(int key, int x, int y)
-{
- switch (key)
- {
- case GLUT_KEY_LEFT : stepLeft(); break;
- case GLUT_KEY_RIGHT : stepRight(); break;
- case GLUT_KEY_UP : stepFront(); break;
- case GLUT_KEY_DOWN : stepBack(); break;
- case GLUT_KEY_PAGE_UP : zoomIn(); break;
- case GLUT_KEY_PAGE_DOWN : zoomOut(); break;
- case GLUT_KEY_HOME : toggleIdle(); break;
- default:
-// std::cout << "unused (special) key : " << key << std::endl;
- break;
- }
-}
-
-void goodbye( void)
-{
- g_scene.remove(sm_ground);
- g_scene.remove(sm_sphere);
-
- std::cout << "goodbye ..." << std::endl;
- exit(0);
-}
-
-void menu(int choice)
-{
-
- static int fullScreen = 0;
- static int px, py, sx, sy;
-
- switch(choice) {
- case 1:
- if (fullScreen == 1) {
- glutPositionWindow(px,py);
- glutReshapeWindow(sx,sy);
- glutChangeToMenuEntry(1,"Full Screen",1);
- fullScreen = 0;
- } else {
- px=glutGet((GLenum)GLUT_WINDOW_X);
- py=glutGet((GLenum)GLUT_WINDOW_Y);
- sx=glutGet((GLenum)GLUT_WINDOW_WIDTH);
- sy=glutGet((GLenum)GLUT_WINDOW_HEIGHT);
- glutFullScreen();
- glutChangeToMenuEntry(1,"Close Full Screen",1);
- fullScreen = 1;
- }
- break;
- case 2:
- toggleIdle();
- break;
- case 3:
- goodbye();
- break;
- default:
- break;
- }
-}
-
-void createMenu()
-{
- glutCreateMenu(menu);
- glutAddMenuEntry("Full Screen", 1);
- glutAddMenuEntry("Toggle Idle (Start/Stop)", 2);
- glutAddMenuEntry("Quit", 3);
- glutAttachMenu(GLUT_RIGHT_BUTTON);
-}
-
-int main(int argc, char **argv) {
- glutInit(&argc, argv);
- glutInitDisplayMode(GLUT_DOUBLE | GLUT_RGB | GLUT_DEPTH);
- glutInitWindowPosition(0, 0);
- glutInitWindowSize(500, 500);
- glutCreateWindow("Physics demo");
-
- myinit();
- glutKeyboardFunc(myKeyboard);
- glutSpecialFunc(mySpecial);
- glutReshapeFunc(myReshape);
- createMenu();
- glutIdleFunc(NULL);
-
- glutDisplayFunc(display);
- glutMainLoop();
- return 0;
-}
-
-
-
-
-
-
-
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/src/Makefile b/source/gameengine/Physics/Sumo/Fuzzics/src/Makefile
deleted file mode 100644
index b2744c5496a..00000000000
--- a/source/gameengine/Physics/Sumo/Fuzzics/src/Makefile
+++ /dev/null
@@ -1,14 +0,0 @@
-#
-# $Id$
-# Copyright (C) 2001 NaN Technologies B.V.
-
-LIBNAME = fuzzics
-DIR = $(OCGDIR)/gameengine/blphys/$(LIBNAME)
-
-include nan_compile.mk
-
-CCFLAGS += $(LEVEL_1_CPP_WARNINGS)
-
-CPPFLAGS += -I../include -I$(NAN_MOTO)/include -I../../include
-CPPFLAGS += -I$(NAN_SOLID)/include
-
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/src/SM_FhObject.cpp b/source/gameengine/Physics/Sumo/Fuzzics/src/SM_FhObject.cpp
deleted file mode 100644
index d866cdb4922..00000000000
--- a/source/gameengine/Physics/Sumo/Fuzzics/src/SM_FhObject.cpp
+++ /dev/null
@@ -1,180 +0,0 @@
-/**
- * $Id$
- *
- * ***** BEGIN GPL 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.
- *
- * 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 LICENSE BLOCK *****
- */
-#include "SM_FhObject.h"
-#include "MT_MinMax.h"
-
-#ifdef HAVE_CONFIG_H
-#include <config.h>
-#endif
-
-SM_FhObject::SM_FhObject(DT_ShapeHandle rayshape, MT_Vector3 ray, SM_Object *parent_object) :
- SM_Object(rayshape, NULL, NULL, NULL),
- m_ray(ray),
- m_ray_direction(ray.normalized()),
- m_parent_object(parent_object)
-{
-}
-
-SM_FhObject::~SM_FhObject()
-{
- DT_DeleteShape(getShapeHandle());
-}
-
-DT_Bool SM_FhObject::ray_hit(void *client_data,
- void *client_object1,
- void *client_object2,
- const DT_CollData *coll_data)
-{
-
- SM_FhObject *fh_object = dynamic_cast<SM_FhObject *>((SM_Object *)client_object2);
- if (!fh_object)
- {
- std::swap(client_object1, client_object2);
- fh_object = dynamic_cast<SM_FhObject *>((SM_Object *)client_object2);
- }
-
- SM_Object *hit_object = (SM_Object *)client_object1;
- const SM_MaterialProps *matProps = hit_object->getMaterialProps();
-
- if ((matProps == 0) || (matProps->m_fh_distance < MT_EPSILON)) {
- return DT_CONTINUE;
- }
-
- SM_Object *cl_object = fh_object->getParentObject();
-
- assert(fh_object);
-
- if (hit_object == cl_object) {
- // Shot myself in the foot...
- return DT_CONTINUE;
- }
-
- const SM_ShapeProps *shapeProps = cl_object->getShapeProps();
-
- // Exit if the client object is not dynamic.
- if (shapeProps == 0) {
- return DT_CONTINUE;
- }
-
- MT_Point3 lspot;
- MT_Vector3 normal;
-
- DT_Vector3 from, to, dnormal;
- DT_Scalar dlspot;
- fh_object->getPosition().getValue(from);
- fh_object->getSpot().getValue(to);
-
-
- if (DT_ObjectRayCast(hit_object->getObjectHandle(),
- from,
- to,
- 1.,
- &dlspot,
- dnormal)) {
-
- lspot = fh_object->getPosition() + (fh_object->getSpot() - fh_object->getPosition()) * dlspot;
- const MT_Vector3& ray_dir = fh_object->getRayDirection();
- MT_Scalar dist = MT_distance(fh_object->getPosition(), lspot) -
- cl_object->getMargin() - shapeProps->m_radius;
-
- normal = MT_Vector3(dnormal).safe_normalized();
-
- if (dist < matProps->m_fh_distance) {
-
- if (shapeProps->m_do_fh) {
- lspot -= hit_object->getPosition();
- MT_Vector3 rel_vel = cl_object->getLinearVelocity() - hit_object->getVelocity(lspot);
- MT_Scalar rel_vel_ray = ray_dir.dot(rel_vel);
- MT_Scalar spring_extent = 1.0 - dist / matProps->m_fh_distance;
-
- MT_Scalar i_spring = spring_extent * matProps->m_fh_spring;
- MT_Scalar i_damp = rel_vel_ray * matProps->m_fh_damping;
-
- cl_object->addLinearVelocity(-(i_spring + i_damp) * ray_dir);
- if (matProps->m_fh_normal) {
- cl_object->addLinearVelocity(
- (i_spring + i_damp) *
- (normal - normal.dot(ray_dir) * ray_dir));
- }
-
- MT_Vector3 lateral = rel_vel - rel_vel_ray * ray_dir;
- const SM_ShapeProps *shapeProps = cl_object->getShapeProps();
-
- if (shapeProps->m_do_anisotropic) {
- MT_Matrix3x3 lcs(cl_object->getOrientation());
- MT_Vector3 loc_lateral = lateral * lcs;
- const MT_Vector3& friction_scaling =
- shapeProps->m_friction_scaling;
-
- loc_lateral.scale(friction_scaling[0],
- friction_scaling[1],
- friction_scaling[2]);
- lateral = lcs * loc_lateral;
- }
-
-
- MT_Scalar rel_vel_lateral = lateral.length();
-
- if (rel_vel_lateral > MT_EPSILON) {
- MT_Scalar friction_factor = matProps->m_friction;
- MT_Scalar max_friction = friction_factor * MT_max(MT_Scalar(0.0), i_spring);
-
- MT_Scalar rel_mom_lateral = rel_vel_lateral /
- cl_object->getInvMass();
-
- MT_Vector3 friction =
- (rel_mom_lateral > max_friction) ?
- -lateral * (max_friction / rel_vel_lateral) :
- -lateral;
-
- cl_object->applyCenterImpulse(friction);
- }
- }
-
- if (shapeProps->m_do_rot_fh) {
- const double *ogl_mat = cl_object->getMatrix();
- MT_Vector3 up(&ogl_mat[8]);
- MT_Vector3 t_spring = up.cross(normal) * matProps->m_fh_spring;
- MT_Vector3 ang_vel = cl_object->getAngularVelocity();
-
- // only rotations that tilt relative to the normal are damped
- ang_vel -= ang_vel.dot(normal) * normal;
-
- MT_Vector3 t_damp = ang_vel * matProps->m_fh_damping;
-
- cl_object->addAngularVelocity(t_spring - t_damp);
- }
- }
- }
-
- return DT_CONTINUE;
-}
-
-
-
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/src/SM_MotionState.cpp b/source/gameengine/Physics/Sumo/Fuzzics/src/SM_MotionState.cpp
deleted file mode 100644
index b8f4e0c591c..00000000000
--- a/source/gameengine/Physics/Sumo/Fuzzics/src/SM_MotionState.cpp
+++ /dev/null
@@ -1,100 +0,0 @@
-/**
- * $Id$
- *
- * ***** BEGIN GPL 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.
- *
- * 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 LICENSE BLOCK *****
- */
-#include <MT_Scalar.h>
-#include <MT_Vector3.h>
-#include <MT_Quaternion.h>
-
-#include "SM_MotionState.h"
-
-void SM_MotionState::integrateMidpoint(MT_Scalar timeStep, const SM_MotionState &prev_state, const MT_Vector3 &velocity, const MT_Quaternion& ang_vel)
-{
- m_pos += (prev_state.getLinearVelocity() + velocity) * (timeStep * 0.5);
- m_orn += (prev_state.getAngularVelocity() * prev_state.getOrientation() + ang_vel * m_orn) * (timeStep * 0.25);
- m_orn.normalize();
-}
-
-void SM_MotionState::integrateBackward(MT_Scalar timeStep, const MT_Vector3 &velocity, const MT_Quaternion& ang_vel)
-{
- m_pos += velocity * timeStep;
- m_orn += ang_vel * m_orn * (timeStep * 0.5);
- m_orn.normalize();
-}
-
-void SM_MotionState::integrateForward(MT_Scalar timeStep, const SM_MotionState &prev_state)
-{
- m_pos += prev_state.getLinearVelocity() * timeStep;
- m_orn += prev_state.getAngularVelocity() * m_orn * (timeStep * 0.5);
- m_orn.normalize();
-}
-
-/*
-// Newtonian lerp: interpolate based on Newtonian motion
-void SM_MotionState::nlerp(const SM_MotionState &prev, const SM_MotionState &next)
-{
- MT_Scalar dt = next.getTime() - prev.getTime();
- MT_Scalar t = getTime() - prev.getTime();
- MT_Vector3 dx = next.getPosition() - prev.getPosition();
- MT_Vector3 a = dx/(dt*dt) - prev.getLinearVelocity()/dt;
-
- m_pos = prev.getPosition() + prev.getLinearVelocity()*t + a*t*t;
-}
-*/
-
-void SM_MotionState::lerp(const SM_MotionState &prev, const SM_MotionState &next)
-{
- MT_Scalar dt = next.getTime() - prev.getTime();
- if (MT_fuzzyZero(dt))
- {
- *this = next;
- return;
- }
-
- MT_Scalar x = (getTime() - prev.getTime())/dt;
-
- m_pos = x*next.getPosition() + (1-x)*prev.getPosition();
-
- m_orn = prev.getOrientation().slerp(next.getOrientation(), 1-x);
-
- m_lin_vel = x*next.getLinearVelocity() + (1-x)*prev.getLinearVelocity();
- m_ang_vel = x*next.getAngularVelocity() + (1-x)*prev.getAngularVelocity();
-}
-
-void SM_MotionState::lerp(MT_Scalar t, const SM_MotionState &other)
-{
- MT_Scalar x = (t - getTime())/(other.getTime() - getTime());
- m_pos = (1-x)*m_pos + x*other.getPosition();
-
- m_orn = other.getOrientation().slerp(m_orn, x);
-
- m_lin_vel = (1-x)*m_lin_vel + x*other.getLinearVelocity();
- m_ang_vel = (1-x)*m_ang_vel + x*other.getAngularVelocity();
-
- m_time = t;
-}
-
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/src/SM_Object.cpp b/source/gameengine/Physics/Sumo/Fuzzics/src/SM_Object.cpp
deleted file mode 100644
index 4b2c7cae008..00000000000
--- a/source/gameengine/Physics/Sumo/Fuzzics/src/SM_Object.cpp
+++ /dev/null
@@ -1,1298 +0,0 @@
-/**
- * $Id$
- * Copyright (C) 2001 NaN Technologies B.V.
- * The basic physics object.
- *
- * ***** BEGIN GPL 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.
- *
- * 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 LICENSE BLOCK *****
- */
-
-#ifdef HAVE_CONFIG_H
-#include <config.h>
-#endif
-
-#ifdef WIN32
-// This warning tells us about truncation of __long__ stl-generated names.
-// It can occasionally cause DevStudio to have internal compiler warnings.
-#pragma warning( disable : 4786 )
-#endif
-
-#include "MT_assert.h"
-
-#include "SM_Object.h"
-#include "SM_Scene.h"
-#include "SM_FhObject.h"
-#include "SM_Debug.h"
-
-#include "MT_MinMax.h"
-
-MT_Scalar SM_Object::ImpulseThreshold = -1.0;
-
-struct Contact
-{
- SM_Object *obj1;
- SM_Object *obj2;
- MT_Vector3 normal;
- MT_Point3 pos;
-
- // Sort objects by height
- bool operator()(const Contact *a, const Contact *b)
- {
- return a->pos[2] < b->pos[2];
- }
-
- Contact(SM_Object *o1, SM_Object *o2, const MT_Vector3 nor, const MT_Point3 p)
- : obj1(o1),
- obj2(o2),
- normal(nor),
- pos(p)
- {
- }
-
- Contact()
- {
- }
-
- void resolve()
- {
- if (obj1->m_static || obj2->m_static)
- {
- if (obj1->isDynamic())
- {
- if (obj1->m_static && obj2->m_static)
- {
- if (obj1->m_static < obj2->m_static)
- {
- obj2->m_error -= normal;
- obj2->m_static = obj1->m_static + 1;
- }
- else
- {
- obj1->m_error += normal;
- obj1->m_static = obj2->m_static + 1;
- }
- }
- else
- {
- if (obj1->m_static)
- {
- obj2->m_error -= normal;
- obj2->m_static = obj1->m_static + 1;
- }
- else
- {
- obj1->m_error += normal;
- obj1->m_static = obj2->m_static + 1;
- }
- }
- }
- else
- {
- obj2->m_error -= normal;
- obj2->m_static = 1;
- }
- }
- else
- {
- // This distinction between dynamic and non-dynamic objects should not be
- // necessary. Non-dynamic objects are assumed to have infinite mass.
- if (obj1->isDynamic()) {
- MT_Vector3 error = normal * 0.5f;
- obj1->m_error += error;
- obj2->m_error -= error;
- }
- else {
- // Same again but now obj1 is non-dynamic
- obj2->m_error -= normal;
- obj2->m_static = obj1->m_static + 1;
- }
- }
-
- }
-
-
- typedef std::set<Contact*, Contact> Set;
-};
-
-static Contact::Set contacts;
-
-SM_Object::SM_Object(
- DT_ShapeHandle shape,
- const SM_MaterialProps *materialProps,
- const SM_ShapeProps *shapeProps,
- SM_Object *dynamicParent) :
-
- m_dynamicParent(dynamicParent),
- m_client_object(0),
- m_physicsClientObject(0),
- m_shape(shape),
- m_materialProps(materialProps),
- m_materialPropsBackup(0),
- m_shapeProps(shapeProps),
- m_shapePropsBackup(0),
- m_margin(0.0),
- m_scaling(1.0, 1.0, 1.0),
- m_reaction_impulse(0.0, 0.0, 0.0),
- m_reaction_force(0.0, 0.0, 0.0),
- m_lin_mom(0.0, 0.0, 0.0),
- m_ang_mom(0.0, 0.0, 0.0),
- m_force(0.0, 0.0, 0.0),
- m_torque(0.0, 0.0, 0.0),
- m_error(0.0, 0.0, 0.0),
- m_combined_lin_vel (0.0, 0.0, 0.0),
- m_combined_ang_vel (0.0, 0.0, 0.0),
- m_fh_object(0),
- m_inv_mass(0.0),
- m_inv_inertia(0., 0., 0.),
- m_kinematic(false),
- m_prev_kinematic(false),
- m_is_rigid_body(false),
- m_static(0)
-{
- m_object = DT_CreateObject(this, shape);
- m_xform.setIdentity();
- m_xform.getValue(m_ogl_matrix);
- if (shapeProps)
- {
- if (shapeProps->m_do_fh || shapeProps->m_do_rot_fh)
- {
- DT_Vector3 zero = {0., 0., 0.}, ray = {0.0, 0.0, -10.0};
- m_fh_object = new SM_FhObject(DT_NewLineSegment(zero, ray), MT_Vector3(ray), this);
- //printf("SM_Object:: WARNING! fh disabled.\n");
- }
- m_inv_mass = 1. / shapeProps->m_mass;
- m_inv_inertia = MT_Vector3(1./shapeProps->m_inertia[0], 1./shapeProps->m_inertia[1], 1./shapeProps->m_inertia[2]);
- }
- updateInvInertiaTensor();
- m_suspended = false;
-}
-
-
- void
-SM_Object::
-integrateForces(
- MT_Scalar timeStep
-){
- if (!m_suspended) {
- m_prev_state = getNextFrame();
- m_prev_state.setLinearVelocity(actualLinVelocity());
- m_prev_state.setAngularVelocity(actualAngVelocity());
- if (isDynamic()) {
- // Integrate momentum (forward Euler)
- m_lin_mom += m_force * timeStep;
- m_ang_mom += m_torque * timeStep;
- // Drain momentum because of air/water resistance
- m_lin_mom *= pow(m_shapeProps->m_lin_drag, timeStep);
- m_ang_mom *= pow(m_shapeProps->m_ang_drag, timeStep);
- // Set velocities according momentum
- getNextFrame().setLinearVelocity(m_lin_mom * m_inv_mass);
- getNextFrame().setAngularVelocity(m_inv_inertia_tensor * m_ang_mom);
- }
- }
-
-};
-
- void
-SM_Object::
-integrateMomentum(
- MT_Scalar timeStep
-){
- // Integrate position and orientation
-
- // only do it for objects with linear and/or angular velocity
- // else clients with hierarchies may get into trouble
- if (!actualLinVelocity().fuzzyZero() || !actualAngVelocity().fuzzyZero())
- {
-
- // those MIDPOINT and BACKWARD integration methods are
- // in this form not ok with some testfiles !
- // For a release build please use forward euler unless completely tested
-
-//#define MIDPOINT
-//#define BACKWARD
-#ifdef MIDPOINT
-// Midpoint rule
- getNextFrame().integrateMidpoint(timeStep, m_prev_state, actualLinVelocity(), actualAngVelocity());
-#elif defined BACKWARD
-// Backward Euler
- getNextFrame().integrateBackward(timeStep, actualLinVelocity(), actualAngVelocity());
-#else
-// Forward Euler
- getNextFrame().integrateForward(timeStep, m_prev_state);
-#endif
-
- calcXform();
- notifyClient();
-
- }
-}
-
-/**
- * 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,
- const MT_Vector3 &rel_vel,
- MT_Scalar restitution,
- MT_Scalar friction_factor,
- MT_Scalar invMass
-)
-{
- /**
- * 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 > 0, the objects are moving apart!
- */
- if (rel_vel_normal < -MT_EPSILON) {
- /**
- * 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;
-
- if (isRigidBody())
- {
- 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 + getNextFrame().getPosition(), impulse * normal);
- } else {
- /**
- * Apply impulse through object center. (no rotation.)
- */
- impulse /= invMass;
- applyCenterImpulse( impulse * normal );
- }
-
- MT_Vector3 external = m_combined_lin_vel + m_combined_ang_vel.cross(local2);
- MT_Vector3 lateral = rel_vel - external - normal * (rel_vel_normal - external.dot(normal));
-#if 0
- // test - only do friction on the physics part of the
- // velocity.
- vel1 -= obj1->m_combined_lin_vel;
- vel2 -= obj2->m_combined_lin_vel;
-
- // This should look familiar....
- 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.
- */
- 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.
- */
-
- MT_Matrix3x3 lcs(getNextFrame().getOrientation());
-
- /**
- * 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.
- */
- const MT_Vector3& friction_scaling =
- m_shapeProps->m_friction_scaling;
-
- // Scale the local lateral...
- loc_lateral.scale(friction_scaling[0],
- friction_scaling[1],
- friction_scaling[2]);
- // ... and transform it back to global coordinates
- 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[
- 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();
-
- if (rel_vel_lateral > MT_EPSILON) {
- lateral /= rel_vel_lateral;
-
- // Compute the maximum friction impulse
- MT_Scalar max_friction =
- friction_factor * MT_max(MT_Scalar(0.0), impulse);
-
- // I guess the GEN_max is not necessary, so let's check it
-
- MT_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.
- */
-
- if (isRigidBody()) {
-
- /**
- * 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)));
-
- MT_Scalar friction = MT_min(impulse_lateral, max_friction);
- applyImpulse(local2 + getNextFrame().getPosition(), -lateral * friction);
- }
- else {
- MT_Scalar impulse_lateral = rel_vel_lateral / invMass;
-
- MT_Scalar friction = MT_min(impulse_lateral, max_friction);
- applyCenterImpulse( -friction * lateral);
- }
-
-
- }
-
- //calcXform();
- //notifyClient();
-
- }
-}
-
-static void AddCallback(SM_Scene *scene, SM_Object *obj1, SM_Object *obj2)
-{
- // If we have callbacks on either of the client objects, do a collision test
- // and add a callback if they intersect.
- DT_Vector3 v;
- if ((obj1->getClientObject() && obj1->getClientObject()->hasCollisionCallback()) ||
- (obj2->getClientObject() && obj2->getClientObject()->hasCollisionCallback()) &&
- DT_GetIntersect(obj1->getObjectHandle(), obj2->getObjectHandle(), v))
- scene->notifyCollision(obj1, obj2);
-}
-
-DT_Bool SM_Object::boing(
- void *client_data,
- void *object1,
- void *object2,
- const DT_CollData *coll_data
-){
- SM_Scene *scene = (SM_Scene *)client_data;
- SM_Object *obj1 = (SM_Object *)object1;
- SM_Object *obj2 = (SM_Object *)object2;
-
- // at this point it is unknown whether we are really intersecting (broad phase)
-
- DT_Vector3 p1, p2;
- if (!obj2->isDynamic()) {
- std::swap(obj1, obj2);
- }
-
- // If one of the objects is a ghost then ignore it for the dynamics
- if (obj1->isGhost() || obj2->isGhost()) {
- AddCallback(scene, obj1, obj2);
- return DT_CONTINUE;
- }
-
- // Objects do not collide with parent objects
- if (obj1->getDynamicParent() == obj2 || obj2->getDynamicParent() == obj1) {
- AddCallback(scene, obj1, obj2);
- return DT_CONTINUE;
- }
-
- if (!obj2->isDynamic()) {
- AddCallback(scene, obj1, obj2);
- return DT_CONTINUE;
- }
-
- // Get collision data from SOLID
- if (!DT_GetPenDepth(obj1->getObjectHandle(), obj2->getObjectHandle(), p1, p2))
- return DT_CONTINUE;
-
- MT_Point3 local1(p1), local2(p2);
- MT_Vector3 normal(local2 - local1);
- MT_Scalar dist = normal.length();
-
- if (dist < MT_EPSILON)
- return DT_CONTINUE;
-
- // Now we are definitely intersecting.
-
- // Set callbacks for game engine.
- if ((obj1->getClientObject() && obj1->getClientObject()->hasCollisionCallback()) ||
- (obj2->getClientObject() && obj2->getClientObject()->hasCollisionCallback()))
- scene->notifyCollision(obj1, obj2);
-
- local1 -= obj1->getNextFrame().getPosition();
- local2 -= obj2->getNextFrame().getPosition();
-
- // Calculate collision parameters
- MT_Vector3 rel_vel = obj1->getVelocity(local1) - obj2->getVelocity(local2);
-
- MT_Scalar restitution =
- MT_min(obj1->getMaterialProps()->m_restitution,
- obj2->getMaterialProps()->m_restitution);
-
- MT_Scalar friction_factor =
- MT_min(obj1->getMaterialProps()->m_friction,
- obj2->getMaterialProps()->m_friction);
-
- MT_Scalar invMass = obj1->getInvMass() + obj2->getInvMass();
-
- normal /= dist;
-
- // Calculate reactions
- if (obj1->isDynamic())
- obj1->dynamicCollision(local1, normal, dist, rel_vel, restitution, friction_factor, invMass);
-
- if (obj2->isDynamic())
- {
- obj2->dynamicCollision(local2, -normal, dist, -rel_vel, restitution, friction_factor, invMass);
- if (!obj1->isDynamic() || obj1->m_static)
- obj2->m_static = obj1->m_static + 1;
- }
-
- return DT_CONTINUE;
-}
-
-DT_Bool SM_Object::fix(
- void *client_data,
- void *object1,
- void *object2,
- const DT_CollData *coll_data
-){
- SM_Object *obj1 = (SM_Object *)object1;
- SM_Object *obj2 = (SM_Object *)object2;
-
- // If one of the objects is a ghost then ignore it for the dynamics
- if (obj1->isGhost() || obj2->isGhost()) {
- return DT_CONTINUE;
- }
-
- if (obj1->getDynamicParent() == obj2 || obj2->getDynamicParent() == obj1) {
- return DT_CONTINUE;
- }
-
- if (!obj2->isDynamic()) {
- std::swap(obj1, obj2);
- }
-
- if (!obj2->isDynamic()) {
- return DT_CONTINUE;
- }
-
- // obj1 points to a dynamic object
- DT_Vector3 p1, p2;
- if (!DT_GetPenDepth(obj1->getObjectHandle(), obj2->getObjectHandle(), p1, p2))
- return DT_CONTINUE;
- MT_Point3 local1(p1), local2(p2);
- // Get collision data from SOLID
- MT_Vector3 normal(local2 - local1);
-
- MT_Scalar dist = normal.dot(normal);
- if (dist < MT_EPSILON || dist > obj2->m_shapeProps->m_radius*obj2->m_shapeProps->m_radius)
- return DT_CONTINUE;
-
-
- if ((obj1->m_static || !obj1->isDynamic()) && obj1->m_static < obj2->m_static)
- {
- obj2->m_static = obj1->m_static + 1;
- } else if (obj2->m_static && obj2->m_static < obj1->m_static)
- {
- obj1->m_static = obj2->m_static + 1;
- }
-
- contacts.insert(new Contact(obj1, obj2, normal, MT_Point3(local1 + 0.5*(local2 - local1))));
-
-
- return DT_CONTINUE;
-}
-
-void SM_Object::relax(void)
-{
- for (Contact::Set::iterator csit = contacts.begin() ; csit != contacts.end(); ++csit)
- {
- (*csit)->resolve();
- delete (*csit);
- }
-
- contacts.clear();
- if (m_error.fuzzyZero())
- return;
- //std::cout << "SM_Object::relax: { " << m_error << " }" << std::endl;
-
- getNextFrame().setPosition(getNextFrame().getPosition() + m_error);
- m_error.setValue(0., 0., 0.);
- //calcXform();
- //notifyClient();
-}
-
-SM_Object::SM_Object() :
- m_dynamicParent(0),
- m_client_object(0),
- m_physicsClientObject(0),
- m_shape(0),
- m_materialProps(0),
- m_materialPropsBackup(0),
- m_shapeProps(0),
- m_shapePropsBackup(0),
- m_object(0),
- m_margin(0.0),
- m_scaling(1.0, 1.0, 1.0),
- m_reaction_impulse(0.0, 0.0, 0.0),
- m_reaction_force(0.0, 0.0, 0.0),
- m_lin_mom(0.0, 0.0, 0.0),
- m_ang_mom(0.0, 0.0, 0.0),
- m_force(0.0, 0.0, 0.0),
- m_torque(0.0, 0.0, 0.0),
- m_error(0.0, 0.0, 0.0),
- m_combined_lin_vel (0.0, 0.0, 0.0),
- m_combined_ang_vel (0.0, 0.0, 0.0),
- m_fh_object(0),
- m_kinematic(false),
- m_prev_kinematic(false),
- m_is_rigid_body(false)
-{
- // warning no initialization of variables done by moto.
-}
-
-SM_Object::
-~SM_Object() {
- if (m_fh_object)
- delete m_fh_object;
-
- DT_DestroyObject(m_object);
- m_object = NULL;
-}
-
- bool
-SM_Object::
-isDynamic(
-) const {
- return m_shapeProps != 0;
-}
-
-/* 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
-SM_Object::
-suspend(
-){
- if (!m_suspended) {
- m_suspended = true;
- suspendDynamics();
- }
-}
-
- void
-SM_Object::
-resume(
-) {
- if (m_suspended) {
- m_suspended = false;
- restoreDynamics();
- }
-}
-
- void
-SM_Object::
-suspendDynamics(
-) {
- if (m_shapeProps) {
- m_shapePropsBackup = m_shapeProps;
- m_shapeProps = 0;
- }
-}
-
- void
-SM_Object::
-restoreDynamics(
-) {
- if (m_shapePropsBackup) {
- m_shapeProps = m_shapePropsBackup;
- m_shapePropsBackup = 0;
- }
-}
-
- bool
-SM_Object::
-isGhost(
-) const {
- return m_materialProps == 0;
-}
-
- void
-SM_Object::
-suspendMaterial(
-) {
- if (m_materialProps) {
- m_materialPropsBackup = m_materialProps;
- m_materialProps = 0;
- }
-}
-
- void
-SM_Object::
-restoreMaterial(
-) {
- if (m_materialPropsBackup) {
- m_materialProps = m_materialPropsBackup;
- m_materialPropsBackup = 0;
- }
-}
-
- SM_FhObject *
-SM_Object::
-getFhObject(
-) const {
- return m_fh_object;
-}
-
- void
-SM_Object::
-registerCallback(
- SM_Callback& callback
-) {
- m_callbackList.push_back(&callback);
-}
-
-// Set the local coordinate system according to the current state
- void
-SM_Object::
-calcXform() {
-#ifdef SM_DEBUG_XFORM
- printf("SM_Object::calcXform m_pos = { %-0.5f, %-0.5f, %-0.5f }\n",
- m_pos[0], m_pos[1], m_pos[2]);
- printf(" m_orn = { %-0.5f, %-0.5f, %-0.5f, %-0.5f }\n",
- m_orn[0], m_orn[1], m_orn[2], m_orn[3]);
- printf(" m_scaling = { %-0.5f, %-0.5f, %-0.5f }\n",
- m_scaling[0], m_scaling[1], m_scaling[2]);
-#endif
- m_xform.setOrigin(getNextFrame().getPosition());
- m_xform.setBasis(MT_Matrix3x3(getNextFrame().getOrientation(), m_scaling));
- m_xform.getValue(m_ogl_matrix);
-
- /* Blender has been known to crash here.
- This usually means SM_Object *this has been deleted more than once. */
- DT_SetMatrixd(m_object, m_ogl_matrix);
- if (m_fh_object) {
- m_fh_object->setPosition(getNextFrame().getPosition());
- m_fh_object->calcXform();
- }
- updateInvInertiaTensor();
-#ifdef SM_DEBUG_XFORM
- printf("\n | %-0.5f %-0.5f %-0.5f %-0.5f |\n",
- m_ogl_matrix[0], m_ogl_matrix[4], m_ogl_matrix[ 8], m_ogl_matrix[12]);
- printf( " | %-0.5f %-0.5f %-0.5f %-0.5f |\n",
- m_ogl_matrix[1], m_ogl_matrix[5], m_ogl_matrix[ 9], m_ogl_matrix[13]);
- printf( "m_ogl_matrix = | %-0.5f %-0.5f %-0.5f %-0.5f |\n",
- m_ogl_matrix[2], m_ogl_matrix[6], m_ogl_matrix[10], m_ogl_matrix[14]);
- printf( " | %-0.5f %-0.5f %-0.5f %-0.5f |\n\n",
- m_ogl_matrix[3], m_ogl_matrix[7], m_ogl_matrix[11], m_ogl_matrix[15]);
-#endif
-}
-
- void
-SM_Object::updateInvInertiaTensor()
-{
- m_inv_inertia_tensor = m_xform.getBasis().scaled(m_inv_inertia[0], m_inv_inertia[1], m_inv_inertia[2]) * m_xform.getBasis().transposed();
-}
-
-// Call callbacks to notify the client of a change of placement
- void
-SM_Object::
-notifyClient() {
- T_CallbackList::iterator i;
- for (i = m_callbackList.begin(); i != m_callbackList.end(); ++i) {
- (*i)->do_me();
- }
-}
-
-
-// Save the current state information for use in the velocity computation in the next frame.
- void
-SM_Object::
-proceedKinematic(
- MT_Scalar timeStep
-) {
- /* nzc: need to bunge this for the logic bubbling as well? */
- if (!m_suspended) {
- m_prev_kinematic = m_kinematic;
- if (m_kinematic) {
- m_prev_xform = m_xform;
- m_timeStep = timeStep;
- calcXform();
- m_kinematic = false;
- }
- }
-}
-
- void
-SM_Object::
-saveReactionForce(
- MT_Scalar timeStep
-) {
- if (isDynamic()) {
- m_reaction_force = m_reaction_impulse / timeStep;
- m_reaction_impulse.setValue(0.0, 0.0, 0.0);
- }
-}
-
- void
-SM_Object::
-clearForce(
-) {
- m_force.setValue(0.0, 0.0, 0.0);
- m_torque.setValue(0.0, 0.0, 0.0);
-}
-
- void
-SM_Object::
-clearMomentum(
-) {
- m_lin_mom.setValue(0.0, 0.0, 0.0);
- m_ang_mom.setValue(0.0, 0.0, 0.0);
-}
-
- void
-SM_Object::
-setMargin(
- MT_Scalar margin
-) {
- m_margin = margin;
- DT_SetMargin(m_object, margin);
-}
-
- MT_Scalar
-SM_Object::
-getMargin(
-) const {
- return m_margin;
-}
-
-const
- SM_MaterialProps *
-SM_Object::
-getMaterialProps(
-) const {
- return m_materialProps;
-}
-
-const
- SM_ShapeProps *
-SM_Object::
-getShapeProps(
-) const {
- return m_shapeProps;
-}
-
- void
-SM_Object::
-setPosition(
- const MT_Point3& pos
-){
- m_kinematic = true;
- getNextFrame().setPosition(pos);
- endFrame();
-}
-
- void
-SM_Object::
-setOrientation(
- const MT_Quaternion& orn
-){
- MT_assert(!orn.fuzzyZero());
- m_kinematic = true;
- getNextFrame().setOrientation(orn);
- endFrame();
-}
-
- void
-SM_Object::
-setScaling(
- const MT_Vector3& scaling
-){
- m_kinematic = true;
- m_scaling = scaling;
-}
-
-/**
- * Functions to handle linear velocity
- */
-
- void
-SM_Object::
-setExternalLinearVelocity(
- const MT_Vector3& lin_vel
-) {
- m_combined_lin_vel=lin_vel;
-}
-
- void
-SM_Object::
-addExternalLinearVelocity(
- const MT_Vector3& lin_vel
-) {
- m_combined_lin_vel+=lin_vel;
-}
-
- void
-SM_Object::
-addLinearVelocity(
- const MT_Vector3& lin_vel
-){
- setLinearVelocity(getNextFrame().getLinearVelocity() + lin_vel);
-}
-
- void
-SM_Object::
-setLinearVelocity(
- const MT_Vector3& lin_vel
-){
- getNextFrame().setLinearVelocity(lin_vel);
- if (m_shapeProps) {
- m_lin_mom = getNextFrame().getLinearVelocity() * m_shapeProps->m_mass;
- }
-}
-
-/**
- * Functions to handle angular velocity
- */
-
- void
-SM_Object::
-setExternalAngularVelocity(
- const MT_Vector3& ang_vel
-) {
- m_combined_ang_vel = ang_vel;
-}
-
- void
-SM_Object::
-addExternalAngularVelocity(
- const MT_Vector3& ang_vel
-) {
- m_combined_ang_vel += ang_vel;
-}
-
- void
-SM_Object::
-setAngularVelocity(
- const MT_Vector3& ang_vel
-) {
- getNextFrame().setAngularVelocity(ang_vel);
- if (m_shapeProps) {
- m_ang_mom = getNextFrame().getAngularVelocity() * m_shapeProps->m_inertia;
- }
-}
-
- void
-SM_Object::
-addAngularVelocity(
- const MT_Vector3& ang_vel
-) {
- setAngularVelocity(getNextFrame().getAngularVelocity() + ang_vel);
-}
-
-
- void
-SM_Object::
-clearCombinedVelocities(
-) {
- m_combined_lin_vel = MT_Vector3(0,0,0);
- m_combined_ang_vel = MT_Vector3(0,0,0);
-}
-
- void
-SM_Object::
-resolveCombinedVelocities(
- const MT_Vector3 & lin_vel,
- const MT_Vector3 & ang_vel
-) {
-
- // Different behaviours for dynamic and non-dynamic
- // objects. For non-dynamic we just set the velocity to
- // zero. For dynmic the physics velocity has to be
- // taken into account. We must make an arbitrary decision
- // on how to resolve the 2 velocities. Choices are
- // Add the physics velocity to the linear velocity. Objects
- // will just keep on moving in the direction they were
- // last set in - untill external forces affect them.
- // Set the combinbed linear and physics velocity to zero.
- // Set the physics velocity in the direction of the set velocity
- // zero.
- if (isDynamic()) {
-
-#if 1
- getNextFrame().setLinearVelocity(getNextFrame().getLinearVelocity() + lin_vel);
- getNextFrame().setAngularVelocity(getNextFrame().getAngularVelocity() + ang_vel);
-#else
-
- //compute the component of the physics velocity in the
- // direction of the set velocity and set it to zero.
- MT_Vector3 lin_vel_norm = lin_vel.normalized();
-
- setLinearVelocity(getNextFrame().getLinearVelocity() - (getNextFrame().getLinearVelocity().dot(lin_vel_norm) * lin_vel_norm));
-#endif
- m_lin_mom = getNextFrame().getLinearVelocity() * m_shapeProps->m_mass;
- m_ang_mom = getNextFrame().getAngularVelocity() * m_shapeProps->m_inertia;
- clearCombinedVelocities();
-
- }
-
-}
-
-
- MT_Scalar
-SM_Object::
-getInvMass(
-) const {
- return m_inv_mass;
- // OPT: cache the result of this division rather than compute it each call
-}
-
- const MT_Vector3&
-SM_Object::
-getInvInertia(
-) const {
- return m_inv_inertia;
- // OPT: cache the result of this division rather than compute it each call
-}
-
- const MT_Matrix3x3&
-SM_Object::
-getInvInertiaTensor(
-) const {
- return m_inv_inertia_tensor;
-}
-
- void
-SM_Object::
-applyForceField(
- const MT_Vector3& accel
-) {
- if (m_shapeProps) {
- m_force += m_shapeProps->m_mass * accel; // F = m * a
- }
-}
-
- void
-SM_Object::
-applyCenterForce(
- const MT_Vector3& force
-) {
- m_force += force;
-}
-
- void
-SM_Object::
-applyTorque(
- const MT_Vector3& torque
-) {
- m_torque += torque;
-}
-
- void
-SM_Object::
-applyImpulse(
- const MT_Point3& attach, const MT_Vector3& impulse
-) {
- applyCenterImpulse(impulse); // Change in linear momentum
- applyAngularImpulse((attach - getNextFrame().getPosition()).cross(impulse)); // Change in angular momentump
-}
-
- void
-SM_Object::
-applyCenterImpulse(
- const MT_Vector3& impulse
-) {
- if (m_shapeProps) {
- m_lin_mom += impulse;
- m_reaction_impulse += impulse;
- getNextFrame().setLinearVelocity(m_lin_mom * m_inv_mass);
-
- // The linear velocity is immedialtely updated since otherwise
- // simultaneous collisions will get a double impulse.
- }
-}
-
- void
-SM_Object::
-applyAngularImpulse(
- const MT_Vector3& impulse
-) {
- if (m_shapeProps) {
- m_ang_mom += impulse;
- getNextFrame().setAngularVelocity( m_inv_inertia_tensor * m_ang_mom);
- }
-}
-
- MT_Point3
-SM_Object::
-getWorldCoord(
- const MT_Point3& local
-) const {
- return m_xform(local);
-}
-
- MT_Vector3
-SM_Object::
-getVelocity(
- const MT_Point3& local
-) const {
- if (m_prev_kinematic && !isDynamic())
- {
- // For displaced objects the velocity is faked using the previous state.
- // Dynamic objects get their own velocity, not the faked velocity.
- // (Dynamic objects shouldn't be displaced in the first place!!)
- return (m_xform(local) - m_prev_xform(local)) / m_timeStep;
- }
-
- // NB: m_xform.getBasis() * local == m_xform(local) - m_xform.getOrigin()
- return actualLinVelocity() + actualAngVelocity().cross(local);
-}
-
-
-const
- MT_Vector3&
-SM_Object::
-getReactionForce(
-) const {
- return m_reaction_force;
-}
-
- void
-SM_Object::
-getMatrix(
- double *m
-) const {
- std::copy(&m_ogl_matrix[0], &m_ogl_matrix[16], &m[0]);
-}
-
-const
- double *
-SM_Object::
-getMatrix(
-) const {
- return m_ogl_matrix;
-}
-
-// Still need this???
-const
- MT_Transform&
-SM_Object::
-getScaledTransform(
-) const {
- return m_xform;
-}
-
- DT_ObjectHandle
-SM_Object::
-getObjectHandle(
-) const {
- return m_object;
-}
-
- DT_ShapeHandle
-SM_Object::
-getShapeHandle(
-) const {
- return m_shape;
-}
-
- SM_Object *
-SM_Object::
-getDynamicParent(
-) {
- return m_dynamicParent;
-}
-
- void
-SM_Object::
-setRigidBody(
- bool is_rigid_body
-) {
- m_is_rigid_body = is_rigid_body;
-}
-
- bool
-SM_Object::
-isRigidBody(
-) const {
- return m_is_rigid_body;
-}
-
-const
- MT_Vector3
-SM_Object::
-actualLinVelocity(
-) const {
- return m_combined_lin_vel + getNextFrame().getLinearVelocity();
-};
-
-const
- MT_Vector3
-SM_Object::
-actualAngVelocity(
-) const {
- return m_combined_ang_vel + getNextFrame().getAngularVelocity();
-}
-
-
-SM_MotionState&
-SM_Object::
-getCurrentFrame()
-{
- return m_frames[1];
-}
-
-SM_MotionState&
-SM_Object::
-getPreviousFrame()
-{
- return m_frames[0];
-}
-
-SM_MotionState &
-SM_Object::
-getNextFrame()
-{
- return m_frames[2];
-}
-
-const SM_MotionState &
-SM_Object::
-getCurrentFrame() const
-{
- return m_frames[1];
-}
-
-const SM_MotionState &
-SM_Object::
-getPreviousFrame() const
-{
- return m_frames[0];
-}
-
-const SM_MotionState &
-SM_Object::
-getNextFrame() const
-{
- return m_frames[2];
-}
-
-
-const MT_Point3&
-SM_Object::
-getPosition() const
-{
- return m_frames[1].getPosition();
-}
-
-const MT_Quaternion&
-SM_Object::
-getOrientation() const
-{
- return m_frames[1].getOrientation();
-}
-
-const MT_Vector3&
-SM_Object::
-getLinearVelocity() const
-{
- return m_frames[1].getLinearVelocity();
-}
-
-const MT_Vector3&
-SM_Object::
-getAngularVelocity() const
-{
- return m_frames[1].getAngularVelocity();
-}
-
-void
-SM_Object::
-interpolate(MT_Scalar timeStep)
-{
- if (!actualLinVelocity().fuzzyZero() || !actualAngVelocity().fuzzyZero())
- {
- getCurrentFrame().setTime(timeStep);
- getCurrentFrame().lerp(getPreviousFrame(), getNextFrame());
- notifyClient();
- }
-}
-
-void
-SM_Object::
-endFrame()
-{
- getPreviousFrame() = getNextFrame();
- getCurrentFrame() = getNextFrame();
- m_static = 0;
-}
diff --git a/source/gameengine/Physics/Sumo/Fuzzics/src/SM_Scene.cpp b/source/gameengine/Physics/Sumo/Fuzzics/src/SM_Scene.cpp
deleted file mode 100644
index f0791bbf89f..00000000000
--- a/source/gameengine/Physics/Sumo/Fuzzics/src/SM_Scene.cpp
+++ /dev/null
@@ -1,378 +0,0 @@
-/**
- * $Id$
- * Copyright (C) 2001 NaN Technologies B.V.
- * The physics scene.
- *
- * ***** BEGIN GPL 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.
- *
- * 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 LICENSE BLOCK *****
- */
-
-#ifdef HAVE_CONFIG_H
-#include <config.h>
-#endif
-
-#ifdef WIN32
-#pragma warning(disable : 4786) // shut off 255 char limit debug template warning
-#endif
-
-#include "SM_Scene.h"
-#include "SM_Object.h"
-#include "SM_FhObject.h"
-
-#include "SM_Debug.h"
-
-#include <algorithm>
-
-SM_Scene::SM_Scene() :
- m_scene(DT_CreateScene()),
- m_respTable(DT_CreateRespTable()),
- m_secondaryRespTable(DT_CreateRespTable()),
- m_fixRespTable(DT_CreateRespTable()),
- m_forceField(0.0, 0.0, 0.0),
- m_frames(0)
-{
- for (int i = 0 ; i < NUM_RESPONSE; i++)
- {
- m_ResponseClass[i] = DT_GenResponseClass(m_respTable);
- m_secondaryResponseClass[i] = DT_GenResponseClass(m_secondaryRespTable);
- m_fixResponseClass[i] = DT_GenResponseClass(m_fixRespTable);
- }
-
- /* Sensor */
- DT_AddPairResponse(m_respTable, m_ResponseClass[SENSOR_RESPONSE], m_ResponseClass[SENSOR_RESPONSE], 0, DT_NO_RESPONSE, this);
- DT_AddPairResponse(m_respTable, m_ResponseClass[SENSOR_RESPONSE], m_ResponseClass[STATIC_RESPONSE], SM_Scene::boing, DT_SIMPLE_RESPONSE, this);
- DT_AddPairResponse(m_respTable, m_ResponseClass[SENSOR_RESPONSE], m_ResponseClass[OBJECT_RESPONSE], SM_Scene::boing, DT_SIMPLE_RESPONSE, this);
- DT_AddPairResponse(m_respTable, m_ResponseClass[SENSOR_RESPONSE], m_ResponseClass[FH_RESPONSE], 0, DT_NO_RESPONSE, this);
-
- /* Static */
- DT_AddPairResponse(m_respTable, m_ResponseClass[STATIC_RESPONSE], m_ResponseClass[SENSOR_RESPONSE], SM_Scene::boing, DT_SIMPLE_RESPONSE, this);
- DT_AddPairResponse(m_respTable, m_ResponseClass[STATIC_RESPONSE], m_ResponseClass[STATIC_RESPONSE], 0, DT_NO_RESPONSE, this);
- DT_AddPairResponse(m_respTable, m_ResponseClass[STATIC_RESPONSE], m_ResponseClass[OBJECT_RESPONSE], SM_Object::boing, DT_BROAD_RESPONSE, this);
- DT_AddPairResponse(m_respTable, m_ResponseClass[STATIC_RESPONSE], m_ResponseClass[FH_RESPONSE], SM_FhObject::ray_hit, DT_SIMPLE_RESPONSE, this);
-
- /* Object */
- DT_AddPairResponse(m_respTable, m_ResponseClass[OBJECT_RESPONSE], m_ResponseClass[SENSOR_RESPONSE], SM_Scene::boing, DT_SIMPLE_RESPONSE, this);
- DT_AddPairResponse(m_respTable, m_ResponseClass[OBJECT_RESPONSE], m_ResponseClass[STATIC_RESPONSE], SM_Object::boing, DT_BROAD_RESPONSE, this);
- DT_AddPairResponse(m_respTable, m_ResponseClass[OBJECT_RESPONSE], m_ResponseClass[OBJECT_RESPONSE], SM_Object::boing, DT_BROAD_RESPONSE, this);
- DT_AddPairResponse(m_respTable, m_ResponseClass[OBJECT_RESPONSE], m_ResponseClass[FH_RESPONSE], SM_FhObject::ray_hit, DT_SIMPLE_RESPONSE, this);
-
- /* Fh Object */
- DT_AddPairResponse(m_respTable, m_ResponseClass[FH_RESPONSE], m_ResponseClass[SENSOR_RESPONSE], 0, DT_NO_RESPONSE, this);
- DT_AddPairResponse(m_respTable, m_ResponseClass[FH_RESPONSE], m_ResponseClass[STATIC_RESPONSE], SM_FhObject::ray_hit, DT_SIMPLE_RESPONSE, this);
- DT_AddPairResponse(m_respTable, m_ResponseClass[FH_RESPONSE], m_ResponseClass[OBJECT_RESPONSE], SM_FhObject::ray_hit, DT_SIMPLE_RESPONSE, this);
- DT_AddPairResponse(m_respTable, m_ResponseClass[FH_RESPONSE], m_ResponseClass[FH_RESPONSE], 0, DT_NO_RESPONSE, this);
-
- /* Object (Fix Pass) */
- DT_AddPairResponse(m_fixRespTable, m_ResponseClass[OBJECT_RESPONSE], m_ResponseClass[SENSOR_RESPONSE], 0, DT_NO_RESPONSE, this);
- DT_AddPairResponse(m_fixRespTable, m_ResponseClass[OBJECT_RESPONSE], m_ResponseClass[STATIC_RESPONSE], SM_Object::fix, DT_BROAD_RESPONSE, this);
- DT_AddPairResponse(m_fixRespTable, m_ResponseClass[OBJECT_RESPONSE], m_ResponseClass[OBJECT_RESPONSE], SM_Object::fix, DT_BROAD_RESPONSE, this);
- DT_AddPairResponse(m_fixRespTable, m_ResponseClass[OBJECT_RESPONSE], m_ResponseClass[FH_RESPONSE], 0, DT_NO_RESPONSE, this);
-}
-
-void SM_Scene::addTouchCallback(int response_class, DT_ResponseCallback callback, void *user)
-{
- DT_AddClassResponse(m_secondaryRespTable, m_secondaryResponseClass[response_class], callback, DT_BROAD_RESPONSE, user);
-}
-
-void SM_Scene::addSensor(SM_Object& object)
-{
- T_ObjectList::iterator i =
- std::find(m_objectList.begin(), m_objectList.end(), &object);
- if (i == m_objectList.end())
- {
- object.calcXform();
- m_objectList.push_back(&object);
- DT_AddObject(m_scene, object.getObjectHandle());
- DT_SetResponseClass(m_respTable, object.getObjectHandle(), m_ResponseClass[SENSOR_RESPONSE]);
- DT_SetResponseClass(m_secondaryRespTable, object.getObjectHandle(), m_secondaryResponseClass [SENSOR_RESPONSE]);
- DT_SetResponseClass(m_fixRespTable, object.getObjectHandle(), m_fixResponseClass[SENSOR_RESPONSE]);
- }
-}
-
-void SM_Scene::add(SM_Object& object) {
- object.calcXform();
- m_objectList.push_back(&object);
- DT_AddObject(m_scene, object.getObjectHandle());
- if (object.isDynamic()) {
- DT_SetResponseClass(m_respTable, object.getObjectHandle(), m_ResponseClass[OBJECT_RESPONSE]);
- DT_SetResponseClass(m_secondaryRespTable, object.getObjectHandle(), m_secondaryResponseClass[OBJECT_RESPONSE]);
- DT_SetResponseClass(m_fixRespTable, object.getObjectHandle(), m_fixResponseClass[OBJECT_RESPONSE]);
- } else {
- DT_SetResponseClass(m_respTable, object.getObjectHandle(), m_ResponseClass[STATIC_RESPONSE]);
- DT_SetResponseClass(m_secondaryRespTable, object.getObjectHandle(), m_secondaryResponseClass[STATIC_RESPONSE]);
- DT_SetResponseClass(m_fixRespTable, object.getObjectHandle(), m_fixResponseClass[STATIC_RESPONSE]);
- }
-
- SM_FhObject *fh_object = object.getFhObject();
-
- if (fh_object) {
- DT_AddObject(m_scene, fh_object->getObjectHandle());
- DT_SetResponseClass(m_respTable, fh_object->getObjectHandle(), m_ResponseClass[FH_RESPONSE]);
- DT_SetResponseClass(m_secondaryRespTable, fh_object->getObjectHandle(), m_secondaryResponseClass[FH_RESPONSE]);
- DT_SetResponseClass(m_fixRespTable, fh_object->getObjectHandle(), m_fixResponseClass[FH_RESPONSE]);
- }
-}
-
-void SM_Scene::requestCollisionCallback(SM_Object &object)
-{
- DT_SetResponseClass(m_respTable, object.getObjectHandle(), m_ResponseClass[OBJECT_RESPONSE]);
- DT_SetResponseClass(m_secondaryRespTable, object.getObjectHandle(), m_secondaryResponseClass[OBJECT_RESPONSE]);
-// DT_SetResponseClass(m_fixRespTable, object.getObjectHandle(), m_fixResponseClass[OBJECT_RESPONSE]);
-}
-
-void SM_Scene::remove(SM_Object& object) {
- //std::cout << "SM_Scene::remove this =" << this << "object = " << &object << std::endl;
- T_ObjectList::iterator i =
- std::find(m_objectList.begin(), m_objectList.end(), &object);
- if (!(i == m_objectList.end()))
- {
- std::swap(*i, m_objectList.back());
- m_objectList.pop_back();
- DT_RemoveObject(m_scene, object.getObjectHandle());
-
- SM_FhObject *fh_object = object.getFhObject();
-
- if (fh_object) {
- DT_RemoveObject(m_scene, fh_object->getObjectHandle());
- }
- }
- else {
- // tried to remove an object that is not in the scene
- //assert(false);
- }
-}
-
-void SM_Scene::beginFrame()
-{
- T_ObjectList::iterator i;
- // Apply a forcefield (such as gravity)
- for (i = m_objectList.begin(); i != m_objectList.end(); ++i)
- (*i)->applyForceField(m_forceField);
-
-}
-
-void SM_Scene::endFrame()
-{
- T_ObjectList::iterator i;
- for (i = m_objectList.begin(); i != m_objectList.end(); ++i)
- (*i)->clearForce();
-}
-
-bool SM_Scene::proceed(MT_Scalar curtime, MT_Scalar ticrate)
-{
- if (!m_frames)
- {
- if (ticrate > 0.)
- m_frames = (unsigned int)(curtime*ticrate) + 1.0;
- else
- m_frames = (unsigned int)(curtime*65536.0);
- }
-
- // Divide the timeStep into a number of subsamples of size roughly
- // equal to subS (might be a little smaller).
- MT_Scalar subStep;
- int num_samples;
- int frames = m_frames;
-
- // Compute the number of steps to do this update.
- if (ticrate > 0.0)
- {
- // Fixed time step
- subStep = 1.0/ticrate;
- num_samples = (unsigned int)(curtime*ticrate + 1.0) - m_frames;
-
- if (num_samples > 4)
- {
- std::cout << "Dropping physics frames! frames:" << num_samples << " substep: " << subStep << std::endl;
- MT_Scalar tr = ticrate;
- do
- {
- frames = frames / 2;
- tr = tr / 2.0;
- num_samples = (unsigned int)(curtime*tr + 1.0) - frames;
- subStep *= 2.0;
- } while (num_samples > 8);
- std::cout << " frames:" << num_samples << " substep: " << subStep << std::endl;
- }
- }
- else
- {
- // Variable time step. (old update)
- // Integrate at least 100 Hz
- MT_Scalar timeStep = curtime - m_frames/65536.0;
- subStep = timeStep > 0.01 ? 0.01 : timeStep;
- num_samples = int(timeStep * 0.01);
- if (num_samples < 1)
- num_samples = 1;
- }
-
- // Do a physics timestep.
- T_ObjectList::iterator i;
- if (num_samples > 0)
- {
- // Do the integration steps per object.
- for (int step = 0; step != num_samples; ++step)
- {
- MT_Scalar time;
- if (ticrate > 0.)
- time = MT_Scalar(frames + step + 1) * subStep;
- else
- time = MT_Scalar(m_frames)/65536.0 + MT_Scalar(step + 1)*subStep;
-
- for (i = m_objectList.begin(); i != m_objectList.end(); ++i) {
- (*i)->endFrame();
- // Apply a forcefield (such as gravity)
- (*i)->integrateForces(subStep);
- // And second we update the object positions by performing
- // an integration step for each object
- (*i)->integrateMomentum(subStep);
- }
-
- // So now first we let the physics scene respond to
- // new forces, velocities set externally.
- // The collsion and friction impulses are computed here.
- // Collision phase
- DT_Test(m_scene, m_respTable);
-
- // Contact phase
- DT_Test(m_scene, m_fixRespTable);
-
- // Finish this timestep by saving al state information for the next
- // timestep and clearing the accumulated forces.
- for (i = m_objectList.begin(); i != m_objectList.end(); ++i) {
- (*i)->relax();
- (*i)->proceedKinematic(subStep);
- (*i)->saveReactionForce(subStep);
- (*i)->getNextFrame().setTime(time);
- //(*i)->clearForce();
- }
- }
- }
-
- if (ticrate > 0)
- {
- // Interpolate between time steps.
- for (i = m_objectList.begin(); i != m_objectList.end(); ++i)
- (*i)->interpolate(curtime);
-
- //only update the m_frames after an actual physics timestep
- if (num_samples)
- {
- m_frames = (unsigned int)(curtime*ticrate) + 1.0;
- }
- }
- else
- {
- m_frames = (unsigned int)(curtime*65536.0);
- }
-
- return num_samples != 0;
-}
-
-void SM_Scene::notifyCollision(SM_Object *obj1, SM_Object *obj2)
-{
- // For each pair of object that collided, call the corresponding callback.
- if (m_secondaryRespTable)
- DT_CallResponse(m_secondaryRespTable, obj1->getObjectHandle(), obj2->getObjectHandle(), 0);
-}
-
-
-SM_Object *SM_Scene::rayTest(void *ignore_client,
- const MT_Point3& from, const MT_Point3& to,
- MT_Point3& result, MT_Vector3& normal) const {
-#ifdef SM_DEBUG_RAYCAST
- std::cout << "ray: { " << from << " } - { " << to << " }" << std::endl;
-#endif
-
- DT_Vector3 n, dfrom, dto;
- DT_Scalar param;
- from.getValue(dfrom);
- to.getValue(dto);
- SM_Object *hit_object = (SM_Object *)
- DT_RayCast(m_scene, ignore_client, dfrom, dto, 1., &param, n);
-
- if (hit_object) {
- //result = hit_object->getWorldCoord(from + (to - from)*param);
- result = from + (to - from) * param;
- normal.setValue(n);
-#ifdef SM_DEBUG_RAYCAST
- std::cout << "ray: { " << from << " } -> { " << to << " }: { " << result
- << " } (" << param << "), normal = { " << normal << " }" << std::endl;
-#endif
- }
-
- return hit_object;
-}
-
-void SM_Scene::clearObjectCombinedVelocities() {
-
- T_ObjectList::iterator i;
-
- for (i = m_objectList.begin(); i != m_objectList.end(); ++i) {
-
- (*i)->clearCombinedVelocities();
-
- }
-
-}
-
-
-void SM_Scene::setSecondaryRespTable(DT_RespTableHandle secondaryRespTable) {
- m_secondaryRespTable = secondaryRespTable;
-}
-
-
-DT_Bool SM_Scene::boing(
- void *client_data,
- void *object1,
- void *object2,
- const DT_CollData *
-){
- SM_Scene *scene = (SM_Scene *)client_data;
- SM_Object *obj1 = (SM_Object *)object1;
- SM_Object *obj2 = (SM_Object *)object2;
-
- scene->notifyCollision(obj1, obj2); // Record this collision for client callbacks
-
-#ifdef SM_DEBUG_BOING
- printf("SM_Scene::boing\n");
-#endif
-
- return DT_CONTINUE;
-}
-
-SM_Scene::~SM_Scene()
-{
- //std::cout << "SM_Scene::~ SM_Scene(): destroy " << this << std::endl;
-// if (m_objectList.begin() != m_objectList.end())
-// std::cout << "SM_Scene::~SM_Scene: There are still objects in the Sumo scene!" << std::endl;
- for (T_ObjectList::iterator it = m_objectList.begin() ; it != m_objectList.end() ; it++)
- delete *it;
-
- DT_DestroyRespTable(m_respTable);
- DT_DestroyRespTable(m_secondaryRespTable);
- DT_DestroyRespTable(m_fixRespTable);
- DT_DestroyScene(m_scene);
-}