diff --git a/sources/reactphysics3d/engine/DynamicEngine.cpp b/sources/reactphysics3d/engine/DynamicEngine.cpp
index a7bacadc..73de4e7f 100644
--- a/sources/reactphysics3d/engine/DynamicEngine.cpp
+++ b/sources/reactphysics3d/engine/DynamicEngine.cpp
@@ -24,7 +24,7 @@
using namespace reactphysics3d;
// Constructor
-DynamicEngine::DynamicEngine(DynamicsWorld& world, const Time& timeStep)
+DynamicEngine::DynamicEngine(DynamicWorld& world, const Time& timeStep)
:PhysicsEngine(world, timeStep) {
}
@@ -40,23 +40,42 @@ DynamicEngine::~DynamicEngine() {
}
-// Compute the interpolation state between the previous body state and the current body state
-// This is used to avoid visual stuttering when the display and physics framerates are out of synchronization
-BodyState DynamicEngine::interpolateState(const BodyState& previousBodyState, const BodyState& currentBodyState) const {
-
- // Compute the interpolation factor
- double alpha = timer.getInterpolationFactor();
-
- // TODO : Implement this method
-
-}
-
// Update the state of a rigid body
void DynamicEngine::updateBodyState(RigidBody* const rigidBody) {
- // TODO : Implement this method
+ // 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
+ numericalIntegrator.integrate(rigidBody->getCurrentBodyState(), timer.getTime(), timer.getTimeStep());
}
// Update the physics simulation
void DynamicEngine::update() {
- // TODO : Implement this method
+
+ // 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
+ RigidBody* rigidBody = dynamic_cast(*it);
+ if (rigidBody) {
+ // Update the state of the rigid body
+ updateBodyState(rigidBody);
+ }
+ }
+
+ // 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
+ RigidBody* rigidBody = dynamic_cast(*it);
+ if (rigidBody) {
+ // 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
index 4f6817d1..4fda081d 100644
--- a/sources/reactphysics3d/engine/DynamicEngine.h
+++ b/sources/reactphysics3d/engine/DynamicEngine.h
@@ -26,6 +26,8 @@
#include "../body/Body.h"
#include "../body/RigidBody.h"
#include "../body/BodyState.h"
+#include "DynamicWorld.h"
+#include "../physics/physics.h"
// Namespace ReactPhysics3D
namespace reactphysics3d {
@@ -41,11 +43,10 @@ class DynamicEngine : public PhysicsEngine {
protected :
NumericalIntegrator numericalIntegrator; // Numerical integrator used to solve differential equations of movement
- BodyState interpolateState(const BodyState& previousBodyState, const BodyState& currentBodyState) const; // Compute the interpolation state
void updateBodyState(RigidBody* const rigidBody); // Update the state of a rigid body
public :
- DynamicEngine(DynamicsWorld& world, const Time& timeStep); // Constructor
+ DynamicEngine(DynamicWorld& world, const Time& timeStep); // Constructor
DynamicEngine(const DynamicEngine& engine); // Copy-constructor
virtual ~DynamicEngine(); // Destructor
diff --git a/sources/reactphysics3d/engine/PhysicsEngine.cpp b/sources/reactphysics3d/engine/PhysicsEngine.cpp
index daab0aaf..b5293d34 100644
--- a/sources/reactphysics3d/engine/PhysicsEngine.cpp
+++ b/sources/reactphysics3d/engine/PhysicsEngine.cpp
@@ -29,6 +29,12 @@ PhysicsEngine::PhysicsEngine(PhysicsWorld& world, const Time& timeStep)
}
+// Copy-constructor
+PhysicsEngine::PhysicsEngine(const PhysicsEngine& engine)
+ :world(engine.world), timer(engine.timer) {
+
+}
+
// Destructor
PhysicsEngine::~PhysicsEngine() {
diff --git a/sources/reactphysics3d/engine/PhysicsEngine.h b/sources/reactphysics3d/engine/PhysicsEngine.h
index 92e66db1..c1d36172 100644
--- a/sources/reactphysics3d/engine/PhysicsEngine.h
+++ b/sources/reactphysics3d/engine/PhysicsEngine.h
@@ -34,16 +34,14 @@ namespace reactphysics3d {
-------------------------------------------------------------------
*/
class PhysicsEngine {
- private :
- PhysicsEngine(const PhysicsEngine&); // Copy-constructor is private because we don't want it to be used
-
protected :
PhysicsWorld world; // Physics world of the physics engine
Timer timer; // Timer of the physics engine
public :
- PhysicsEngine(PhysicsWorld& world, const Time& timeStep); // Constructor
- virtual ~PhysicsEngine(); // Destructor
+ PhysicsEngine(PhysicsWorld& world, const Time& timeStep); // Constructor
+ PhysicsEngine(const PhysicsEngine& engine); // Copy-constructor
+ virtual ~PhysicsEngine(); // Destructor
virtual void update()=0; // Update the physics simulation
};
diff --git a/sources/reactphysics3d/engine/PhysicsWorld.cpp b/sources/reactphysics3d/engine/PhysicsWorld.cpp
index 4c6679bd..dc764d85 100644
--- a/sources/reactphysics3d/engine/PhysicsWorld.cpp
+++ b/sources/reactphysics3d/engine/PhysicsWorld.cpp
@@ -44,7 +44,7 @@ void PhysicsWorld::addBody(Body* body) throw(std::invalid_argument) {
// Check if the body pointer is not null
if (body != 0) {
// Check if the body pointer isn't already in the bodyList
- for(std::vector::iterator it = bodyList.begin(); it != bodyList.end(); ) {
+ for(std::vector::iterator it = bodyList.begin(); it != bodyList.end(); ++it) {
if (*it == body) {
// The body is already in the bodyList, therefore we throw an exception
throw std::invalid_argument("Exception in PhysicsWorld::addBody() : The argument body is already in the PhysicsWorld");
diff --git a/sources/reactphysics3d/engine/PhysicsWorld.h b/sources/reactphysics3d/engine/PhysicsWorld.h
index 317756f2..90b38f9d 100644
--- a/sources/reactphysics3d/engine/PhysicsWorld.h
+++ b/sources/reactphysics3d/engine/PhysicsWorld.h
@@ -48,8 +48,30 @@ class PhysicsWorld {
void addBody(Body* body) throw(std::invalid_argument); // Add a body to the physics world
void removeBody(Body const* const body) throw(std::invalid_argument); // Remove a body from the physics world
+ Vector3D getGravity() const; // Return the gravity vector of the world
+ std::vector::const_iterator getBodyListStartIterator() const; // Return a start iterator on the body list
+ std::vector::const_iterator getBodyListEndIterator() const; // Return a end iterator on the body list
};
+// --- Inline functions --- //
+
+// Return the gravity vector of the world
+inline Vector3D PhysicsWorld::getGravity() const {
+ return gravity;
+}
+
+// Return a start iterator on the body list
+inline std::vector::const_iterator PhysicsWorld::getBodyListStartIterator() const {
+ // Return an iterator on the start of the body list
+ return bodyList.begin();
+}
+
+// Return a end iterator on the body list
+inline std::vector::const_iterator PhysicsWorld::getBodyListEndIterator() const {
+ // Return an iterator on the end of the body list
+ return bodyList.end();
+}
+
} // End of the ReactPhysics3D namespace
#endif
diff --git a/sources/reactphysics3d/engine/Timer.cpp b/sources/reactphysics3d/engine/Timer.cpp
index e90a9d4b..ae9199b4 100644
--- a/sources/reactphysics3d/engine/Timer.cpp
+++ b/sources/reactphysics3d/engine/Timer.cpp
@@ -1,21 +1,21 @@
/****************************************************************************
- * 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 . *
- ***************************************************************************/
+* 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 "Timer.h"
@@ -23,9 +23,9 @@
// We want to use the ReactPhysics3D namespace
using namespace reactphysics3d;
- // Constructor
- Timer::Timer(const Time& initialTime, const Time& timeStep) throw(std::invalid_argument)
- : timeStep(timeStep), time(initialTime), currentDisplayTime(Time(0.0)), deltatDisplayTime(Time(0.0)) {
+// Constructor
+Timer::Timer(const Time& initialTime, const Time& timeStep) throw(std::invalid_argument)
+ : timeStep(timeStep), time(initialTime), currentDisplayTime(Time(0.0)), deltaDisplayTime(Time(0.0)) {
// Check if the timestep is different from zero
if (timeStep.getValue() != 0.0) {
accumulator = 0.0;
@@ -36,13 +36,13 @@ using namespace reactphysics3d;
// We throw an exception
throw std::invalid_argument("Exception in Timer constructor : The timestep has to be different from zero");
}
- }
+}
// Copy-constructor
Timer::Timer(const Timer& timer)
: timeStep(timer.timeStep), time(timer.time), currentDisplayTime(timer.currentDisplayTime),
- deltatDisplayTime(timer.deltatDisplayTime), accumulator(timer.accumulator) {
+ deltaDisplayTime(timer.deltaDisplayTime), accumulator(timer.accumulator) {
isRunning = timer.isRunning;
}
@@ -51,30 +51,6 @@ Timer::~Timer() {
}
-// Update the timer
-void Timer::update() {
- // Update the current time of the physics engine
- time.setValue(time.getValue() + timeStep.getValue());
-
- // Update the accumulator value
- accumulator -= timeStep.getValue();
-}
-
-// Compute and return the interpolation factor between two body states
-double Timer::getInterpolationFactor() const {
- // Compute and return the interpolation factor
- return (accumulator / timeStep.getValue());
-}
-
-// Set the new currentDisplayTime value
-void Timer::updateDisplayTime(const Time& newDisplayTime) {
- // Compute the delta display time between two display frames
- deltatDisplayTime.setValue(newDisplayTime.getValue() - currentDisplayTime.getValue());
-
- // Update the current display time
- currentDisplayTime = newDisplayTime;
-}
-
diff --git a/sources/reactphysics3d/engine/Timer.h b/sources/reactphysics3d/engine/Timer.h
index 40c62e95..fc9882a7 100644
--- a/sources/reactphysics3d/engine/Timer.h
+++ b/sources/reactphysics3d/engine/Timer.h
@@ -37,7 +37,7 @@ class Timer {
Time timeStep; // Timestep dt of the physics engine (timestep > 0.0)
Time time; // Current time of the physics engine
Time currentDisplayTime; // Current display time
- Time deltatDisplayTime; // Current time difference between two display frames
+ Time deltaDisplayTime; // Current time difference between two display frames
double accumulator; // Used to fix the time step and avoid strange time effects
bool isRunning; // True if the timer is running
@@ -103,6 +103,33 @@ inline double Timer::getAccumulator() const {
return accumulator;
}
- } // End of the ReactPhysics3D namespace
+// Update the timer
+inline void Timer::update() {
+ // Update the current time of the physics engine
+ time.setValue(time.getValue() + timeStep.getValue());
+
+ // Update the accumulator value
+ accumulator -= timeStep.getValue();
+}
+
+// Compute and return the interpolation factor between two body states
+inline double Timer::getInterpolationFactor() const {
+ // Compute and return the interpolation factor
+ return (accumulator / timeStep.getValue());
+}
+
+// Set the new currentDisplayTime value
+inline void Timer::updateDisplayTime(const Time& newDisplayTime) {
+ // Compute the delta display time between two display frames
+ deltaDisplayTime.setValue(newDisplayTime.getValue() - currentDisplayTime.getValue());
+
+ // Update the current display time
+ currentDisplayTime.setValue(newDisplayTime.getValue());
+
+ // Update the accumulator value
+ accumulator += deltaDisplayTime.getValue();
+}
+
+} // End of the ReactPhysics3D namespace
#endif