Rename the Constraint class into Joint and do not perform collision detection between two sleeping bodies

This commit is contained in:
Daniel Chappuis 2013-09-07 10:57:58 +02:00
parent 1e64a93971
commit d4c7eee175
27 changed files with 242 additions and 207 deletions

View File

@ -32,8 +32,8 @@ using namespace reactphysics3d;
// Constructor // Constructor
Body::Body(bodyindex id) Body::Body(bodyindex id)
: mID(id), mIsAlreadyInIsland(false), mIsAllowedToSleep(true), mIsSleeping(false), : mID(id), mIsAlreadyInIsland(false), mIsAllowedToSleep(true), mIsActive(true),
mSleepTime(0) { mIsSleeping(false), mSleepTime(0) {
} }

View File

@ -53,6 +53,9 @@ class Body {
/// True if the body is allowed to go to sleep for better efficiency /// True if the body is allowed to go to sleep for better efficiency
bool mIsAllowedToSleep; bool mIsAllowedToSleep;
/// True if the body is active
bool mIsActive;
/// True if the body is sleeping (for sleeping technique) /// True if the body is sleeping (for sleeping technique)
bool mIsSleeping; bool mIsSleeping;
@ -95,6 +98,9 @@ class Body {
/// Return whether or not the body is sleeping /// Return whether or not the body is sleeping
bool isSleeping() const; bool isSleeping() const;
/// Return true if the body is active
bool isActive() const;
/// Set the variable to know whether or not the body is sleeping /// Set the variable to know whether or not the body is sleeping
virtual void setIsSleeping(bool isSleeping); virtual void setIsSleeping(bool isSleeping);
@ -147,6 +153,11 @@ inline bool Body::isSleeping() const {
return mIsSleeping; return mIsSleeping;
} }
// Return true if the body is active
inline bool Body::isActive() const {
return mIsActive;
}
// Set the variable to know whether or not the body is sleeping // Set the variable to know whether or not the body is sleeping
inline void Body::setIsSleeping(bool isSleeping) { inline void Body::setIsSleeping(bool isSleeping) {

View File

@ -33,8 +33,8 @@ using namespace reactphysics3d;
// Constructor // Constructor
CollisionBody::CollisionBody(const Transform& transform, CollisionShape *collisionShape, CollisionBody::CollisionBody(const Transform& transform, CollisionShape *collisionShape,
bodyindex id) bodyindex id)
: Body(id), mCollisionShape(collisionShape), mTransform(transform), : Body(id), mCollisionShape(collisionShape), mTransform(transform),
mIsActive(true), mHasMoved(false), mContactManifoldsList(NULL) { mHasMoved(false), mContactManifoldsList(NULL) {
assert(collisionShape); assert(collisionShape);

View File

@ -65,9 +65,6 @@ class CollisionBody : public Body {
/// Interpolation factor used for the state interpolation /// Interpolation factor used for the state interpolation
decimal mInterpolationFactor; decimal mInterpolationFactor;
/// True if the body is active (not sleeping)
bool mIsActive;
/// True if the body is able to move /// True if the body is able to move
bool mIsMotionEnabled; bool mIsMotionEnabled;
@ -116,12 +113,6 @@ class CollisionBody : public Body {
/// Set the collision shape /// Set the collision shape
void setCollisionShape(CollisionShape* collisionShape); void setCollisionShape(CollisionShape* collisionShape);
/// Return true for an active body
bool getIsActive() const;
/// Set the isActive variable
void setIsActive(bool isActive);
/// Return the current position and orientation /// Return the current position and orientation
const Transform& getTransform() const; const Transform& getTransform() const;
@ -185,16 +176,6 @@ inline void CollisionBody::setCollisionShape(CollisionShape* collisionShape) {
mCollisionShape = collisionShape; mCollisionShape = collisionShape;
} }
// Return true if the body is active
inline bool CollisionBody::getIsActive() const {
return mIsActive;
}
// Set the isActive variable
inline void CollisionBody::setIsActive(bool isActive) {
mIsActive = isActive;
}
// Return the interpolated transform for rendering // Return the interpolated transform for rendering
inline Transform CollisionBody::getInterpolatedTransform() const { inline Transform CollisionBody::getInterpolatedTransform() const {
return Transform::interpolateTransforms(mOldTransform, mTransform, mInterpolationFactor); return Transform::interpolateTransforms(mOldTransform, mTransform, mInterpolationFactor);

View File

@ -25,7 +25,7 @@
// Libraries // Libraries
#include "RigidBody.h" #include "RigidBody.h"
#include "constraint/Constraint.h" #include "constraint/Joint.h"
#include "../collision/shapes/CollisionShape.h" #include "../collision/shapes/CollisionShape.h"
// We want to use the ReactPhysics3D namespace // We want to use the ReactPhysics3D namespace
@ -48,7 +48,7 @@ RigidBody::~RigidBody() {
} }
// Remove a joint from the joints list // Remove a joint from the joints list
void RigidBody::removeJointFromJointsList(MemoryAllocator& memoryAllocator, const Constraint* joint) { void RigidBody::removeJointFromJointsList(MemoryAllocator& memoryAllocator, const Joint* joint) {
assert(joint != NULL); assert(joint != NULL);
assert(mJointsList != NULL); assert(mJointsList != NULL);

View File

@ -38,7 +38,7 @@ namespace reactphysics3d {
// Class declarations // Class declarations
struct JointListElement; struct JointListElement;
class Constraint; class Joint;
// Class RigidBody // Class RigidBody
/** /**
@ -103,7 +103,7 @@ class RigidBody : public CollisionBody {
RigidBody& operator=(const RigidBody& body); RigidBody& operator=(const RigidBody& body);
/// Remove a joint from the joints list /// Remove a joint from the joints list
void removeJointFromJointsList(MemoryAllocator& memoryAllocator, const Constraint* joint); void removeJointFromJointsList(MemoryAllocator& memoryAllocator, const Joint* joint);
public : public :
@ -137,18 +137,6 @@ class RigidBody : public CollisionBody {
/// Set the inverse of the mass /// Set the inverse of the mass
void setMassInverse(decimal massInverse); void setMassInverse(decimal massInverse);
/// Return the current external force of the body
Vector3 getExternalForce() const;
/// Set the current external force on the body
void setExternalForce(const Vector3& force);
/// Return the current external torque of the body
Vector3 getExternalTorque() const;
/// Set the current external torque of the body
void setExternalTorque(const Vector3& torque);
/// Return the inverse of the mass of the body /// Return the inverse of the mass of the body
decimal getMassInverse() const; decimal getMassInverse() const;
@ -197,6 +185,15 @@ class RigidBody : public CollisionBody {
/// Set the variable to know whether or not the body is sleeping /// Set the variable to know whether or not the body is sleeping
virtual void setIsSleeping(bool isSleeping); virtual void setIsSleeping(bool isSleeping);
/// Apply an external force to the body at its gravity center.
void applyForceToCenter(const Vector3& force);
/// Apply an external force to the body at a given point (in world-coordinates).
void applyForce(const Vector3& force, const Vector3& point);
/// Apply an external torque to the body.
void applyTorque(const Vector3& torque);
// -------------------- Friendship -------------------- // // -------------------- Friendship -------------------- //
friend class DynamicsWorld; friend class DynamicsWorld;
@ -236,26 +233,6 @@ inline Matrix3x3 RigidBody::getInertiaTensorLocalInverse() const {
return mInertiaTensorLocalInverse; return mInertiaTensorLocalInverse;
} }
// Return the external force on the body
inline Vector3 RigidBody::getExternalForce() const {
return mExternalForce;
}
// Set the external force on the body
inline void RigidBody::setExternalForce(const Vector3& force) {
mExternalForce = force;
}
// Return the current external torque on the body
inline Vector3 RigidBody::getExternalTorque() const {
return mExternalTorque;
}
// Set the current external torque on the body
inline void RigidBody::setExternalTorque(const Vector3& torque) {
mExternalTorque = torque;
}
// Return the inverse of the mass of the body // Return the inverse of the mass of the body
inline decimal RigidBody::getMassInverse() const { inline decimal RigidBody::getMassInverse() const {
return mMassInverse; return mMassInverse;
@ -367,6 +344,62 @@ inline void RigidBody::setIsSleeping(bool isSleeping) {
Body::setIsSleeping(isSleeping); Body::setIsSleeping(isSleeping);
} }
// Apply an external force to the body at its gravity center.
/// If the body is sleeping, calling this method will wake it up. Note that the
/// force will we added to the sum of the applied forces and that this sum will be
/// reset to zero at the end of each call of the DynamicsWorld::update() method.
inline void RigidBody::applyForceToCenter(const Vector3& force) {
// If it is a static body, do not apply any force
if (!mIsMotionEnabled) return;
// Awake the body if it was sleeping
if (mIsSleeping) {
setIsSleeping(false);
}
// Add the force
mExternalForce += force;
}
// Apply an external force to the body at a given point (in world-coordinates).
/// If the point is not at the center of gravity of the body, it will also
/// generate some torque and therefore, change the angular velocity of the body.
/// If the body is sleeping, calling this method will wake it up. Note that the
/// force will we added to the sum of the applied forces and that this sum will be
/// reset to zero at the end of each call of the DynamicsWorld::update() method.
inline void RigidBody::applyForce(const Vector3& force, const Vector3& point) {
// If it is a static body, do not apply any force
if (!mIsMotionEnabled) return;
// Awake the body if it was sleeping
if (mIsSleeping) {
setIsSleeping(false);
}
// Add the force and torque
mExternalForce += force;
mExternalTorque += (point - mTransform.getPosition()).cross(force);
}
// Apply an external torque to the body.
/// If the body is sleeping, calling this method will wake it up. Note that the
/// force will we added to the sum of the applied torques and that this sum will be
/// reset to zero at the end of each call of the DynamicsWorld::update() method.
inline void RigidBody::applyTorque(const Vector3& torque) {
// If it is a static body, do not apply any force
if (!mIsMotionEnabled) return;
// Awake the body if it was sleeping
if (mIsSleeping) {
setIsSleeping(false);
}
// Add the torque
mExternalTorque += torque;
}
} }
#endif #endif

View File

@ -112,6 +112,9 @@ void CollisionDetection::computeNarrowPhase() {
// Check if the two bodies are allowed to collide, otherwise, we do not test for collision // Check if the two bodies are allowed to collide, otherwise, we do not test for collision
if (mNoCollisionPairs.count(pair->getBodiesIndexPair()) > 0) continue; if (mNoCollisionPairs.count(pair->getBodiesIndexPair()) > 0) continue;
// Check if the two bodies are sleeping, if so, we do no test collision between them
if (body1->isSleeping() && body2->isSleeping()) continue;
// Select the narrow phase algorithm to use according to the two collision shapes // Select the narrow phase algorithm to use according to the two collision shapes
NarrowPhaseAlgorithm& narrowPhaseAlgorithm = SelectNarrowPhaseAlgorithm( NarrowPhaseAlgorithm& narrowPhaseAlgorithm = SelectNarrowPhaseAlgorithm(

View File

@ -34,7 +34,7 @@ const decimal BallAndSocketJoint::BETA = decimal(0.2);
// Constructor // Constructor
BallAndSocketJoint::BallAndSocketJoint(const BallAndSocketJointInfo& jointInfo) BallAndSocketJoint::BallAndSocketJoint(const BallAndSocketJointInfo& jointInfo)
: Constraint(jointInfo), mImpulse(Vector3(0, 0, 0)) { : Joint(jointInfo), mImpulse(Vector3(0, 0, 0)) {
// Compute the local-space anchor point for each body // Compute the local-space anchor point for each body
mLocalAnchorPointBody1 = mBody1->getTransform().getInverse() * jointInfo.anchorPointWorldSpace; mLocalAnchorPointBody1 = mBody1->getTransform().getInverse() * jointInfo.anchorPointWorldSpace;

View File

@ -27,7 +27,7 @@
#define REACTPHYSICS3D_BALL_AND_SOCKET_JOINT_H #define REACTPHYSICS3D_BALL_AND_SOCKET_JOINT_H
// Libraries // Libraries
#include "Constraint.h" #include "Joint.h"
#include "../mathematics/mathematics.h" #include "../mathematics/mathematics.h"
namespace reactphysics3d { namespace reactphysics3d {
@ -37,7 +37,7 @@ namespace reactphysics3d {
* This structure is used to gather the information needed to create a ball-and-socket * This structure is used to gather the information needed to create a ball-and-socket
* joint. This structure will be used to create the actual ball-and-socket joint. * joint. This structure will be used to create the actual ball-and-socket joint.
*/ */
struct BallAndSocketJointInfo : public ConstraintInfo { struct BallAndSocketJointInfo : public JointInfo {
public : public :
@ -49,7 +49,7 @@ struct BallAndSocketJointInfo : public ConstraintInfo {
/// Constructor /// Constructor
BallAndSocketJointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2, BallAndSocketJointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2,
const Vector3& initAnchorPointWorldSpace) const Vector3& initAnchorPointWorldSpace)
: ConstraintInfo(rigidBody1, rigidBody2, BALLSOCKETJOINT), : JointInfo(rigidBody1, rigidBody2, BALLSOCKETJOINT),
anchorPointWorldSpace(initAnchorPointWorldSpace) {} anchorPointWorldSpace(initAnchorPointWorldSpace) {}
}; };
@ -58,7 +58,7 @@ struct BallAndSocketJointInfo : public ConstraintInfo {
* This class represents a ball-and-socket joint that allows arbitrary rotation * This class represents a ball-and-socket joint that allows arbitrary rotation
* between two bodies. * between two bodies.
*/ */
class BallAndSocketJoint : public Constraint { class BallAndSocketJoint : public Joint {
private : private :

View File

@ -31,7 +31,8 @@ using namespace std;
// Constructor // Constructor
ContactPoint::ContactPoint(const ContactPointInfo& contactInfo) ContactPoint::ContactPoint(const ContactPointInfo& contactInfo)
: Constraint(contactInfo), mNormal(contactInfo.normal), : mBody1(contactInfo.body1), mBody2(contactInfo.body2),
mNormal(contactInfo.normal),
mPenetrationDepth(contactInfo.penetrationDepth), mPenetrationDepth(contactInfo.penetrationDepth),
mLocalPointOnBody1(contactInfo.localPoint1), mLocalPointOnBody1(contactInfo.localPoint1),
mLocalPointOnBody2(contactInfo.localPoint2), mLocalPointOnBody2(contactInfo.localPoint2),
@ -50,23 +51,3 @@ ContactPoint::ContactPoint(const ContactPointInfo& contactInfo)
ContactPoint::~ContactPoint() { ContactPoint::~ContactPoint() {
} }
// Initialize before solving the constraint
void ContactPoint::initBeforeSolve(const ConstraintSolverData& constraintSolverData) {
}
// Warm start the constraint (apply the previous impulse at the beginning of the step)
void ContactPoint::warmstart(const ConstraintSolverData& constraintSolverData) {
}
// Solve the velocity constraint
void ContactPoint::solveVelocityConstraint(const ConstraintSolverData& constraintSolverData) {
}
// Solve the position constraint
void ContactPoint::solvePositionConstraint(const ConstraintSolverData& constraintSolverData) {
}

View File

@ -27,7 +27,6 @@
#define REACTPHYSICS3D_CONTACT_POINT_H #define REACTPHYSICS3D_CONTACT_POINT_H
// Libraries // Libraries
#include "Constraint.h"
#include "../body/RigidBody.h" #include "../body/RigidBody.h"
#include "../configuration.h" #include "../configuration.h"
#include "../mathematics/mathematics.h" #include "../mathematics/mathematics.h"
@ -43,7 +42,7 @@ namespace reactphysics3d {
* informations are used to compute the contact set for a contact * informations are used to compute the contact set for a contact
* between two bodies. * between two bodies.
*/ */
struct ContactPointInfo : public ConstraintInfo { struct ContactPointInfo {
private: private:
@ -59,6 +58,12 @@ struct ContactPointInfo : public ConstraintInfo {
// -------------------- Attributes -------------------- // // -------------------- Attributes -------------------- //
/// First rigid body of the constraint
RigidBody* body1;
/// Second rigid body of the constraint
RigidBody* body2;
/// Normal vector the the collision contact in world space /// Normal vector the the collision contact in world space
const Vector3 normal; const Vector3 normal;
@ -76,7 +81,7 @@ struct ContactPointInfo : public ConstraintInfo {
/// Constructor /// Constructor
ContactPointInfo(const Vector3& normal, decimal penetrationDepth, ContactPointInfo(const Vector3& normal, decimal penetrationDepth,
const Vector3& localPoint1, const Vector3& localPoint2) const Vector3& localPoint1, const Vector3& localPoint2)
: ConstraintInfo(CONTACT), normal(normal), penetrationDepth(penetrationDepth), : normal(normal), penetrationDepth(penetrationDepth),
localPoint1(localPoint1), localPoint2(localPoint2) { localPoint1(localPoint1), localPoint2(localPoint2) {
} }
@ -85,15 +90,20 @@ struct ContactPointInfo : public ConstraintInfo {
// Class ContactPoint // Class ContactPoint
/** /**
* This class represents a collision contact point between two * This class represents a collision contact point between two
* bodies in the physics engine. The ContactPoint class inherits from * bodies in the physics engine.
* the Constraint class.
*/ */
class ContactPoint : public Constraint { class ContactPoint {
protected : private :
// -------------------- Attributes -------------------- // // -------------------- Attributes -------------------- //
/// First rigid body of the contact
RigidBody* mBody1;
/// Second rigid body of the contact
RigidBody* mBody2;
/// Normal vector of the contact (From body1 toward body2) in world space /// Normal vector of the contact (From body1 toward body2) in world space
const Vector3 mNormal; const Vector3 mNormal;
@ -143,7 +153,13 @@ class ContactPoint : public Constraint {
ContactPoint(const ContactPointInfo& contactInfo); ContactPoint(const ContactPointInfo& contactInfo);
/// Destructor /// Destructor
virtual ~ContactPoint(); ~ContactPoint();
/// Return the reference to the body 1
RigidBody* const getBody1() const;
/// Return the reference to the body 2
RigidBody* const getBody2() const;
/// Return the normal vector of the contact /// Return the normal vector of the contact
Vector3 getNormal() const; Vector3 getNormal() const;
@ -209,21 +225,19 @@ class ContactPoint : public Constraint {
decimal getPenetrationDepth() const; decimal getPenetrationDepth() const;
/// Return the number of bytes used by the contact point /// Return the number of bytes used by the contact point
virtual size_t getSizeInBytes() const; size_t getSizeInBytes() const;
/// Initialize before solving the constraint
virtual void initBeforeSolve(const ConstraintSolverData& constraintSolverData);
/// Warm start the constraint (apply the previous impulse at the beginning of the step)
virtual void warmstart(const ConstraintSolverData& constraintSolverData);
/// Solve the velocity constraint
virtual void solveVelocityConstraint(const ConstraintSolverData& constraintSolverData);
/// Solve the position constraint
virtual void solvePositionConstraint(const ConstraintSolverData& constraintSolverData);
}; };
// Return the reference to the body 1
inline RigidBody* const ContactPoint::getBody1() const {
return mBody1;
}
// Return the reference to the body 2
inline RigidBody* const ContactPoint::getBody2() const {
return mBody2;
}
// Return the normal vector of the contact // Return the normal vector of the contact
inline Vector3 ContactPoint::getNormal() const { inline Vector3 ContactPoint::getNormal() const {
return mNormal; return mNormal;

View File

@ -34,7 +34,7 @@ const decimal FixedJoint::BETA = decimal(0.2);
// Constructor // Constructor
FixedJoint::FixedJoint(const FixedJointInfo& jointInfo) FixedJoint::FixedJoint(const FixedJointInfo& jointInfo)
: Constraint(jointInfo), mImpulseTranslation(0, 0, 0), mImpulseRotation(0, 0, 0) { : Joint(jointInfo), mImpulseTranslation(0, 0, 0), mImpulseRotation(0, 0, 0) {
// Compute the local-space anchor point for each body // Compute the local-space anchor point for each body
const Transform& transform1 = mBody1->getTransform(); const Transform& transform1 = mBody1->getTransform();

View File

@ -27,7 +27,7 @@
#define REACTPHYSICS3D_FIXED_JOINT_H #define REACTPHYSICS3D_FIXED_JOINT_H
// Libraries // Libraries
#include "Constraint.h" #include "Joint.h"
#include "../mathematics/mathematics.h" #include "../mathematics/mathematics.h"
namespace reactphysics3d { namespace reactphysics3d {
@ -37,7 +37,7 @@ namespace reactphysics3d {
* This structure is used to gather the information needed to create a fixed * This structure is used to gather the information needed to create a fixed
* joint. This structure will be used to create the actual fixed joint. * joint. This structure will be used to create the actual fixed joint.
*/ */
struct FixedJointInfo : public ConstraintInfo { struct FixedJointInfo : public JointInfo {
public : public :
@ -49,7 +49,7 @@ struct FixedJointInfo : public ConstraintInfo {
/// Constructor /// Constructor
FixedJointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2, FixedJointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2,
const Vector3& initAnchorPointWorldSpace) const Vector3& initAnchorPointWorldSpace)
: ConstraintInfo(rigidBody1, rigidBody2, FIXEDJOINT), : JointInfo(rigidBody1, rigidBody2, FIXEDJOINT),
anchorPointWorldSpace(initAnchorPointWorldSpace){} anchorPointWorldSpace(initAnchorPointWorldSpace){}
}; };
@ -58,7 +58,7 @@ struct FixedJointInfo : public ConstraintInfo {
* This class represents a fixed joint that is used to forbid any translation or rotation * This class represents a fixed joint that is used to forbid any translation or rotation
* between two bodies. * between two bodies.
*/ */
class FixedJoint : public Constraint { class FixedJoint : public Joint {
private : private :

View File

@ -35,7 +35,7 @@ const decimal HingeJoint::BETA = decimal(0.2);
// Constructor // Constructor
HingeJoint::HingeJoint(const HingeJointInfo& jointInfo) HingeJoint::HingeJoint(const HingeJointInfo& jointInfo)
: Constraint(jointInfo), mImpulseTranslation(0, 0, 0), mImpulseRotation(0, 0), : Joint(jointInfo), mImpulseTranslation(0, 0, 0), mImpulseRotation(0, 0),
mImpulseLowerLimit(0), mImpulseUpperLimit(0), mImpulseMotor(0), mImpulseLowerLimit(0), mImpulseUpperLimit(0), mImpulseMotor(0),
mIsLimitEnabled(jointInfo.isLimitEnabled), mIsMotorEnabled(jointInfo.isMotorEnabled), mIsLimitEnabled(jointInfo.isLimitEnabled), mIsMotorEnabled(jointInfo.isMotorEnabled),
mLowerLimit(jointInfo.minAngleLimit), mUpperLimit(jointInfo.maxAngleLimit), mLowerLimit(jointInfo.minAngleLimit), mUpperLimit(jointInfo.maxAngleLimit),

View File

@ -27,7 +27,7 @@
#define REACTPHYSICS3D_HINGE_JOINT_H #define REACTPHYSICS3D_HINGE_JOINT_H
// Libraries // Libraries
#include "Constraint.h" #include "Joint.h"
#include "../mathematics/mathematics.h" #include "../mathematics/mathematics.h"
namespace reactphysics3d { namespace reactphysics3d {
@ -37,7 +37,7 @@ namespace reactphysics3d {
* This structure is used to gather the information needed to create a hinge joint. * This structure is used to gather the information needed to create a hinge joint.
* This structure will be used to create the actual hinge joint. * This structure will be used to create the actual hinge joint.
*/ */
struct HingeJointInfo : public ConstraintInfo { struct HingeJointInfo : public JointInfo {
public : public :
@ -74,7 +74,7 @@ struct HingeJointInfo : public ConstraintInfo {
HingeJointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2, HingeJointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2,
const Vector3& initAnchorPointWorldSpace, const Vector3& initAnchorPointWorldSpace,
const Vector3& initRotationAxisWorld) const Vector3& initRotationAxisWorld)
: ConstraintInfo(rigidBody1, rigidBody2, HINGEJOINT), : JointInfo(rigidBody1, rigidBody2, HINGEJOINT),
anchorPointWorldSpace(initAnchorPointWorldSpace), anchorPointWorldSpace(initAnchorPointWorldSpace),
rotationAxisWorld(initRotationAxisWorld), isLimitEnabled(false), rotationAxisWorld(initRotationAxisWorld), isLimitEnabled(false),
isMotorEnabled(false), minAngleLimit(-1), maxAngleLimit(1), isMotorEnabled(false), minAngleLimit(-1), maxAngleLimit(1),
@ -85,7 +85,7 @@ struct HingeJointInfo : public ConstraintInfo {
const Vector3& initAnchorPointWorldSpace, const Vector3& initAnchorPointWorldSpace,
const Vector3& initRotationAxisWorld, const Vector3& initRotationAxisWorld,
decimal initMinAngleLimit, decimal initMaxAngleLimit) decimal initMinAngleLimit, decimal initMaxAngleLimit)
: ConstraintInfo(rigidBody1, rigidBody2, HINGEJOINT), : JointInfo(rigidBody1, rigidBody2, HINGEJOINT),
anchorPointWorldSpace(initAnchorPointWorldSpace), anchorPointWorldSpace(initAnchorPointWorldSpace),
rotationAxisWorld(initRotationAxisWorld), isLimitEnabled(true), rotationAxisWorld(initRotationAxisWorld), isLimitEnabled(true),
isMotorEnabled(false), minAngleLimit(initMinAngleLimit), isMotorEnabled(false), minAngleLimit(initMinAngleLimit),
@ -98,7 +98,7 @@ struct HingeJointInfo : public ConstraintInfo {
const Vector3& initRotationAxisWorld, const Vector3& initRotationAxisWorld,
decimal initMinAngleLimit, decimal initMaxAngleLimit, decimal initMinAngleLimit, decimal initMaxAngleLimit,
decimal initMotorSpeed, decimal initMaxMotorTorque) decimal initMotorSpeed, decimal initMaxMotorTorque)
: ConstraintInfo(rigidBody1, rigidBody2, HINGEJOINT), : JointInfo(rigidBody1, rigidBody2, HINGEJOINT),
anchorPointWorldSpace(initAnchorPointWorldSpace), anchorPointWorldSpace(initAnchorPointWorldSpace),
rotationAxisWorld(initRotationAxisWorld), isLimitEnabled(true), rotationAxisWorld(initRotationAxisWorld), isLimitEnabled(true),
isMotorEnabled(false), minAngleLimit(initMinAngleLimit), isMotorEnabled(false), minAngleLimit(initMinAngleLimit),
@ -111,7 +111,7 @@ struct HingeJointInfo : public ConstraintInfo {
* This class represents a hinge joint that allows arbitrary rotation * This class represents a hinge joint that allows arbitrary rotation
* between two bodies around a single axis. * between two bodies around a single axis.
*/ */
class HingeJoint : public Constraint { class HingeJoint : public Joint {
private : private :

View File

@ -24,22 +24,21 @@
********************************************************************************/ ********************************************************************************/
// Libraries // Libraries
#include "Constraint.h" #include "Joint.h"
using namespace reactphysics3d; using namespace reactphysics3d;
// Constructor // Constructor
Constraint::Constraint(const ConstraintInfo& constraintInfo) Joint::Joint(const JointInfo& jointInfo)
:mBody1(constraintInfo.body1), mBody2(constraintInfo.body2), mActive(true), :mBody1(jointInfo.body1), mBody2(jointInfo.body2), mType(jointInfo.type),
mType(constraintInfo.type), mPositionCorrectionTechnique(jointInfo.positionCorrectionTechnique),
mPositionCorrectionTechnique(constraintInfo.positionCorrectionTechnique), mIsCollisionEnabled(jointInfo.isCollisionEnabled), mIsAlreadyInIsland(false) {
mIsCollisionEnabled(constraintInfo.isCollisionEnabled), mIsAlreadyInIsland(false) {
assert(mBody1 != NULL); assert(mBody1 != NULL);
assert(mBody2 != NULL); assert(mBody2 != NULL);
} }
// Destructor // Destructor
Constraint::~Constraint() { Joint::~Joint() {
} }

View File

@ -35,11 +35,11 @@
namespace reactphysics3d { namespace reactphysics3d {
// Enumeration for the type of a constraint // Enumeration for the type of a constraint
enum ConstraintType {CONTACT, BALLSOCKETJOINT, SLIDERJOINT, HINGEJOINT, FIXEDJOINT}; enum JointType {BALLSOCKETJOINT, SLIDERJOINT, HINGEJOINT, FIXEDJOINT};
// Class declarations // Class declarations
struct ConstraintSolverData; struct ConstraintSolverData;
class Constraint; class Joint;
// Structure JointListElement // Structure JointListElement
/** /**
@ -52,7 +52,7 @@ struct JointListElement {
// -------------------- Attributes -------------------- // // -------------------- Attributes -------------------- //
/// Pointer to the actual joint /// Pointer to the actual joint
Constraint* joint; Joint* joint;
/// Next element of the list /// Next element of the list
JointListElement* next; JointListElement* next;
@ -60,32 +60,32 @@ struct JointListElement {
// -------------------- Methods -------------------- // // -------------------- Methods -------------------- //
/// Constructor /// Constructor
JointListElement(Constraint* initJoint, JointListElement* initNext) JointListElement(Joint* initJoint, JointListElement* initNext)
:joint(initJoint), next(initNext){ :joint(initJoint), next(initNext){
} }
}; };
// Structure ConstraintInfo // Structure JointInfo
/** /**
* This structure is used to gather the information needed to create a constraint. * This structure is used to gather the information needed to create a joint.
*/ */
struct ConstraintInfo { struct JointInfo {
public : public :
// -------------------- Attributes -------------------- // // -------------------- Attributes -------------------- //
/// First rigid body of the constraint /// First rigid body of the joint
RigidBody* body1; RigidBody* body1;
/// Second rigid body of the constraint /// Second rigid body of the joint
RigidBody* body2; RigidBody* body2;
/// Type of the constraint /// Type of the joint
ConstraintType type; JointType type;
/// True if the two bodies of the constraint are allowed to collide with each other /// True if the two bodies of the joint are allowed to collide with each other
bool isCollisionEnabled; bool isCollisionEnabled;
/// Position correction technique used for the constraint (used for joints). /// Position correction technique used for the constraint (used for joints).
@ -93,46 +93,41 @@ struct ConstraintInfo {
JointsPositionCorrectionTechnique positionCorrectionTechnique; JointsPositionCorrectionTechnique positionCorrectionTechnique;
/// Constructor /// Constructor
ConstraintInfo(ConstraintType constraintType) JointInfo(JointType constraintType)
: body1(NULL), body2(NULL), type(constraintType), : body1(NULL), body2(NULL), type(constraintType),
positionCorrectionTechnique(NON_LINEAR_GAUSS_SEIDEL), positionCorrectionTechnique(NON_LINEAR_GAUSS_SEIDEL),
isCollisionEnabled(true) {} isCollisionEnabled(true) {}
/// Constructor /// Constructor
ConstraintInfo(RigidBody* rigidBody1, RigidBody* rigidBody2, ConstraintType constraintType) JointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2, JointType constraintType)
: body1(rigidBody1), body2(rigidBody2), type(constraintType), : body1(rigidBody1), body2(rigidBody2), type(constraintType),
positionCorrectionTechnique(NON_LINEAR_GAUSS_SEIDEL), positionCorrectionTechnique(NON_LINEAR_GAUSS_SEIDEL),
isCollisionEnabled(true) { isCollisionEnabled(true) {
} }
/// Destructor /// Destructor
virtual ~ConstraintInfo() {} virtual ~JointInfo() {}
}; };
// Class Constraint // Class Joint
/** /**
* This abstract class represents a constraint in the physics engine. * This abstract class represents a joint between two bodies.
* A constraint can be a collision contact point or a joint for
* instance.
*/ */
class Constraint { class Joint {
protected : protected :
// -------------------- Attributes -------------------- // // -------------------- Attributes -------------------- //
/// Pointer to the first body of the constraint /// Pointer to the first body of the joint
RigidBody* const mBody1; RigidBody* const mBody1;
/// Pointer to the second body of the constraint /// Pointer to the second body of the joint
RigidBody* const mBody2; RigidBody* const mBody2;
/// True if the constraint is active /// Type of the joint
bool mActive; const JointType mType;
/// Type of the constraint
const ConstraintType mType;
/// Body 1 index in the velocity array to solve the constraint /// Body 1 index in the velocity array to solve the constraint
uint mIndexBody1; uint mIndexBody1;
@ -152,20 +147,20 @@ class Constraint {
// -------------------- Methods -------------------- // // -------------------- Methods -------------------- //
/// Private copy-constructor /// Private copy-constructor
Constraint(const Constraint& constraint); Joint(const Joint& constraint);
/// Private assignment operator /// Private assignment operator
Constraint& operator=(const Constraint& constraint); Joint& operator=(const Joint& constraint);
public : public :
// -------------------- Methods -------------------- // // -------------------- Methods -------------------- //
/// Constructor /// Constructor
Constraint(const ConstraintInfo& constraintInfo); Joint(const JointInfo& jointInfo);
/// Destructor /// Destructor
virtual ~Constraint(); virtual ~Joint();
/// Return the reference to the body 1 /// Return the reference to the body 1
RigidBody* const getBody1() const; RigidBody* const getBody1() const;
@ -177,21 +172,21 @@ class Constraint {
bool isActive() const; bool isActive() const;
/// Return the type of the constraint /// Return the type of the constraint
ConstraintType getType() const; JointType getType() const;
/// Return true if the collision between the two bodies of the constraint is enabled /// Return true if the collision between the two bodies of the joint is enabled
bool isCollisionEnabled() const; bool isCollisionEnabled() const;
/// Return true if the joint has already been added into an island /// Return true if the joint has already been added into an island
bool isAlreadyInIsland() const; bool isAlreadyInIsland() const;
/// Return the number of bytes used by the constraint /// Return the number of bytes used by the joint
virtual size_t getSizeInBytes() const = 0; virtual size_t getSizeInBytes() const = 0;
/// Initialize before solving the constraint /// Initialize before solving the joint
virtual void initBeforeSolve(const ConstraintSolverData& constraintSolverData) = 0; virtual void initBeforeSolve(const ConstraintSolverData& constraintSolverData) = 0;
/// Warm start the constraint (apply the previous impulse at the beginning of the step) /// Warm start the joint (apply the previous impulse at the beginning of the step)
virtual void warmstart(const ConstraintSolverData& constraintSolverData) = 0; virtual void warmstart(const ConstraintSolverData& constraintSolverData) = 0;
/// Solve the velocity constraint /// Solve the velocity constraint
@ -207,32 +202,32 @@ class Constraint {
}; };
// Return the reference to the body 1 // Return the reference to the body 1
inline RigidBody* const Constraint::getBody1() const { inline RigidBody* const Joint::getBody1() const {
return mBody1; return mBody1;
} }
// Return the reference to the body 2 // Return the reference to the body 2
inline RigidBody* const Constraint::getBody2() const { inline RigidBody* const Joint::getBody2() const {
return mBody2; return mBody2;
} }
// Return true if the constraint is active // Return true if the joint is active
inline bool Constraint::isActive() const { inline bool Joint::isActive() const {
return mActive; return (mBody1->isActive() && mBody2->isActive());
} }
// Return the type of the constraint // Return the type of the joint
inline ConstraintType Constraint::getType() const { inline JointType Joint::getType() const {
return mType; return mType;
} }
// Return true if the collision between the two bodies of the constraint is enabled // Return true if the collision between the two bodies of the joint is enabled
inline bool Constraint::isCollisionEnabled() const { inline bool Joint::isCollisionEnabled() const {
return mIsCollisionEnabled; return mIsCollisionEnabled;
} }
// Return true if the joint has already been added into an island // Return true if the joint has already been added into an island
inline bool Constraint::isAlreadyInIsland() const { inline bool Joint::isAlreadyInIsland() const {
return mIsAlreadyInIsland; return mIsAlreadyInIsland;
} }

View File

@ -33,7 +33,7 @@ const decimal SliderJoint::BETA = decimal(0.2);
// Constructor // Constructor
SliderJoint::SliderJoint(const SliderJointInfo& jointInfo) SliderJoint::SliderJoint(const SliderJointInfo& jointInfo)
: Constraint(jointInfo), mImpulseTranslation(0, 0), mImpulseRotation(0, 0, 0), : Joint(jointInfo), mImpulseTranslation(0, 0), mImpulseRotation(0, 0, 0),
mImpulseLowerLimit(0), mImpulseUpperLimit(0), mImpulseMotor(0), mImpulseLowerLimit(0), mImpulseUpperLimit(0), mImpulseMotor(0),
mIsLimitEnabled(jointInfo.isLimitEnabled), mIsMotorEnabled(jointInfo.isMotorEnabled), mIsLimitEnabled(jointInfo.isLimitEnabled), mIsMotorEnabled(jointInfo.isMotorEnabled),
mLowerLimit(jointInfo.minTranslationLimit), mLowerLimit(jointInfo.minTranslationLimit),

View File

@ -37,7 +37,7 @@ namespace reactphysics3d {
* This structure is used to gather the information needed to create a slider * This structure is used to gather the information needed to create a slider
* joint. This structure will be used to create the actual slider joint. * joint. This structure will be used to create the actual slider joint.
*/ */
struct SliderJointInfo : public ConstraintInfo { struct SliderJointInfo : public JointInfo {
public : public :
@ -71,7 +71,7 @@ struct SliderJointInfo : public ConstraintInfo {
SliderJointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2, SliderJointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2,
const Vector3& initAnchorPointWorldSpace, const Vector3& initAnchorPointWorldSpace,
const Vector3& initSliderAxisWorldSpace) const Vector3& initSliderAxisWorldSpace)
: ConstraintInfo(rigidBody1, rigidBody2, SLIDERJOINT), : JointInfo(rigidBody1, rigidBody2, SLIDERJOINT),
anchorPointWorldSpace(initAnchorPointWorldSpace), anchorPointWorldSpace(initAnchorPointWorldSpace),
sliderAxisWorldSpace(initSliderAxisWorldSpace), sliderAxisWorldSpace(initSliderAxisWorldSpace),
isLimitEnabled(false), isMotorEnabled(false), minTranslationLimit(-1.0), isLimitEnabled(false), isMotorEnabled(false), minTranslationLimit(-1.0),
@ -82,7 +82,7 @@ struct SliderJointInfo : public ConstraintInfo {
const Vector3& initAnchorPointWorldSpace, const Vector3& initAnchorPointWorldSpace,
const Vector3& initSliderAxisWorldSpace, const Vector3& initSliderAxisWorldSpace,
decimal initMinTranslationLimit, decimal initMaxTranslationLimit) decimal initMinTranslationLimit, decimal initMaxTranslationLimit)
: ConstraintInfo(rigidBody1, rigidBody2, SLIDERJOINT), : JointInfo(rigidBody1, rigidBody2, SLIDERJOINT),
anchorPointWorldSpace(initAnchorPointWorldSpace), anchorPointWorldSpace(initAnchorPointWorldSpace),
sliderAxisWorldSpace(initSliderAxisWorldSpace), sliderAxisWorldSpace(initSliderAxisWorldSpace),
isLimitEnabled(true), isMotorEnabled(false), isLimitEnabled(true), isMotorEnabled(false),
@ -96,7 +96,7 @@ struct SliderJointInfo : public ConstraintInfo {
const Vector3& initSliderAxisWorldSpace, const Vector3& initSliderAxisWorldSpace,
decimal initMinTranslationLimit, decimal initMaxTranslationLimit, decimal initMinTranslationLimit, decimal initMaxTranslationLimit,
decimal initMotorSpeed, decimal initMaxMotorForce) decimal initMotorSpeed, decimal initMaxMotorForce)
: ConstraintInfo(rigidBody1, rigidBody2, SLIDERJOINT), : JointInfo(rigidBody1, rigidBody2, SLIDERJOINT),
anchorPointWorldSpace(initAnchorPointWorldSpace), anchorPointWorldSpace(initAnchorPointWorldSpace),
sliderAxisWorldSpace(initSliderAxisWorldSpace), sliderAxisWorldSpace(initSliderAxisWorldSpace),
isLimitEnabled(true), isMotorEnabled(true), isLimitEnabled(true), isMotorEnabled(true),
@ -109,7 +109,7 @@ struct SliderJointInfo : public ConstraintInfo {
/** /**
* This class represents a slider joint. * This class represents a slider joint.
*/ */
class SliderJoint : public Constraint { class SliderJoint : public Joint {
private : private :

View File

@ -36,7 +36,7 @@
#include "../body/CollisionBody.h" #include "../body/CollisionBody.h"
#include "OverlappingPair.h" #include "OverlappingPair.h"
#include "../collision/CollisionDetection.h" #include "../collision/CollisionDetection.h"
#include "../constraint/Constraint.h" #include "../constraint/Joint.h"
#include "../constraint/ContactPoint.h" #include "../constraint/ContactPoint.h"
#include "../memory/MemoryAllocator.h" #include "../memory/MemoryAllocator.h"

View File

@ -65,7 +65,7 @@ void ConstraintSolver::initializeForIsland(decimal dt, Island* island) {
mConstraintSolverData.isWarmStartingActive = mIsWarmStartingActive; mConstraintSolverData.isWarmStartingActive = mIsWarmStartingActive;
// For each joint of the island // For each joint of the island
Constraint** joints = island->getJoints(); Joint** joints = island->getJoints();
for (uint i=0; i<island->getNbJoints(); i++) { for (uint i=0; i<island->getNbJoints(); i++) {
// Initialize the constraint before solving it // Initialize the constraint before solving it
@ -87,7 +87,7 @@ void ConstraintSolver::solveVelocityConstraints(Island* island) {
assert(island->getNbJoints() > 0); assert(island->getNbJoints() > 0);
// For each joint of the island // For each joint of the island
Constraint** joints = island->getJoints(); Joint** joints = island->getJoints();
for (uint i=0; i<island->getNbJoints(); i++) { for (uint i=0; i<island->getNbJoints(); i++) {
// Solve the constraint // Solve the constraint
@ -104,7 +104,7 @@ void ConstraintSolver::solvePositionConstraints(Island* island) {
assert(island->getNbJoints() > 0); assert(island->getNbJoints() > 0);
// For each joint of the island // For each joint of the island
Constraint** joints = island->getJoints(); Joint** joints = island->getJoints();
for (uint i=0; i < island->getNbJoints(); i++) { for (uint i=0; i < island->getNbJoints(); i++) {
// Solve the constraint // Solve the constraint

View File

@ -29,7 +29,7 @@
// Libraries // Libraries
#include "../configuration.h" #include "../configuration.h"
#include "mathematics/mathematics.h" #include "mathematics/mathematics.h"
#include "../constraint/Constraint.h" #include "../constraint/Joint.h"
#include "Island.h" #include "Island.h"
#include <map> #include <map>
#include <set> #include <set>

View File

@ -29,7 +29,7 @@
// Libraries // Libraries
#include "../constraint/ContactPoint.h" #include "../constraint/ContactPoint.h"
#include "../configuration.h" #include "../configuration.h"
#include "../constraint/Constraint.h" #include "../constraint/Joint.h"
#include "ContactManifold.h" #include "ContactManifold.h"
#include "Island.h" #include "Island.h"
#include "Impulse.h" #include "Impulse.h"

View File

@ -147,6 +147,9 @@ void DynamicsWorld::update() {
// Update the AABBs of the bodies // Update the AABBs of the bodies
updateRigidBodiesAABB(); updateRigidBodiesAABB();
// Reset the external force and torque applied to the bodies
resetBodiesForceAndTorque();
} }
// Compute and set the interpolation factor to all the bodies // Compute and set the interpolation factor to all the bodies
@ -315,10 +318,10 @@ void DynamicsWorld::integrateRigidBodiesVelocities() {
// Integrate the external force to get the new velocity of the body // Integrate the external force to get the new velocity of the body
mConstrainedLinearVelocities[indexBody] = bodies[b]->getLinearVelocity() + mConstrainedLinearVelocities[indexBody] = bodies[b]->getLinearVelocity() +
dt * bodies[b]->getMassInverse() * bodies[b]->getExternalForce(); dt * bodies[b]->getMassInverse() * bodies[b]->mExternalForce;
mConstrainedAngularVelocities[indexBody] = bodies[b]->getAngularVelocity() + mConstrainedAngularVelocities[indexBody] = bodies[b]->getAngularVelocity() +
dt * bodies[b]->getInertiaTensorInverseWorld() * dt * bodies[b]->getInertiaTensorInverseWorld() *
bodies[b]->getExternalTorque(); bodies[b]->mExternalTorque;
// If the gravity has to be applied to this rigid body // If the gravity has to be applied to this rigid body
if (bodies[b]->isGravityEnabled() && mIsGravityEnabled) { if (bodies[b]->isGravityEnabled() && mIsGravityEnabled) {
@ -527,7 +530,7 @@ void DynamicsWorld::destroyRigidBody(RigidBody* rigidBody) {
// Destroy all the joints in which the rigid body to be destroyed is involved // Destroy all the joints in which the rigid body to be destroyed is involved
// TODO : Iterate on the mJointList of the rigid body instead over all the joints of the world // TODO : Iterate on the mJointList of the rigid body instead over all the joints of the world
bodyindex idToRemove = rigidBody->getID(); bodyindex idToRemove = rigidBody->getID();
for (std::set<Constraint*>::iterator it = mJoints.begin(); it != mJoints.end(); ++it) { for (std::set<Joint*>::iterator it = mJoints.begin(); it != mJoints.end(); ++it) {
if ((*it)->getBody1()->getID() == idToRemove || (*it)->getBody2()->getID() == idToRemove) { if ((*it)->getBody1()->getID() == idToRemove || (*it)->getBody2()->getID() == idToRemove) {
destroyJoint(*it); destroyJoint(*it);
} }
@ -548,9 +551,9 @@ void DynamicsWorld::destroyRigidBody(RigidBody* rigidBody) {
} }
// Create a joint between two bodies in the world and return a pointer to the new joint // Create a joint between two bodies in the world and return a pointer to the new joint
Constraint* DynamicsWorld::createJoint(const ConstraintInfo& jointInfo) { Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) {
Constraint* newJoint = NULL; Joint* newJoint = NULL;
// Allocate memory to create the new joint // Allocate memory to create the new joint
switch(jointInfo.type) { switch(jointInfo.type) {
@ -617,7 +620,7 @@ Constraint* DynamicsWorld::createJoint(const ConstraintInfo& jointInfo) {
} }
// Destroy a joint // Destroy a joint
void DynamicsWorld::destroyJoint(Constraint* joint) { void DynamicsWorld::destroyJoint(Joint* joint) {
assert(joint != NULL); assert(joint != NULL);
@ -642,14 +645,14 @@ void DynamicsWorld::destroyJoint(Constraint* joint) {
size_t nbBytes = joint->getSizeInBytes(); size_t nbBytes = joint->getSizeInBytes();
// Call the destructor of the joint // Call the destructor of the joint
joint->Constraint::~Constraint(); joint->Joint::~Joint();
// Release the allocated memory // Release the allocated memory
mMemoryAllocator.release(joint, nbBytes); mMemoryAllocator.release(joint, nbBytes);
} }
// Add the joint to the list of joints of the two bodies involved in the joint // Add the joint to the list of joints of the two bodies involved in the joint
void DynamicsWorld::addJointToBody(Constraint* joint) { void DynamicsWorld::addJointToBody(Joint* joint) {
assert(joint != NULL); assert(joint != NULL);
@ -741,7 +744,7 @@ void DynamicsWorld::computeIslands() {
it != mContactManifolds.end(); ++it) { it != mContactManifolds.end(); ++it) {
(*it)->mIsAlreadyInIsland = false; (*it)->mIsAlreadyInIsland = false;
} }
for (std::set<Constraint*>::iterator it = mJoints.begin(); it != mJoints.end(); ++it) { for (std::set<Joint*>::iterator it = mJoints.begin(); it != mJoints.end(); ++it) {
(*it)->mIsAlreadyInIsland = false; (*it)->mIsAlreadyInIsland = false;
} }
@ -763,8 +766,8 @@ void DynamicsWorld::computeIslands() {
// TODO : When we will use STATIC bodies, we will need to take care of this case here // TODO : When we will use STATIC bodies, we will need to take care of this case here
if (!body->getIsMotionEnabled()) continue; if (!body->getIsMotionEnabled()) continue;
// If the body is sleeping, we go to the next body // If the body is sleeping or inactive, we go to the next body
if (body->isSleeping()) continue; if (body->isSleeping() || !body->isActive()) continue;
// Reset the stack of bodies to visit // Reset the stack of bodies to visit
uint stackIndex = 0; uint stackIndex = 0;
@ -784,6 +787,7 @@ void DynamicsWorld::computeIslands() {
// Get the next body to visit from the stack // Get the next body to visit from the stack
stackIndex--; stackIndex--;
RigidBody* bodyToVisit = stackBodiesToVisit[stackIndex]; RigidBody* bodyToVisit = stackBodiesToVisit[stackIndex];
assert(bodyToVisit->isActive());
// Awake the body if it is slepping // Awake the body if it is slepping
bodyToVisit->setIsSleeping(false); bodyToVisit->setIsSleeping(false);
@ -828,7 +832,7 @@ void DynamicsWorld::computeIslands() {
for (jointElement = bodyToVisit->mJointsList; jointElement != NULL; for (jointElement = bodyToVisit->mJointsList; jointElement != NULL;
jointElement = jointElement->next) { jointElement = jointElement->next) {
Constraint* joint = jointElement->joint; Joint* joint = jointElement->joint;
// Check if the current joint has already been added into an island // Check if the current joint has already been added into an island
if (joint->isAlreadyInIsland()) continue; if (joint->isAlreadyInIsland()) continue;

View File

@ -77,7 +77,7 @@ class DynamicsWorld : public CollisionWorld {
std::vector<ContactManifold*> mContactManifolds; std::vector<ContactManifold*> mContactManifolds;
/// All the joints of the world /// All the joints of the world
std::set<Constraint*> mJoints; std::set<Joint*> mJoints;
/// Gravity vector of the world /// Gravity vector of the world
Vector3 mGravity; Vector3 mGravity;
@ -144,6 +144,9 @@ class DynamicsWorld : public CollisionWorld {
/// Update the AABBs of the bodies /// Update the AABBs of the bodies
void updateRigidBodiesAABB(); void updateRigidBodiesAABB();
/// Reset the external force and torque applied to the bodies
void resetBodiesForceAndTorque();
/// Update the position and orientation of a body /// Update the position and orientation of a body
void updatePositionAndOrientationOfBody(RigidBody* body, Vector3 newLinVelocity, void updatePositionAndOrientationOfBody(RigidBody* body, Vector3 newLinVelocity,
Vector3 newAngVelocity); Vector3 newAngVelocity);
@ -232,13 +235,13 @@ public :
void destroyRigidBody(RigidBody* rigidBody); void destroyRigidBody(RigidBody* rigidBody);
/// Create a joint between two bodies in the world and return a pointer to the new joint /// Create a joint between two bodies in the world and return a pointer to the new joint
Constraint* createJoint(const ConstraintInfo& jointInfo); Joint* createJoint(const JointInfo& jointInfo);
/// Destroy a joint /// Destroy a joint
void destroyJoint(Constraint* joint); void destroyJoint(Joint* joint);
/// Add the joint to the list of joints of the two bodies involved in the joint /// Add the joint to the list of joints of the two bodies involved in the joint
void addJointToBody(Constraint* joint); void addJointToBody(Joint* joint);
//// Add a contact manifold to the linked list of contact manifolds of the two bodies involed //// Add a contact manifold to the linked list of contact manifolds of the two bodies involed
//// in the corresponding contact. //// in the corresponding contact.
@ -309,6 +312,17 @@ public :
uint getNbIslands() const {return mNbIslands;} uint getNbIslands() const {return mNbIslands;}
}; };
// Reset the external force and torque applied to the bodies
inline void DynamicsWorld::resetBodiesForceAndTorque() {
// For each body of the world
std::set<RigidBody*>::iterator it;
for (it = mRigidBodies.begin(); it != mRigidBodies.end(); ++it) {
(*it)->mExternalForce.setToZero();
(*it)->mExternalTorque.setToZero();
}
}
// Start the physics simulation // Start the physics simulation
inline void DynamicsWorld::start() { inline void DynamicsWorld::start() {
mTimer.start(); mTimer.start();

View File

@ -40,8 +40,8 @@ Island::Island(uint id, uint nbMaxBodies, uint nbMaxContactManifolds, uint nbMax
mNbAllocatedBytesContactManifolds = sizeof(ContactManifold*) * nbMaxContactManifolds; mNbAllocatedBytesContactManifolds = sizeof(ContactManifold*) * nbMaxContactManifolds;
mContactManifolds = (ContactManifold**) mMemoryAllocator.allocate( mContactManifolds = (ContactManifold**) mMemoryAllocator.allocate(
mNbAllocatedBytesContactManifolds); mNbAllocatedBytesContactManifolds);
mNbAllocatedBytesJoints = sizeof(Constraint*) * nbMaxJoints; mNbAllocatedBytesJoints = sizeof(Joint*) * nbMaxJoints;
mJoints = (Constraint**) mMemoryAllocator.allocate(mNbAllocatedBytesJoints); mJoints = (Joint**) mMemoryAllocator.allocate(mNbAllocatedBytesJoints);
} }
// Destructor // Destructor

View File

@ -29,7 +29,7 @@
// Libraries // Libraries
#include "../memory/MemoryAllocator.h" #include "../memory/MemoryAllocator.h"
#include "../body/RigidBody.h" #include "../body/RigidBody.h"
#include "../constraint/Constraint.h" #include "../constraint/Joint.h"
#include "ContactManifold.h" #include "ContactManifold.h"
namespace reactphysics3d { namespace reactphysics3d {
@ -55,7 +55,7 @@ class Island {
ContactManifold** mContactManifolds; ContactManifold** mContactManifolds;
/// Array with all the joints between bodies of the island /// Array with all the joints between bodies of the island
Constraint** mJoints; Joint** mJoints;
/// Current number of bodies in the island /// Current number of bodies in the island
uint mNbBodies; uint mNbBodies;
@ -104,7 +104,7 @@ class Island {
void addContactManifold(ContactManifold* contactManifold); void addContactManifold(ContactManifold* contactManifold);
/// Add a joint into the island /// Add a joint into the island
void addJoint(Constraint* joint); void addJoint(Joint* joint);
/// Return the number of bodies in the island /// Return the number of bodies in the island
uint getNbBodies() const; uint getNbBodies() const;
@ -122,7 +122,7 @@ class Island {
ContactManifold** getContactManifold(); ContactManifold** getContactManifold();
/// Return a pointer to the array of joints /// Return a pointer to the array of joints
Constraint** getJoints(); Joint** getJoints();
// TODO : REMOVE THIS // TODO : REMOVE THIS
uint getID() const {return mID;} uint getID() const {return mID;}
@ -146,7 +146,7 @@ inline void Island::addContactManifold(ContactManifold* contactManifold) {
} }
// Add a joint into the island // Add a joint into the island
inline void Island::addJoint(Constraint* joint) { inline void Island::addJoint(Joint* joint) {
mJoints[mNbJoints] = joint; mJoints[mNbJoints] = joint;
mNbJoints++; mNbJoints++;
} }
@ -177,7 +177,7 @@ inline ContactManifold** Island::getContactManifold() {
} }
// Return a pointer to the array of joints // Return a pointer to the array of joints
inline Constraint** Island::getJoints() { inline Joint** Island::getJoints() {
return mJoints; return mJoints;
} }