From 639e91b21b0e14d9aab31845b78ff2b98dd88c83 Mon Sep 17 00:00:00 2001 From: "chappuis.daniel" Date: Sat, 5 Jun 2010 22:22:06 +0000 Subject: [PATCH] Correction of some errors git-svn-id: https://reactphysics3d.googlecode.com/svn/trunk@325 92aac97c-a6ce-11dd-a772-7fcde58d38e6 --- .../engine/ConstraintSolver.cpp | 10 +++--- .../reactphysics3d/engine/ConstraintSolver.h | 4 +-- .../reactphysics3d/engine/PhysicsEngine.cpp | 2 +- sources/reactphysics3d/engine/PhysicsWorld.h | 26 +++++++-------- sources/reactphysics3d/mathematics/Matrix.cpp | 32 ++++++++++++++++++- sources/reactphysics3d/mathematics/Matrix.h | 2 ++ sources/reactphysics3d/mathematics/Vector.cpp | 8 +++++ sources/reactphysics3d/mathematics/Vector.h | 23 ++++++++++--- .../lcp/LCPProjectedGaussSeidel.cpp | 27 +++++++++------- .../mathematics/lcp/LCPProjectedGaussSeidel.h | 8 ++--- .../mathematics/lcp/LCPSolver.cpp | 3 +- .../mathematics/lcp/LCPSolver.h | 6 ++-- 12 files changed, 105 insertions(+), 46 deletions(-) diff --git a/sources/reactphysics3d/engine/ConstraintSolver.cpp b/sources/reactphysics3d/engine/ConstraintSolver.cpp index 8cbcc2bb..387466cb 100644 --- a/sources/reactphysics3d/engine/ConstraintSolver.cpp +++ b/sources/reactphysics3d/engine/ConstraintSolver.cpp @@ -26,7 +26,7 @@ using namespace reactphysics3d; // Constructor ConstraintSolver::ConstraintSolver(PhysicsWorld& world) - :physicsWorld(world), bodyMapping(0) , lcpSolver(LCPProjectedGaussSeidel(MAX_LCP_ITERATIONS)) { + :physicsWorld(world), bodyMapping(0), lcpSolver(new LCPProjectedGaussSeidel(MAX_LCP_ITERATIONS)) { } @@ -38,10 +38,12 @@ ConstraintSolver::~ConstraintSolver() { // Allocate all the matrices needed to solve the LCP problem void ConstraintSolver::allocate() { uint nbConstraints = 0; + Constraint* constraint; // For each constraint - for (uint c=0; c::iterator it; + for (it = physicsWorld.getConstraintsBeginIterator(); it evaluate(); @@ -230,7 +232,7 @@ void ConstraintSolver::solve(double dt) { computeMatrixB_sp(); // Solve the LCP problem (computation of lambda) - //lcpSolver.solve(A, b, lowLimits, highLimits, lambda); + lcpSolver->solve(J_sp, B_sp, activeConstraints.size(), nbBodies, bodyMapping, bodyNumberMapping, b, lowerBounds, upperBounds, lambda); // TODO : Implement this method ... diff --git a/sources/reactphysics3d/engine/ConstraintSolver.h b/sources/reactphysics3d/engine/ConstraintSolver.h index 458926ad..6d741df2 100644 --- a/sources/reactphysics3d/engine/ConstraintSolver.h +++ b/sources/reactphysics3d/engine/ConstraintSolver.h @@ -41,8 +41,8 @@ const uint MAX_LCP_ITERATIONS = 10; // Maximum number of iterations when sol */ class ConstraintSolver { protected: - LCPSolver& lcpSolver; // LCP Solver PhysicsWorld& physicsWorld; // Reference to the physics world + LCPSolver* lcpSolver; // LCP Solver std::vector activeConstraints; // Current active constraints in the physics world std::vector constraintBodies; // Bodies that are implied in some constraint uint nbBodies; // Current number of bodies in the physics world @@ -75,7 +75,7 @@ class ConstraintSolver { void computeMatrixB_sp(); // Compute the matrix B_sp public: - ConstraintSolver(const PhysicsWorld& world); // Constructor + ConstraintSolver(PhysicsWorld& world); // Constructor virtual ~ConstraintSolver(); // Destructor void solve(double dt); // Solve the current LCP problem }; diff --git a/sources/reactphysics3d/engine/PhysicsEngine.cpp b/sources/reactphysics3d/engine/PhysicsEngine.cpp index d9a40cf0..45af4249 100644 --- a/sources/reactphysics3d/engine/PhysicsEngine.cpp +++ b/sources/reactphysics3d/engine/PhysicsEngine.cpp @@ -91,7 +91,7 @@ void PhysicsEngine::updateCollision() { if (collisionDetection.computeCollisionDetection()) { // TODO : Delete this ---------------------------------------------------------- - for (std::vector::const_iterator it = world->getConstraintListStartIterator(); it != world->getConstraintListEndIterator(); ++it) { + for (std::vector::iterator it = world->getConstraintsBeginIterator(); it != world->getConstraintsEndIterator(); ++it) { RigidBody* rigidBody1 = dynamic_cast((*it)->getBody1()); RigidBody* rigidBody2 = dynamic_cast((*it)->getBody2()); rigidBody1->setIsMotionEnabled(false); diff --git a/sources/reactphysics3d/engine/PhysicsWorld.h b/sources/reactphysics3d/engine/PhysicsWorld.h index 2e93b7d7..3b16fb1a 100644 --- a/sources/reactphysics3d/engine/PhysicsWorld.h +++ b/sources/reactphysics3d/engine/PhysicsWorld.h @@ -59,10 +59,10 @@ class PhysicsWorld { void addConstraint(Constraint* constraint) throw(std::invalid_argument); // Add a constraint void removeConstraint(Constraint* constraint) throw(std::invalid_argument); // Remove a constraint void removeAllContactConstraints(); // Remove all collision contacts constraints - std::vector::const_iterator getConstraintListStartIterator() const; // Return a start iterator on the constraint list - std::vector::const_iterator getConstraintListEndIterator() const; // Return a end iterator on the constraint list - std::vector& getBodies(); // Return a reference to the bodies of the physics world - std::vector& getConstraints(); // Return a reference to the constraints of the physics world + std::vector::iterator getConstraintsBeginIterator(); // Return a start iterator on the constraint list + std::vector::iterator getConstraintsEndIterator(); // Return a end iterator on the constraint list + std::vector::iterator getBodiesBeginIterator(); // Return an iterator to the beginning of the bodies of the physics world + std::vector::iterator getBodiesEndIterator(); // Return an iterator to the end of the bodies of the physics world }; // --- Inline functions --- // @@ -95,25 +95,25 @@ inline void PhysicsWorld::setIsGratityOn(bool isGravityOn) { } // Return a start iterator on the constraint list -inline std::vector::const_iterator PhysicsWorld::getConstraintListStartIterator() const { +inline std::vector::iterator PhysicsWorld::getConstraintsBeginIterator() { return constraints.begin(); } // Return a end iterator on the constraint list -inline std::vector::const_iterator PhysicsWorld::getConstraintListEndIterator() const { +inline std::vector::iterator PhysicsWorld::getConstraintsEndIterator() { return constraints.end(); } -// Return a reference to the bodies of the physics world -std::vector& PhysicsWorld::getBodies() { - return bodies; +// Return an iterator to the beginning of the bodies of the physics world +inline std::vector::iterator PhysicsWorld::getBodiesBeginIterator() { + return bodies.begin(); } -// Return a reference to the constraints of the physics world -std::vector& PhysicsWorld::getConstraints() { - return constraints; +// Return an iterator to the end of the bodies of the physics world +inline std::vector::iterator PhysicsWorld::getBodiesEndIterator() { + return bodies.end(); } } // End of the ReactPhysics3D namespace - #endif + #endif \ No newline at end of file diff --git a/sources/reactphysics3d/mathematics/Matrix.cpp b/sources/reactphysics3d/mathematics/Matrix.cpp index e85020f2..61219923 100644 --- a/sources/reactphysics3d/mathematics/Matrix.cpp +++ b/sources/reactphysics3d/mathematics/Matrix.cpp @@ -276,7 +276,6 @@ double Matrix::getTrace() const throw(MathematicsException) { // We throw an exception because the matrix is non-square throw MathematicsException("MathematicsException : Impossible to compute the trace for a non-square matrix"); } - } // Return a sub matrix of size of the current matrix @@ -353,6 +352,16 @@ void Matrix::initWithValue(double value) { } } + + Vector Matrix::getVector() const { + assert(nbColumn == 1); + Vector vec(nbRow); + for (int i=0; i bodyNumberMapping, +void LCPProjectedGaussSeidel::solve(Matrix** J_sp, Matrix** B_sp, uint nbConstraints, + uint nbBodies, Body*** const bodyMapping, std::map bodyNumberMapping, const Vector& b, const Vector& lowLimits, const Vector& highLimits, Vector& lambda) const { lambda = lambdaInit; - double d[] = new double[nbConstraints]; // TODO : Avoid those kind of memory allocation here for optimization (allocate once in the object) - Body* indexBody1, indexBody2; + double* d = new double[nbConstraints]; // TODO : Avoid those kind of memory allocation here for optimization (allocate once in the object) + uint indexBody1, indexBody2; double deltaLambda; double lambdaTemp; uint i, iter; - Vector* a = new Vector(6)[nbBodies]; // Array that contains nbBodies vector of dimension 6x1 + Vector* a = new Vector[nbBodies]; // Array that contains nbBodies vector of dimension 6x1 + for (i=0; i bodyNumberMapping, Vector* const a, uint nbBodies) const { uint i; - Body* indexBody1, indexBody2; + uint indexBody1, indexBody2; // Init the vector a with zero values for (i=0; i bodyNumberMapping, Vector* const a, uint nbBodies) const ; // Compute the vector a used in the solve() method public: LCPProjectedGaussSeidel(uint maxIterations); // Constructor virtual ~LCPProjectedGaussSeidel(); // Destructor - virtual void solve(const Matrix** const J_sp, const Matrix** const B_sp, const Body*** const bodyMapping, - std::map bodyNumberMapping, const Vector& b, const Vector& lowLimits, - const Vector& highLimits, Vector& lambda) const; // Solve a LCP problem using Projected-Gauss-Seidel algorithm // Set the initial value for lambda + virtual void solve(Matrix** J_sp, Matrix** B_sp, uint nbConstraints, + uint nbBodies, Body*** const bodyMapping, std::map bodyNumberMapping, + const Vector& b, const Vector& lowLimits, const Vector& highLimits, Vector& lambda) const; // Solve a LCP problem using Projected-Gauss-Seidel algorithm // Set the initial value for lambda }; } // End of the ReactPhysics3D namespace diff --git a/sources/reactphysics3d/mathematics/lcp/LCPSolver.cpp b/sources/reactphysics3d/mathematics/lcp/LCPSolver.cpp index 945c4d63..63483131 100644 --- a/sources/reactphysics3d/mathematics/lcp/LCPSolver.cpp +++ b/sources/reactphysics3d/mathematics/lcp/LCPSolver.cpp @@ -23,7 +23,8 @@ using namespace reactphysics3d; // Constructor -LCPSolver::LCPSolver() { +LCPSolver::LCPSolver(uint maxIterations) + : maxIterations(maxIterations) { } diff --git a/sources/reactphysics3d/mathematics/lcp/LCPSolver.h b/sources/reactphysics3d/mathematics/lcp/LCPSolver.h index 95d4aa6a..f343ffbb 100644 --- a/sources/reactphysics3d/mathematics/lcp/LCPSolver.h +++ b/sources/reactphysics3d/mathematics/lcp/LCPSolver.h @@ -60,9 +60,9 @@ class LCPSolver { public: LCPSolver(uint maxIterations); // Constructor virtual ~LCPSolver(); // Destructor - virtual void solve(const Matrix** const J_sp, const Matrix** const B_sp, const Body*** const bodyMapping, - std::map bodyNumberMapping, const Vector& b, const Vector& lowLimits, - const Vector& highLimits, Vector& lambda) const=0; // Solve a LCP problem + virtual void solve(Matrix** J_sp, Matrix** B_sp, uint nbConstraints, + uint nbBodies, Body*** const bodyMapping, std::map bodyNumberMapping, + const Vector& b, const Vector& lowLimits, const Vector& highLimits, Vector& lambda) const=0; // Solve a LCP problem void setLambdaInit(const Vector& lambdaInit); // Set the initial lambda vector void setMaxIterations(uint maxIterations); // Set the maximum number of iterations };