diff --git a/sources/reactphysics3d/engine/CollisionEngine.cpp b/sources/reactphysics3d/engine/CollisionEngine.cpp deleted file mode 100644 index 22a4dbe3..00000000 --- a/sources/reactphysics3d/engine/CollisionEngine.cpp +++ /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 Lesser 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 Lesser General Public License for more details. * -* * -* You should have received a copy of the GNU Lesser General Public License * -* along with ReactPhysics3D. If not, see . * -***************************************************************************/ - -// Libraries -#include "CollisionEngine.h" -#include -#include // TODO : Remove this in the final version -#include // TODO : Remove this in the final version - -// We want to use the ReactPhysics3D namespace -using namespace reactphysics3d; - -// Constructor -CollisionEngine::CollisionEngine(PhysicsWorld* world, const Time& timeStep) - :DynamicEngine(world, timeStep) { -} - - // Destructor -CollisionEngine::~CollisionEngine() { - -} - -// Update the physics simulation -void CollisionEngine::update() { - - // While the time accumulator is not empty - while(timer.getAccumulator() >= timer.getTimeStep().getValue()) { - - // Remove all old collision contact constraints - world->removeAllContactConstraints(); - - // Compute the collision detection - if (collisionDetection.computeCollisionDetection(world)) { - - // TODO : Delete this ---------------------------------------------------------- - for (std::vector::const_iterator it = world->getConstraintListStartIterator(); it != world->getConstraintListEndIterator(); ++it) { - RigidBody* rigidBody1 = dynamic_cast((*it)->getBody1()); - RigidBody* rigidBody2 = dynamic_cast((*it)->getBody2()); - rigidBody1->setIsMotionEnabled(false); - rigidBody2->setIsMotionEnabled(false); - } - // ----------------------------------------------------------------------------- - } - - // For each body in the dynamic world - for(std::vector::const_iterator it = world->getBodyListStartIterator(); it != world->getBodyListEndIterator(); ++it) { - // If the body is a RigidBody and if the rigid body motion is enabled - RigidBody* rigidBody = dynamic_cast(*it); - if (rigidBody && rigidBody->getIsMotionEnabled()) { - // Update the state of the rigid body with an entire time step - updateBodyState(rigidBody, timer.getTimeStep()); - } - } - - // Update the timer - timer.update(); - } - - // For each body in the the dynamic world - for(std::vector::const_iterator it = world->getBodyListStartIterator(); it != world->getBodyListEndIterator(); ++it) { - // If the body is a RigidBody and if the rigid body motion is enabled - RigidBody* rigidBody = dynamic_cast(*it); - if (rigidBody && rigidBody->getIsMotionEnabled()) { - // Update the interpolation factor of the rigid body - // This one will be used to compute the interpolated state - rigidBody->setInterpolationFactor(timer.getInterpolationFactor()); - } - } -} diff --git a/sources/reactphysics3d/engine/CollisionEngine.h b/sources/reactphysics3d/engine/CollisionEngine.h deleted file mode 100644 index d63cf384..00000000 --- a/sources/reactphysics3d/engine/CollisionEngine.h +++ /dev/null @@ -1,50 +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 Lesser 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 Lesser General Public License for more details. * -* * -* You should have received a copy of the GNU Lesser General Public License * -* along with ReactPhysics3D. If not, see . * -***************************************************************************/ - -#ifndef COLLISIONENGINE_H -#define COLLISIONENGINE_H - -// Libraries -#include "DynamicEngine.h" -#include "../collision/CollisionDetection.h" - -// ReactPhysics3D namespace -namespace reactphysics3d { - -/* ------------------------------------------------------------------- - Class CollisionEngine : - This class implements the physics engine where bodies can - collide. This class inherits from the class DynamicEngine. - ------------------------------------------------------------------- -*/ -class CollisionEngine : public DynamicEngine { - private : - CollisionDetection collisionDetection; // Collision detection - // ConstraintSolver constraintSolver; // Constraint solver - - public : - CollisionEngine(PhysicsWorld* world, const Time& timeStep); // Constructor - virtual ~CollisionEngine(); // Destructor - - virtual void update(); // Update the physics simulation -}; - -} // End of the ReactPhysics3D namespace - -#endif diff --git a/sources/reactphysics3d/engine/DynamicEngine.cpp b/sources/reactphysics3d/engine/DynamicEngine.cpp deleted file mode 100644 index 73469100..00000000 --- a/sources/reactphysics3d/engine/DynamicEngine.cpp +++ /dev/null @@ -1,104 +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 Lesser 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 Lesser General Public License for more details. * - * * - * You should have received a copy of the GNU Lesser General Public License * - * along with ReactPhysics3D. If not, see . * - ***************************************************************************/ - -// Libraries -#include "DynamicEngine.h" -#include "../integration/RungeKutta4.h" -#include "../integration/ExplicitEuler.h" -#include "../integration/SemiImplicitEuler.h" - -// We want to use the ReactPhysics3D namespace -using namespace reactphysics3d; - -// Constructor -DynamicEngine::DynamicEngine(PhysicsWorld* world, const Time& timeStep) - :PhysicsEngine(world, timeStep) { - // Check if the pointer to the world is not NULL - if (world == 0) { - // Throw an exception - throw std::invalid_argument("Exception in PhysicsEngine constructor : World pointer cannot be NULL"); - } - - // Creation of the Semi-Implicit Euler integration algorithm - integrationAlgorithm = new SemiImplicitEuler(); -} - -// Copy-constructor -DynamicEngine::DynamicEngine(const DynamicEngine& engine) - :PhysicsEngine(engine) { - integrationAlgorithm = engine.integrationAlgorithm; -} - -// Destructor -DynamicEngine::~DynamicEngine() { - // Destroy the integration algorithm - delete integrationAlgorithm; -} - -// Update the state of a rigid body -void DynamicEngine::updateBodyState(RigidBody* const rigidBody, const Time& timeStep) { - - // If the gravity force is on - if(world->getIsGravityOn()) { - // Apply the current gravity force to the body - rigidBody->getCurrentBodyState().setForce(world->getGravity()); - } - - // The current body state of the body becomes the previous body state - rigidBody->updatePreviousBodyState(); - - // Integrate the current body state at time t to get the next state at time t + dt - integrationAlgorithm->integrate(rigidBody->getCurrentBodyState(), timer.getTime(), timeStep); - - // If the body state has changed, we have to update some informations in the rigid body - rigidBody->update(); -} - -// Update the physics simulation -void DynamicEngine::update() { - // Check if the physics simulation is running - if (timer.getIsRunning()) { - // While the time accumulator is not empty - while(timer.getAccumulator() >= timer.getTimeStep().getValue()) { - // For each body in the dynamic world - for(std::vector::const_iterator it = world->getBodyListStartIterator(); it != world->getBodyListEndIterator(); ++it) { - // If the body is a RigidBody and if the rigid body motion is enabled - RigidBody* rigidBody = dynamic_cast(*it); - if (rigidBody && rigidBody->getIsMotionEnabled()) { - // Update the state of the rigid body - updateBodyState(rigidBody, timer.getTimeStep()); - } - } - - // Update the timer - timer.update(); - } - - // For each body in the dynamic world - for(std::vector::const_iterator it = world->getBodyListStartIterator(); it != world->getBodyListEndIterator(); ++it) { - // If the body is a RigidBody and if the rigid body motion is enabled - RigidBody* rigidBody = dynamic_cast(*it); - if (rigidBody && rigidBody->getIsMotionEnabled()) { - // Update the interpolation factor of the rigid body - // This one will be used to compute the interpolated state - rigidBody->setInterpolationFactor(timer.getInterpolationFactor()); - } - } - } -} diff --git a/sources/reactphysics3d/engine/DynamicEngine.h b/sources/reactphysics3d/engine/DynamicEngine.h deleted file mode 100644 index e74aa8ac..00000000 --- a/sources/reactphysics3d/engine/DynamicEngine.h +++ /dev/null @@ -1,58 +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 Lesser 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 Lesser General Public License for more details. * - * * - * You should have received a copy of the GNU Lesser General Public License * - * along with ReactPhysics3D. If not, see . * - ***************************************************************************/ - -#ifndef DYNAMICENGINE_H -#define DYNAMICENGINE_H - -// Libraries -#include "PhysicsEngine.h" -#include "../integration/IntegrationAlgorithm.h" -#include "../body/Body.h" -#include "../body/RigidBody.h" -#include "../body/BodyState.h" -#include "PhysicsWorld.h" -#include "../physics/physics.h" - -// Namespace ReactPhysics3D -namespace reactphysics3d { - -/* ------------------------------------------------------------------- - Class DynamicEngine : - This class that represents a physics engine where we use - the dynamics to simulate the movement of bodies. The class - DynamicEngine inherits from the class PhysicsEngine. - ------------------------------------------------------------------- -*/ -class DynamicEngine : public PhysicsEngine { - protected : - IntegrationAlgorithm* integrationAlgorithm; // Integration algorithm used to solve differential equations of movement - - void updateBodyState(RigidBody* const rigidBody, const Time& timeStep); // Update the state of a rigid body - - public : - DynamicEngine(PhysicsWorld* world, const Time& timeStep); // Constructor - DynamicEngine(const DynamicEngine& engine); // Copy-constructor - virtual ~DynamicEngine(); // Destructor - - virtual void update(); // Update the physics simulation -}; - -} - -#endif