diff --git a/sources/reactphysics3d/body/BodyState.cpp b/sources/reactphysics3d/body/BodyState.cpp
deleted file mode 100644
index cc5713da..00000000
--- a/sources/reactphysics3d/body/BodyState.cpp
+++ /dev/null
@@ -1,93 +0,0 @@
-/****************************************************************************
- * Copyright (C) 2009 Daniel Chappuis *
- ****************************************************************************
- * This file is part of ReactPhysics3D. *
- * *
- * ReactPhysics3D 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 3 of the License, or *
- * (at your option) any later version. *
- * *
- * ReactPhysics3D 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 ReactPhysics3D. If not, see . *
- ***************************************************************************/
-
- // Libraries
- #include "BodyState.h"
-
- // We want to use the ReactPhysics3D namespace
- using namespace reactphysics3d;
-
- // Constructor
- BodyState::BodyState(const Vector3D& position, const Matrix3x3& inertiaTensorInverse, const Kilogram& massInverse)
- : position(position), linearMomentum(Vector3D()), orientation(Quaternion(1,0,0, 0)), angularMomentum(Vector3D()),
- linearVelocity(Vector3D()), angularVelocity(Vector3D()), spin(Quaternion()), inertiaTensorInverse(inertiaTensorInverse),
- massInverse(massInverse) {
- // TODO : orientation will be initialized in another way
- // TODO : linearMomentum will be initialized in another way
- // TODO : angularMomentum will be initialize in another way
- // TODO : linearVelocity will be initialize in another way
- // TODO : angularVelocity will be initialize in another way
- // TODO : spin will be initialize in another way
- }
-
-// Copy-constructor
-BodyState::BodyState(const BodyState& bodyState)
- : position(bodyState.position), linearMomentum(bodyState.linearMomentum), orientation(bodyState.orientation),
- angularMomentum(bodyState.angularMomentum), linearVelocity(bodyState.linearVelocity),
- angularVelocity(bodyState.angularVelocity), spin(bodyState.spin), inertiaTensorInverse(bodyState.inertiaTensorInverse),
- massInverse(bodyState.massInverse) {
-}
-
-// Destructor
-BodyState::~BodyState() {
-
-}
-
-// Recalculate the secondary values of the BodyState when the primary values have changed
-void BodyState::recalculate() {
- // Compute the linear velocity
- linearVelocity = linearMomentum * massInverse.getValue();
-
- // Compute the angular velocity
- angularVelocity = inertiaTensorInverse * angularMomentum;
-
- // Normalize the orientation quaternion
- orientation = orientation.getUnit();
-
- // Compute the spin quaternion
- spin = Quaternion(0, angularVelocity.getX(), angularVelocity.getY(), angularVelocity.getZ()) * orientation * 0.5;
-}
-
-// Compute the body state at time t + dt
-void computeAtTime(const Time& time, const Time& timeStep, const DerivativeBodyState& lastDerivativeBodyState) {
-
- double t = time.getValue(); // Current time
- double dt = timeStep.getValue(); // Timestep
-
- // Compute the position at time t + dt
- position = position + lastDerivativeBodyState.getLinearVelocity() * dt;
-
- // Compute the linear momentum at time t + dt
- linearMomentum = linearMomentum + lastDerivativeBodyState.force * dt;
-
- // Compute the orientation at time t + dt
- orientation = orientation + lastDerivativeBodyState.getSpin() * dt;
-
- // Compute the angular momentum at time t + dt
- angularMomentum = angularMomentum + lastDerivativeBodyState.torque * dt;
-
- // Recalculate the secondary values of the body state
- recalculate();
-}
-
-
-// Overloaded operator for the multiplication with a number
-BodyState BodyState::operator*(double number) const {
- // TODO : Implement this method
-}
diff --git a/sources/reactphysics3d/body/BodyState.h b/sources/reactphysics3d/body/BodyState.h
deleted file mode 100644
index 890fcc99..00000000
--- a/sources/reactphysics3d/body/BodyState.h
+++ /dev/null
@@ -1,143 +0,0 @@
-/****************************************************************************
- * Copyright (C) 2009 Daniel Chappuis *
- ****************************************************************************
- * This file is part of ReactPhysics3D. *
- * *
- * ReactPhysics3D 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 3 of the License, or *
- * (at your option) any later version. *
- * *
- * ReactPhysics3D 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 ReactPhysics3D. If not, see . *
- ***************************************************************************/
-
-#ifndef BODYSTATE_H
-#define BODYSTATE_H
-
-// Libraries
-#include "../mathematics/mathematics.h"
-#include "../physics/physics.h"
-
-// Namespace reactphysics3d
-namespace reactphysics3d {
-
-/* -------------------------------------------------------------------
- Class BodyState :
- A BodyState contains all the dynamics values of a body.
- -------------------------------------------------------------------
-*/
-class BodyState {
- private :
- // Primary values
- Vector3D position; // Position of the body
- Vector3D linearMomentum; // Linear momentum of the body
- Quaternion orientation; // Orientation quaternion of the body
- Vector3D angularMomentum; // Angular momentum of the body
-
- // Secondary values
- Vector3D linearVelocity; // Linear velocity of the body
- Vector3D angularVelocity; // Angular velocity of the body
- Quaternion spin; // Spin is the derivative of orientation quaternion over time.
-
- // Constants
- Matrix3x3 inertiaTensorInverse; // Inverse of the inertia tensor of the body
- Kilogram massInverse; // Inverse of the mass of the body
-
- public :
- BodyState(const Vector3D& position, const Matrix3x3& inertiaTensorInverse, const Kilogram& massInverse); // Constructor
- BodyState(const BodyState& bodyState); // Copy-constructor
- virtual ~BodyState(); // Destructor
-
- Vector3D getPosition() const; // Return the position of the body
- void setPosition(const Vector3D& position); // Set the position of the body
- Vector3D getLinearMomentum() const; // Return the linear momemtum
- void setLinearMomentum(const Vector3D& linearMomentum); // Set the linear momentum
- Quaternion getOrientation() const; // Return the orientation quaternion
- void setOrientation(const Quaternion& orientation); // Set the orientation quaternion
- Vector3D getAngularMomentum() const; // Return the angular momentum
- void setAngularMomentum(const Vector3D& angularMomentum); // Set the angular momentum
- Vector3D getAngularVelocity() const; // Return the angular velocity
- Quaternion getSpin() const; // Return the spin of the body
- void setMassInverse(Kilogram massInverse); // Set the inverse of the mass
- void setInertiaTensorInverse(const Matrix3x3& inertiaTensorInverse); // Set the inverse of the inertia tensor
-
- void recalculate(); // Recalculate the secondary values
- // of the BodyState from the primary ones
- void computeAtTime(const Time& time, const Time& timeStep,
- const DerivativeBodyState& lastDerivativeBodyState); // Compute the body state at time t + dt
-
- // Overloaded operators
- BodyState operator*(double number) const; // Overloaded operator for the multiplication with a number
-};
-
-// --- Inlines functions --- //
-
-// Return the position of the body
-inline Vector3D BodyState::getPosition() const {
- return position;
-}
-
-// Set the position of the body
-inline void BodyState::setPosition(const Vector3D& position) {
- this->position = position;
-}
-
-// Return the linear momentum of the body
-inline Vector3D BodyState::getLinearMomentum() const {
- return linearMomentum;
-}
-
-// Set the linear momentum of the body
-inline void BodyState::setLinearMomentum(const Vector3D& linearMomentum) {
- this->linearMomentum = linearMomentum;
-}
-
-// Return the orientation quaternion of the body
-inline Quaternion BodyState::getOrientation() const {
- return orientation;
-}
-
-// Set the orientation quaternion
-inline void BodyState::setOrientation(const Quaternion& orientation) {
- this->orientation = orientation;
-}
-
-// Return the angular momentum of the body
-inline Vector3D BodyState::getAngularMomentum() const {
- return angularMomentum;
-}
-
-// Set the angular momentum of the body
-inline void BodyState::setAngularMomentum(const Vector3D& angularMomentum) {
- this->angularMomentum = angularMomentum;
-}
-
-// Return the angular velocity of the body
-inline Vector3D BodyState::getAngularVelocity() const {
- return angularVelocity;
-}
-
-// Return the spin of the body
-inline Quaternion BodyState::getSpin() const {
- return spin;
-}
-
-// Set the inverse of the mass
-inline void BodyState::setMassInverse(Kilogram massInverse) {
- this->massInverse = massInverse;
-}
-
-// Set the inverse of the inertia tensor
-inline void BodyState::setInertiaTensorInverse(const Matrix3x3& inertiaTensorInverse) {
- this->inertiaTensorInverse = inertiaTensorInverse;
-}
-
-}
-
-#endif
diff --git a/sources/reactphysics3d/body/RigidBody.cpp b/sources/reactphysics3d/body/RigidBody.cpp
deleted file mode 100644
index 0a4052cc..00000000
--- a/sources/reactphysics3d/body/RigidBody.cpp
+++ /dev/null
@@ -1,57 +0,0 @@
-/****************************************************************************
- * Copyright (C) 2009 Daniel Chappuis *
- ****************************************************************************
- * This file is part of ReactPhysics3D. *
- * *
- * ReactPhysics3D 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 3 of the License, or *
- * (at your option) any later version. *
- * *
- * ReactPhysics3D 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 ReactPhysics3D. If not, see . *
- ***************************************************************************/
-
- // Libraries
- #include "RigidBody.h"
-
- // We want to use the ReactPhysics3D namespace
- using namespace reactphysics3d;
-
- // Constructor
- RigidBody::RigidBody(const Vector3D& position, const Kilogram& mass, const Matrix3x3& inertiaTensor)
- : Body(mass), inertiaTensor(inertiaTensor),
- currentBodyState(position, inertiaTensor.getInverse(),Kilogram(1.0/mass.getValue())),
- previousBodyState(position, inertiaTensor.getInverse(), Kilogram(1.0/mass.getValue())) {
- isMotionEnabled = true;
- isCollisionEnabled = true;
- }
-
- // Copy-constructor
- RigidBody::RigidBody(const RigidBody& rigidBody) : Body(rigidBody), inertiaTensor(rigidBody.inertiaTensor),
- currentBodyState(rigidBody.currentBodyState), previousBodyState(rigidBody.previousBodyState) {
- this->isMotionEnabled = rigidBody.isMotionEnabled;
- this->isCollisionEnabled = rigidBody.isCollisionEnabled;
- }
-
- // Destructor
- RigidBody::~RigidBody() {
-
- };
-
-// Return the force on the body at time t
-Vector3D RigidBody::computeForce(Time time) const {
- // TODO : Implement this method
- return Vector3D(1*time.getValue(),0,0);
-}
-
-// Return the torque on the body at time
-Vector3D RigidBody::computeTorque(Time time) const {
- // TODO : Implement this method
- return Vector3D(1*time.getValue(),0,0);
-}
diff --git a/sources/reactphysics3d/body/RigidBody.h b/sources/reactphysics3d/body/RigidBody.h
deleted file mode 100644
index 2c917097..00000000
--- a/sources/reactphysics3d/body/RigidBody.h
+++ /dev/null
@@ -1,85 +0,0 @@
-/****************************************************************************
- * Copyright (C) 2009 Daniel Chappuis *
- ****************************************************************************
- * This file is part of ReactPhysics3D. *
- * *
- * ReactPhysics3D 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 3 of the License, or *
- * (at your option) any later version. *
- * *
- * ReactPhysics3D 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 ReactPhysics3D. If not, see . *
- ***************************************************************************/
-
- #ifndef RIGIDBODY_H
- #define RIGIDBODY_H
-
- // Libraries
- #include "Body.h"
- #include "BodyState.h"
- #include "../mathematics/mathematics.h"
- #include "../physics/physics.h"
-
-// Namespace reactphysics3d
-namespace reactphysics3d {
-
-/* -------------------------------------------------------------------
- Class RigidBody :
- This class represents a rigid body of the physics
- engine. A rigid body is a non-deformable body that
- has a constant mass.
- -------------------------------------------------------------------
-*/
-class RigidBody : public Body {
- private :
- Matrix3x3 inertiaTensor; // Inertia tensor of the body
- BodyState currentBodyState; // Current body state
- BodyState previousBodyState; // Previous body state
- bool isMotionEnabled; // True if the body can move
- bool isCollisionEnabled; // True if the body can collide with others bodies
-
- public :
- RigidBody(const Vector3D& position, const Kilogram& mass, const Matrix3x3& inertiaTensor); // Constructor
- RigidBody(const RigidBody& rigidBody); // Copy-constructor
- virtual ~RigidBody(); // Destructor
-
- Matrix3x3 getInertiaTensor() const; // Return the inertia tensor of the body
- void setInertiaTensor(const Matrix3x3& inertiaTensor); // Set the inertia tensor of the body
- BodyState getCurrentBodyState() const; // Return the current state of the body
- BodyState getPreviousBodyState() const; // Return the previous state of the body
- Vector3D computeForce(Time time) const; // Return the force on the body at time t
- Vector3D computeTorque(Time time) const; // Return the torque on the body at time t
-};
-
-// --- Inline functions --- //
-
-// Return the inertia tensor of the body
-inline Matrix3x3 RigidBody::getInertiaTensor() const {
- return inertiaTensor;
-}
-
-// Set the inertia tensor of the body
-inline void RigidBody::setInertiaTensor(const Matrix3x3& inertiaTensor) {
- this->inertiaTensor = inertiaTensor;
-}
-
-// Return the current state of the body
-inline BodyState RigidBody::getCurrentBodyState() const {
- return currentBodyState;
-}
-
-// Return the previous state of the body
-inline BodyState RigidBody::getPreviousBodyState() const {
- return previousBodyState;
-}
-
-
-}
-
- #endif