diff --git a/documentation/API/Doxyfile b/documentation/API/Doxyfile index 5373c5f0..c257ecd7 100644 --- a/documentation/API/Doxyfile +++ b/documentation/API/Doxyfile @@ -32,7 +32,7 @@ PROJECT_NAME = "ReactPhysics3D" # This could be handy for archiving the generated documentation or # if some version control system is used. -PROJECT_NUMBER = "0.4.0" +PROJECT_NUMBER = "0.5.0" # Using the PROJECT_BRIEF tag one can provide an optional one line description # for a project that appears at the top of each page and should give viewer diff --git a/src/body/Body.cpp b/src/body/Body.cpp index 297afa7e..3dc57437 100644 --- a/src/body/Body.cpp +++ b/src/body/Body.cpp @@ -31,6 +31,9 @@ using namespace reactphysics3d; // Constructor +/** + * @param id ID of the new body + */ Body::Body(bodyindex id) : mID(id), mIsAlreadyInIsland(false), mIsAllowedToSleep(true), mIsActive(true), mIsSleeping(false), mSleepTime(0), mUserData(NULL) { diff --git a/src/body/Body.h b/src/body/Body.h index a4dc54f6..2dc1e455 100644 --- a/src/body/Body.h +++ b/src/body/Body.h @@ -37,7 +37,9 @@ namespace reactphysics3d { // TODO : Make this class abstract // Class Body /** - * This class is an abstract class to represent a body of the physics engine. + * This class to represent a body of the physics engine. You should not + * instantiante this class but instantiate the CollisionBody or RigidBody + * classes instead. */ class Body { @@ -81,6 +83,9 @@ class Body { /// Private assignment operator Body& operator=(const Body& body); + /// Set the variable to know whether or not the body is sleeping + virtual void setIsSleeping(bool isSleeping); + public : // -------------------- Methods -------------------- // @@ -91,7 +96,7 @@ class Body { /// Destructor virtual ~Body(); - /// Return the id of the body + /// Return the ID of the body bodyindex getID() const; /// Return whether or not the body is allowed to sleep @@ -109,9 +114,6 @@ class Body { /// Set whether or not the body is active virtual void setIsActive(bool isActive); - /// Set the variable to know whether or not the body is sleeping - virtual void setIsSleeping(bool isSleeping); - /// Return a pointer to the user data attached to this body void* getUserData() const; @@ -136,16 +138,25 @@ class Body { }; // Return the id of the body +/** + * @return The ID of the body + */ inline bodyindex Body::getID() const { return mID; } // Return whether or not the body is allowed to sleep +/** + * @return True if the body is allowed to sleep and false otherwise + */ inline bool Body::isAllowedToSleep() const { return mIsAllowedToSleep; } // Set whether or not the body is allowed to go to sleep +/** + * @param isAllowedToSleep True if the body is allowed to sleep + */ inline void Body::setIsAllowedToSleep(bool isAllowedToSleep) { mIsAllowedToSleep = isAllowedToSleep; @@ -153,16 +164,25 @@ inline void Body::setIsAllowedToSleep(bool isAllowedToSleep) { } // Return whether or not the body is sleeping +/** + * @return True if the body is currently sleeping and false otherwise + */ inline bool Body::isSleeping() const { return mIsSleeping; } // Return true if the body is active +/** + * @return True if the body currently active and false otherwise + */ inline bool Body::isActive() const { return mIsActive; } // Set whether or not the body is active +/** + * @param isActive True if you want to activate the body + */ inline void Body::setIsActive(bool isActive) { mIsActive = isActive; } @@ -183,11 +203,17 @@ inline void Body::setIsSleeping(bool isSleeping) { } // Return a pointer to the user data attached to this body +/** + * @return A pointer to the user data you have attached to the body + */ inline void* Body::getUserData() const { return mUserData; } // Attach user data to this body +/** + * @param userData A pointer to the user data you want to attach to the body + */ inline void Body::setUserData(void* userData) { mUserData = userData; } diff --git a/src/body/CollisionBody.cpp b/src/body/CollisionBody.cpp index 2b8af243..fda23f22 100644 --- a/src/body/CollisionBody.cpp +++ b/src/body/CollisionBody.cpp @@ -32,6 +32,11 @@ using namespace reactphysics3d; // Constructor +/** + * @param transform The transform of the body + * @param world The physics world where the body is created + * @param id ID of the body + */ CollisionBody::CollisionBody(const Transform& transform, CollisionWorld& world, bodyindex id) : Body(id), mType(DYNAMIC), mTransform(transform), mProxyCollisionShapes(NULL), mNbCollisionShapes(0), mContactManifoldsList(NULL), mWorld(world) { @@ -51,15 +56,20 @@ CollisionBody::~CollisionBody() { } // Add a collision shape to the body. -/// This methods will create a copy of the collision shape you provided inside the world and -/// return a pointer to the actual collision shape in the world. You can use this pointer to -/// remove the collision from the body. Note that when the body is destroyed, all the collision -/// shapes will also be destroyed automatically. Because an internal copy of the collision shape -/// you provided is performed, you can delete it right after calling this method. The second -/// parameter is the transformation that transform the local-space of the collision shape into -/// the local-space of the body. -/// This method will return a pointer to the proxy collision shape that links the body with -/// the collision shape you have added. +/// When you add a collision shape to the body, an internal copy of this +/// collision shape will be created internally. Therefore, you can delete it +/// right after calling this method or use it later to add it to another body. +/// This method will return a pointer to a new proxy shape. A proxy shape is +/// an object that links a collision shape and a given body. You can use the +/// returned proxy shape to get and set information about the corresponding +/// collision shape for that body. +/** + * @param collisionShape The collision shape you want to add to the body + * @param transform The transformation of the collision shape that transforms the + * local-space of the collision shape into the local-space of the body + * @return A pointer to the proxy shape that has been created to link the body to + * the new collision shape you have added. + */ ProxyShape* CollisionBody::addCollisionShape(const CollisionShape& collisionShape, const Transform& transform) { @@ -94,6 +104,12 @@ ProxyShape* CollisionBody::addCollisionShape(const CollisionShape& collisionShap } // Remove a collision shape from the body +/// To remove a collision shape, you need to specify the pointer to the proxy +/// shape that has been returned when you have added the collision shape to the +/// body +/** + * @param proxyShape The pointer of the proxy shape you want to remove + */ void CollisionBody::removeCollisionShape(const ProxyShape* proxyShape) { ProxyShape* current = mProxyCollisionShapes; @@ -201,6 +217,9 @@ void CollisionBody::updateBroadPhaseState() const { } // Set whether or not the body is active +/** + * @param isActive True if you want to activate the body + */ void CollisionBody::setIsActive(bool isActive) { // If the state does not change @@ -268,6 +287,11 @@ int CollisionBody::resetIsAlreadyInIslandAndCountManifolds() { } // Return true if a point is inside the collision body +/// This method returns true if a point is inside any collision shape of the body +/** + * @param worldPoint The point to test (in world-space coordinates) + * @return True if the point is inside the body + */ bool CollisionBody::testPointInside(const Vector3& worldPoint) const { // For each collision shape of the body @@ -282,6 +306,12 @@ bool CollisionBody::testPointInside(const Vector3& worldPoint) const { // Raycast method with feedback information /// The method returns the closest hit among all the collision shapes of the body +/** +* @param ray The ray used to raycast agains the body +* @param[out] raycastInfo Structure that contains the result of the raycasting +* (valid only if the method returned true) +* @return True if the ray hit the body and false otherwise +*/ bool CollisionBody::raycast(const Ray& ray, RaycastInfo& raycastInfo) { // If the body is not active, it cannot be hit by rays @@ -304,6 +334,9 @@ bool CollisionBody::raycast(const Ray& ray, RaycastInfo& raycastInfo) { } // Compute and return the AABB of the body by merging all proxy shapes AABBs +/** +* @return The axis-aligned bounding box (AABB) of the body in world-space coordinates +*/ AABB CollisionBody::getAABB() const { AABB bodyAABB; diff --git a/src/body/CollisionBody.h b/src/body/CollisionBody.h index 7a656b96..2f8db75c 100644 --- a/src/body/CollisionBody.h +++ b/src/body/CollisionBody.h @@ -118,6 +118,9 @@ class CollisionBody : public Body { /// Reset the mIsAlreadyInIsland variable of the body and contact manifolds int resetIsAlreadyInIslandAndCountManifolds(); + /// Set the interpolation factor of the body + void setInterpolationFactor(decimal factor); + public : // -------------------- Methods -------------------- // @@ -153,15 +156,6 @@ class CollisionBody : public Body { /// Return the interpolated transform for rendering Transform getInterpolatedTransform() const; - /// Set the interpolation factor of the body - void setInterpolationFactor(decimal factor); - - /// Return true if the body can collide with others bodies - bool isCollisionEnabled() const; - - /// Enable/disable the collision with this body - void enableCollision(bool isCollisionEnabled); - /// Return the first element of the linked list of contact manifolds involving this body const ContactManifoldListElement* getContactManifoldsList() const; @@ -203,11 +197,26 @@ class CollisionBody : public Body { }; // Return the type of the body +/** + * @return the type of the body (STATIC, KINEMATIC, DYNAMIC) + */ inline BodyType CollisionBody::getType() const { return mType; } // Set the type of the body +/// The type of the body can either STATIC, KINEMATIC or DYNAMIC as described bellow: +/// STATIC : A static body has infinite mass, zero velocity but the position can be +/// changed manually. A static body does not collide with other static or kinematic bodies. +/// KINEMATIC : A kinematic body has infinite mass, the velocity can be changed manually and its +/// position is computed by the physics engine. A kinematic body does not collide with +/// other static or kinematic bodies. +/// DYNAMIC : A dynamic body has non-zero mass, non-zero velocity determined by forces and its +/// position is determined by the physics engine. A dynamic body can collide with other +/// dynamic, static or kinematic bodies. +/** + * @param type The type of the body (STATIC, KINEMATIC, DYNAMIC) + */ inline void CollisionBody::setType(BodyType type) { mType = type; @@ -219,6 +228,9 @@ inline void CollisionBody::setType(BodyType type) { } // Return the interpolated transform for rendering +/** + * @return The current interpolated transformation (between previous and current frame) + */ inline Transform CollisionBody::getInterpolatedTransform() const { return Transform::interpolateTransforms(mOldTransform, mTransform, mInterpolationFactor); } @@ -230,11 +242,19 @@ inline void CollisionBody::setInterpolationFactor(decimal factor) { } // Return the current position and orientation +/** + * @return The current transformation of the body that transforms the local-space + * of the body into world-space + */ inline const Transform& CollisionBody::getTransform() const { return mTransform; } // Set the current position and orientation +/** + * @param transform The transformation of the body that transforms the local-space + * of the body into world-space + */ inline void CollisionBody::setTransform(const Transform& transform) { // Update the transform of the body @@ -251,36 +271,64 @@ inline void CollisionBody::updateOldTransform() { } // Return the first element of the linked list of contact manifolds involving this body +/** + * @return A pointer to the first element of the linked-list with the contact + * manifolds of this body + */ inline const ContactManifoldListElement* CollisionBody::getContactManifoldsList() const { return mContactManifoldsList; } // Return the linked list of proxy shapes of that body +/** +* @return The pointer of the first proxy shape of the linked-list of all the +* proxy shapes of the body +*/ inline ProxyShape* CollisionBody::getProxyShapesList() { return mProxyCollisionShapes; } // Return the linked list of proxy shapes of that body +/** +* @return The pointer of the first proxy shape of the linked-list of all the +* proxy shapes of the body +*/ inline const ProxyShape* CollisionBody::getProxyShapesList() const { return mProxyCollisionShapes; } // Return the world-space coordinates of a point given the local-space coordinates of the body +/** +* @param localPoint A point in the local-space coordinates of the body +* @return The point in world-space coordinates +*/ inline Vector3 CollisionBody::getWorldPoint(const Vector3& localPoint) const { return mTransform * localPoint; } // Return the world-space vector of a vector given in local-space coordinates of the body +/** +* @param localVector A vector in the local-space coordinates of the body +* @return The vector in world-space coordinates +*/ inline Vector3 CollisionBody::getWorldVector(const Vector3& localVector) const { return mTransform.getOrientation() * localVector; } // Return the body local-space coordinates of a point given in the world-space coordinates +/** +* @param worldPoint A point in world-space coordinates +* @return The point in the local-space coordinates of the body +*/ inline Vector3 CollisionBody::getLocalPoint(const Vector3& worldPoint) const { return mTransform.getInverse() * worldPoint; } // Return the body local-space coordinates of a vector given in the world-space coordinates +/** +* @param worldVector A vector in world-space coordinates +* @return The vector in the local-space coordinates of the body +*/ inline Vector3 CollisionBody::getLocalVector(const Vector3& worldVector) const { return mTransform.getOrientation().getInverse() * worldVector; } diff --git a/src/body/RigidBody.cpp b/src/body/RigidBody.cpp index 2cf2f0cd..dcaae9a2 100644 --- a/src/body/RigidBody.cpp +++ b/src/body/RigidBody.cpp @@ -33,6 +33,11 @@ using namespace reactphysics3d; // Constructor +/** +* @param transform The transformation of the body +* @param world The world where the body has been added +* @param id The ID of the body +*/ RigidBody::RigidBody(const Transform& transform, CollisionWorld& world, bodyindex id) : CollisionBody(transform, world, id), mInitMass(decimal(1.0)), mCenterOfMassLocal(0, 0, 0), mCenterOfMassWorld(transform.getPosition()), @@ -48,7 +53,19 @@ RigidBody::~RigidBody() { assert(mJointsList == NULL); } -// Set the type of the body (static, kinematic or dynamic) +// Set the type of the body +/// The type of the body can either STATIC, KINEMATIC or DYNAMIC as described bellow: +/// STATIC : A static body has infinite mass, zero velocity but the position can be +/// changed manually. A static body does not collide with other static or kinematic bodies. +/// KINEMATIC : A kinematic body has infinite mass, the velocity can be changed manually and its +/// position is computed by the physics engine. A kinematic body does not collide with +/// other static or kinematic bodies. +/// DYNAMIC : A dynamic body has non-zero mass, non-zero velocity determined by forces and its +/// position is determined by the physics engine. A dynamic body can collide with other +/// dynamic, static or kinematic bodies. +/** + * @param type The type of the body (STATIC, KINEMATIC, DYNAMIC) + */ void RigidBody::setType(BodyType type) { if (mType == type) return; @@ -96,6 +113,10 @@ void RigidBody::setType(BodyType type) { } // Set the local inertia tensor of the body (in local-space coordinates) +/** + * @param inertiaTensorLocal The 3x3 inertia tensor matrix of the body in local-space + * coordinates + */ void RigidBody::setInertiaTensorLocal(const Matrix3x3& inertiaTensorLocal) { if (mType != DYNAMIC) return; @@ -107,6 +128,10 @@ void RigidBody::setInertiaTensorLocal(const Matrix3x3& inertiaTensorLocal) { } // Set the local center of mass of the body (in local-space coordinates) +/** + * @param centerOfMassLocal The center of mass of the body in local-space + * coordinates + */ void RigidBody::setCenterOfMassLocal(const Vector3& centerOfMassLocal) { if (mType != DYNAMIC) return; @@ -122,6 +147,9 @@ void RigidBody::setCenterOfMassLocal(const Vector3& centerOfMassLocal) { } // Set the mass of the rigid body +/** + * @param mass The mass (in kilograms) of the body + */ void RigidBody::setMass(decimal mass) { if (mType != DYNAMIC) return; @@ -166,15 +194,21 @@ void RigidBody::removeJointFromJointsList(MemoryAllocator& memoryAllocator, cons } // Add a collision shape to the body. -/// This methods will create a copy of the collision shape you provided inside the world and -/// return a pointer to the actual collision shape in the world. You can use this pointer to -/// remove the collision from the body. Note that when the body is destroyed, all the collision -/// shapes will also be destroyed automatically. Because an internal copy of the collision shape -/// you provided is performed, you can delete it right after calling this method. -/// The second parameter is the mass of the collision shape (this will used to compute the -/// total mass of the rigid body and its inertia tensor). The mass must be positive. The third -/// parameter is the transformation that transform the local-space of the collision shape into -/// the local-space of the body. By default, the second parameter is the identity transform. +/// When you add a collision shape to the body, an internal copy of this +/// collision shape will be created internally. Therefore, you can delete it +/// right after calling this method or use it later to add it to another body. +/// This method will return a pointer to a new proxy shape. A proxy shape is +/// an object that links a collision shape and a given body. You can use the +/// returned proxy shape to get and set information about the corresponding +/// collision shape for that body. +/** + * @param collisionShape The collision shape you want to add to the body + * @param transform The transformation of the collision shape that transforms the + * local-space of the collision shape into the local-space of the body + * @param mass Mass (in kilograms) of the collision shape you want to add + * @return A pointer to the proxy shape that has been created to link the body to + * the new collision shape you have added. + */ ProxyShape* RigidBody::addCollisionShape(const CollisionShape& collisionShape, const Transform& transform, decimal mass) { @@ -216,10 +250,16 @@ ProxyShape* RigidBody::addCollisionShape(const CollisionShape& collisionShape, } // Remove a collision shape from the body -void RigidBody::removeCollisionShape(const ProxyShape* proxyCollisionShape) { +/// To remove a collision shape, you need to specify the pointer to the proxy +/// shape that has been returned when you have added the collision shape to the +/// body +/** + * @param proxyShape The pointer of the proxy shape you want to remove + */ +void RigidBody::removeCollisionShape(const ProxyShape* proxyShape) { // Remove the collision shape - CollisionBody::removeCollisionShape(proxyCollisionShape); + CollisionBody::removeCollisionShape(proxyShape); // Recompute the total mass, center of mass and inertia tensor recomputeMassInformation(); diff --git a/src/body/RigidBody.h b/src/body/RigidBody.h index e1415d65..38ba604b 100644 --- a/src/body/RigidBody.h +++ b/src/body/RigidBody.h @@ -118,6 +118,9 @@ class RigidBody : public CollisionBody { /// Update the broad-phase state for this body (because it has moved for instance) virtual void updateBroadPhaseState() const; + /// Set the variable to know whether or not the body is sleeping + virtual void setIsSleeping(bool isSleeping); + public : // -------------------- Methods -------------------- // @@ -194,9 +197,6 @@ class RigidBody : public CollisionBody { /// Return the first element of the linked list of joints involving this body JointListElement* getJointsList(); - /// Set the variable to know whether or not the body is sleeping - virtual void setIsSleeping(bool isSleeping); - /// Apply an external force to the body at its center of mass. void applyForceToCenterOfMass(const Vector3& force); @@ -212,7 +212,7 @@ class RigidBody : public CollisionBody { decimal mass); /// Remove a collision shape from the body - virtual void removeCollisionShape(const ProxyShape* proxyCollisionShape); + virtual void removeCollisionShape(const ProxyShape* proxyShape); /// Recompute the center of mass, total mass and inertia tensor of the body using all /// the collision shapes attached to the body. @@ -229,16 +229,25 @@ class RigidBody : public CollisionBody { }; // Method that return the mass of the body +/** + * @return The mass (in kilograms) of the body + */ inline decimal RigidBody::getMass() const { return mInitMass; } // Return the linear velocity +/** + * @return The linear velocity vector of the body + */ inline Vector3 RigidBody::getLinearVelocity() const { return mLinearVelocity; } // Return the angular velocity of the body +/** + * @return The angular velocity vector of the body + */ inline Vector3 RigidBody::getAngularVelocity() const { return mAngularVelocity; } @@ -246,6 +255,9 @@ inline Vector3 RigidBody::getAngularVelocity() const { // Set the angular velocity. /// You should only call this method for a kinematic body. Otherwise, it /// will do nothing. +/** +* @param angularVelocity The angular velocity vector of the body +*/ inline void RigidBody::setAngularVelocity(const Vector3& angularVelocity) { // If it is a kinematic body @@ -254,7 +266,10 @@ inline void RigidBody::setAngularVelocity(const Vector3& angularVelocity) { } } -// Return the local inertia tensor of the body (in body coordinates) +// Return the local inertia tensor of the body (in local-space coordinates) +/** + * @return The 3x3 inertia tensor matrix of the body (in local-space coordinates) + */ inline const Matrix3x3& RigidBody::getInertiaTensorLocal() const { return mInertiaTensorLocal; } @@ -265,6 +280,9 @@ inline const Matrix3x3& RigidBody::getInertiaTensorLocal() const { /// by I_w = R * I_b * R^T /// where R is the rotation matrix (and R^T its transpose) of /// the current orientation quaternion of the body +/** + * @return The 3x3 inertia tensor matrix of the body in world-space coordinates + */ inline Matrix3x3 RigidBody::getInertiaTensorWorld() const { // Compute and return the inertia tensor in world coordinates @@ -278,10 +296,15 @@ inline Matrix3x3 RigidBody::getInertiaTensorWorld() const { /// by I_w = R * I_b^-1 * R^T /// where R is the rotation matrix (and R^T its transpose) of the /// current orientation quaternion of the body -// TODO : DO NOT RECOMPUTE THE MATRIX MULTIPLICATION EVERY TIME. WE NEED TO STORE THE -// INVERSE WORLD TENSOR IN THE CLASS AND UPLDATE IT WHEN THE ORIENTATION OF THE BODY CHANGES +/** + * @return The 3x3 inverse inertia tensor matrix of the body in world-space + * coordinates + */ inline Matrix3x3 RigidBody::getInertiaTensorInverseWorld() const { + // TODO : DO NOT RECOMPUTE THE MATRIX MULTIPLICATION EVERY TIME. WE NEED TO STORE THE + // INVERSE WORLD TENSOR IN THE CLASS AND UPLDATE IT WHEN THE ORIENTATION OF THE BODY CHANGES + // Compute and return the inertia tensor in world coordinates return mTransform.getOrientation().getMatrix() * mInertiaTensorLocalInverse * mTransform.getOrientation().getMatrix().getTranspose(); @@ -290,6 +313,9 @@ inline Matrix3x3 RigidBody::getInertiaTensorInverseWorld() const { // Set the linear velocity of the rigid body. /// You should only call this method for a kinematic body. Otherwise, it /// will do nothing. +/** + * @param linearVelocity Linear velocity vector of the body + */ inline void RigidBody::setLinearVelocity(const Vector3& linearVelocity) { // If it is a kinematic body @@ -301,53 +327,83 @@ inline void RigidBody::setLinearVelocity(const Vector3& linearVelocity) { } // Return true if the gravity needs to be applied to this rigid body +/** + * @return True if the gravity is applied to the body + */ inline bool RigidBody::isGravityEnabled() const { return mIsGravityEnabled; } // Set the variable to know if the gravity is applied to this rigid body +/** + * @param isEnabled True if you want the gravity to be applied to this body + */ inline void RigidBody::enableGravity(bool isEnabled) { mIsGravityEnabled = isEnabled; } // Return a reference to the material properties of the rigid body +/** + * @return A reference to the material of the body + */ inline Material& RigidBody::getMaterial() { return mMaterial; } // Set a new material for this rigid body +/** + * @param material The material you want to set to the body + */ inline void RigidBody::setMaterial(const Material& material) { mMaterial = material; } // Return the linear velocity damping factor +/** + * @return The linear damping factor of this body + */ inline decimal RigidBody::getLinearDamping() const { return mLinearDamping; } // Set the linear damping factor +/** + * @param linearDamping The linear damping factor of this body + */ inline void RigidBody::setLinearDamping(decimal linearDamping) { assert(linearDamping >= decimal(0.0)); mLinearDamping = linearDamping; } // Return the angular velocity damping factor +/** + * @return The angular damping factor of this body + */ inline decimal RigidBody::getAngularDamping() const { return mAngularDamping; } // Set the angular damping factor +/** + * @param angularDamping The angular damping factor of this body + */ inline void RigidBody::setAngularDamping(decimal angularDamping) { assert(angularDamping >= decimal(0.0)); mAngularDamping = angularDamping; } // Return the first element of the linked list of joints involving this body +/** + * @return The first element of the linked-list of all the joints involving this body + */ inline const JointListElement* RigidBody::getJointsList() const { return mJointsList; } // Return the first element of the linked list of joints involving this body +/** + * @return The first element of the linked-list of all the joints involving this body + */ inline JointListElement* RigidBody::getJointsList() { return mJointsList; } @@ -370,6 +426,9 @@ inline void RigidBody::setIsSleeping(bool isSleeping) { /// 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. /// You can only apply a force to a dynamic body otherwise, this method will do nothing. +/** + * @param force The external force to apply on the center of mass of the body + */ inline void RigidBody::applyForceToCenterOfMass(const Vector3& force) { // If it is not a dynamic body, we do nothing @@ -391,6 +450,10 @@ inline void RigidBody::applyForceToCenterOfMass(const Vector3& force) { /// 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. /// You can only apply a force to a dynamic body otherwise, this method will do nothing. +/** + * @param force The force to apply on the body + * @param point The point where the force is applied (in world-space coordinates) + */ inline void RigidBody::applyForce(const Vector3& force, const Vector3& point) { // If it is not a dynamic body, we do nothing @@ -411,6 +474,9 @@ inline void RigidBody::applyForce(const Vector3& force, const Vector3& point) { /// 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. /// You can only apply a force to a dynamic body otherwise, this method will do nothing. +/** + * @param torque The external torque to apply on the body + */ inline void RigidBody::applyTorque(const Vector3& torque) { // If it is not a dynamic body, we do nothing diff --git a/src/collision/ProxyShape.cpp b/src/collision/ProxyShape.cpp index d0f90ae3..dee97d9f 100644 --- a/src/collision/ProxyShape.cpp +++ b/src/collision/ProxyShape.cpp @@ -5,6 +5,12 @@ using namespace reactphysics3d; // Constructor +/** + * @param body Pointer to the parent body + * @param shape Pointer to the collision shape + * @param transform Transformation from collision shape local-space to body local-space + * @param mass Mass of the collision shape (in kilograms) + */ ProxyShape::ProxyShape(CollisionBody* body, CollisionShape* shape, const Transform& transform, decimal mass) :mBody(body), mCollisionShape(shape), mLocalToBodyTransform(transform), mMass(mass), @@ -23,6 +29,10 @@ ProxyShape::~ProxyShape() { } // Return true if a point is inside the collision shape +/** + * @param worldPoint Point to test in world-space coordinates + * @return True if the point is inside the collision shape + */ bool ProxyShape::testPointInside(const Vector3& worldPoint) { const Transform localToWorld = mBody->getTransform() * mLocalToBodyTransform; const Vector3 localPoint = localToWorld.getInverse() * worldPoint; diff --git a/src/collision/ProxyShape.h b/src/collision/ProxyShape.h index 25be73ab..e122e34a 100644 --- a/src/collision/ProxyShape.h +++ b/src/collision/ProxyShape.h @@ -77,12 +77,6 @@ class ProxyShape { /// Return the collision shape margin decimal getMargin() const; - /// Return the next proxy shape in the linked list of proxy shapes - ProxyShape* getNext(); - - /// Return the next proxy shape in the linked list of proxy shapes - const ProxyShape* getNext() const; - public: // -------------------- Methods -------------------- // @@ -121,17 +115,23 @@ class ProxyShape { /// Raycast method with feedback information bool raycast(const Ray& ray, RaycastInfo& raycastInfo); + /// Return the collision bits mask + unsigned short getCollideWithMaskBits() const; + + /// Set the collision bits mask + void setCollideWithMaskBits(unsigned short collideWithMaskBits); + /// Return the collision category bits unsigned short getCollisionCategoryBits() const; /// Set the collision category bits void setCollisionCategoryBits(unsigned short collisionCategoryBits); - /// Return the collision bits mask - unsigned short getCollideWithMaskBits() const; + /// Return the next proxy shape in the linked list of proxy shapes + ProxyShape* getNext(); - /// Set the collision bits mask - void setCollideWithMaskBits(unsigned short collideWithMaskBits); + /// Return the next proxy shape in the linked list of proxy shapes + const ProxyShape* getNext() const; // -------------------- Friendship -------------------- // @@ -149,36 +149,59 @@ class ProxyShape { }; /// Return the collision shape +/** + * @return Pointer to the internal collision shape + */ inline const CollisionShape* ProxyShape::getCollisionShape() const { return mCollisionShape; } // Return the parent body +/** + * @return Pointer to the parent body + */ inline CollisionBody* ProxyShape::getBody() const { return mBody; } // Return the mass of the collision shape +/** + * @return Mass of the collision shape (in kilograms) + */ inline decimal ProxyShape::getMass() const { return mMass; } // Return a pointer to the user data attached to this body +/** + * @return A pointer to the user data stored into the proxy shape + */ inline void* ProxyShape::getUserData() const { return mUserData; } // Attach user data to this body +/** + * @param userData Pointer to the user data you want to store within the proxy shape + */ inline void ProxyShape::setUserData(void* userData) { mUserData = userData; } // Return the local to parent body transform +/** + * @return The transformation that transforms the local-space of the collision shape + * to the local-space of the parent body + */ inline const Transform& ProxyShape::getLocalToBodyTransform() const { return mLocalToBodyTransform; } // Return the local to world transform +/** + * @return The transformation that transforms the local-space of the collision + * shape to the world-space + */ inline const Transform ProxyShape::getLocalToWorldTransform() const { return mBody->mTransform * mLocalToBodyTransform; } @@ -199,6 +222,12 @@ inline decimal ProxyShape::getMargin() const { } // Raycast method with feedback information +/** + * @param ray Ray to use for the raycasting + * @param[out] raycastInfo Result of the raycasting that is valid only if the + * methods returned true + * @return True if the ray hit the collision shape + */ inline bool ProxyShape::raycast(const Ray& ray, RaycastInfo& raycastInfo) { // If the corresponding body is not active, it cannot be hit by rays @@ -208,31 +237,49 @@ inline bool ProxyShape::raycast(const Ray& ray, RaycastInfo& raycastInfo) { } // Return the next proxy shape in the linked list of proxy shapes +/** + * @return Pointer to the next proxy shape in the linked list of proxy shapes + */ inline ProxyShape* ProxyShape::getNext() { return mNext; } // Return the next proxy shape in the linked list of proxy shapes +/** + * @return Pointer to the next proxy shape in the linked list of proxy shapes + */ inline const ProxyShape* ProxyShape::getNext() const { return mNext; } // Return the collision category bits +/** + * @return The collision category bits mask of the proxy shape + */ inline unsigned short ProxyShape::getCollisionCategoryBits() const { return mCollisionCategoryBits; } // Set the collision category bits +/** + * @param collisionCategoryBits The collision category bits mask of the proxy shape + */ inline void ProxyShape::setCollisionCategoryBits(unsigned short collisionCategoryBits) { mCollisionCategoryBits = collisionCategoryBits; } // Return the collision bits mask +/** + * @return The bits mask that specifies with which collision category this shape will collide + */ inline unsigned short ProxyShape::getCollideWithMaskBits() const { return mCollideWithMaskBits; } // Set the collision bits mask +/** + * @param collideWithMaskBits The bits mask that specifies with which collision category this shape will collide + */ inline void ProxyShape::setCollideWithMaskBits(unsigned short collideWithMaskBits) { mCollideWithMaskBits = collideWithMaskBits; } diff --git a/src/collision/RaycastInfo.h b/src/collision/RaycastInfo.h index 3eb4de42..dfba996c 100644 --- a/src/collision/RaycastInfo.h +++ b/src/collision/RaycastInfo.h @@ -116,6 +116,10 @@ class RaycastCallback { /// value in the RaycastInfo object), the current ray will be clipped /// to this fraction in the next queries. If you return -1.0, it will /// ignore this ProxyShape and continue the ray cast. + /** + * @param raycastInfo Information about the raycast hit + * @return Value that controls the continuation of the ray after a hit + */ virtual decimal notifyRaycastHit(const RaycastInfo& raycastInfo)=0; }; diff --git a/src/collision/shapes/BoxShape.cpp b/src/collision/shapes/BoxShape.cpp index 38a69d15..1536bef5 100644 --- a/src/collision/shapes/BoxShape.cpp +++ b/src/collision/shapes/BoxShape.cpp @@ -33,6 +33,10 @@ using namespace reactphysics3d; // Constructor +/** + * @param extent The vector with the three extents of the box (in meters) + * @param margin The collision margin (in meters) around the collision shape + */ BoxShape::BoxShape(const Vector3& extent, decimal margin) : CollisionShape(BOX, margin), mExtent(extent - Vector3(margin, margin, margin)) { assert(extent.x > decimal(0.0) && extent.x > margin); @@ -52,6 +56,11 @@ BoxShape::~BoxShape() { } // Return the local inertia tensor of the collision shape +/** + * @param[out] tensor The 3x3 inertia tensor matrix of the shape in local-space + * coordinates + * @param mass Mass to use to compute the inertia tensor of the collision shape + */ void BoxShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const { decimal factor = (decimal(1.0) / decimal(3.0)) * mass; Vector3 realExtent = mExtent + Vector3(mMargin, mMargin, mMargin); diff --git a/src/collision/shapes/BoxShape.h b/src/collision/shapes/BoxShape.h index 53d6e4bd..a9b82133 100644 --- a/src/collision/shapes/BoxShape.h +++ b/src/collision/shapes/BoxShape.h @@ -81,6 +81,12 @@ class BoxShape : public CollisionShape { /// Raycast method with feedback information virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const; + /// Allocate and return a copy of the object + virtual BoxShape* clone(void* allocatedMemory) const; + + /// Return the number of bytes used by the collision shape + virtual size_t getSizeInBytes() const; + public : // -------------------- Methods -------------------- // @@ -91,18 +97,12 @@ class BoxShape : public CollisionShape { /// Destructor virtual ~BoxShape(); - /// Allocate and return a copy of the object - virtual BoxShape* clone(void* allocatedMemory) const; - /// Return the extents of the box Vector3 getExtent() const; /// Return the local bounds of the shape in x, y and z directions virtual void getLocalBounds(Vector3& min, Vector3& max) const; - /// Return the number of bytes used by the collision shape - virtual size_t getSizeInBytes() const; - /// Return the local inertia tensor of the collision shape virtual void computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const; @@ -116,12 +116,19 @@ inline BoxShape* BoxShape::clone(void* allocatedMemory) const { } // Return the extents of the box +/** + * @return The vector with the three extents of the box shape (in meters) + */ inline Vector3 BoxShape::getExtent() const { return mExtent + Vector3(mMargin, mMargin, mMargin); } // Return the local bounds of the shape in x, y and z directions /// This method is used to compute the AABB of the box +/** + * @param min The minimum bounds of the shape in local-space coordinates + * @param max The maximum bounds of the shape in local-space coordinates + */ inline void BoxShape::getLocalBounds(Vector3& min, Vector3& max) const { // Maximum bounds diff --git a/src/collision/shapes/CapsuleShape.cpp b/src/collision/shapes/CapsuleShape.cpp index 976b8f3c..4e7777a5 100644 --- a/src/collision/shapes/CapsuleShape.cpp +++ b/src/collision/shapes/CapsuleShape.cpp @@ -32,6 +32,10 @@ using namespace reactphysics3d; // Constructor +/** + * @param radius The radius of the capsule (in meters) + * @param height The height of the capsule (in meters) + */ CapsuleShape::CapsuleShape(decimal radius, decimal height) : CollisionShape(CAPSULE, radius), mRadius(radius), mHalfHeight(height * decimal(0.5)) { assert(radius > decimal(0.0)); @@ -107,6 +111,11 @@ Vector3 CapsuleShape::getLocalSupportPointWithoutMargin(const Vector3& direction } // Return the local inertia tensor of the capsule +/** + * @param[out] tensor The 3x3 inertia tensor matrix of the shape in local-space + * coordinates + * @param mass Mass to use to compute the inertia tensor of the collision shape + */ void CapsuleShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const { // The inertia tensor formula for a capsule can be found in : Game Engine Gems, Volume 1 diff --git a/src/collision/shapes/CapsuleShape.h b/src/collision/shapes/CapsuleShape.h index f0591aaf..2cc8cb33 100644 --- a/src/collision/shapes/CapsuleShape.h +++ b/src/collision/shapes/CapsuleShape.h @@ -83,6 +83,12 @@ class CapsuleShape : public CollisionShape { const Vector3& sphereCenter, decimal maxFraction, Vector3& hitLocalPoint, decimal& hitFraction) const; + /// Allocate and return a copy of the object + virtual CapsuleShape* clone(void* allocatedMemory) const; + + /// Return the number of bytes used by the collision shape + virtual size_t getSizeInBytes() const; + public : // -------------------- Methods -------------------- // @@ -93,18 +99,12 @@ class CapsuleShape : public CollisionShape { /// Destructor virtual ~CapsuleShape(); - /// Allocate and return a copy of the object - virtual CapsuleShape* clone(void* allocatedMemory) const; - /// Return the radius of the capsule decimal getRadius() const; /// Return the height of the capsule decimal getHeight() const; - /// Return the number of bytes used by the collision shape - virtual size_t getSizeInBytes() const; - /// Return the local bounds of the shape in x, y and z directions virtual void getLocalBounds(Vector3& min, Vector3& max) const; @@ -121,11 +121,17 @@ inline CapsuleShape* CapsuleShape::clone(void* allocatedMemory) const { } // Get the radius of the capsule +/** + * @return The radius of the capsule shape (in meters) + */ inline decimal CapsuleShape::getRadius() const { return mRadius; } // Return the height of the capsule +/** + * @return The height of the capsule shape (in meters) + */ inline decimal CapsuleShape::getHeight() const { return mHalfHeight + mHalfHeight; } @@ -137,6 +143,10 @@ inline size_t CapsuleShape::getSizeInBytes() const { // Return the local bounds of the shape in x, y and z directions // This method is used to compute the AABB of the box +/** + * @param min The minimum bounds of the shape in local-space coordinates + * @param max The maximum bounds of the shape in local-space coordinates + */ inline void CapsuleShape::getLocalBounds(Vector3& min, Vector3& max) const { // Maximum bounds diff --git a/src/collision/shapes/CollisionShape.cpp b/src/collision/shapes/CollisionShape.cpp index e35bf8cf..e61d5358 100644 --- a/src/collision/shapes/CollisionShape.cpp +++ b/src/collision/shapes/CollisionShape.cpp @@ -50,6 +50,11 @@ CollisionShape::~CollisionShape() { } // Compute the world-space AABB of the collision shape given a transform +/** + * @param[out] aabb The axis-aligned bounding box (AABB) of the collision shape + * computed in world-space coordinates + * @param transform Transform used to compute the AABB of the collision shape + */ void CollisionShape::computeAABB(AABB& aabb, const Transform& transform) const { PROFILE("CollisionShape::computeAABB()"); diff --git a/src/collision/shapes/CollisionShape.h b/src/collision/shapes/CollisionShape.h index f8699f75..96e4fffc 100644 --- a/src/collision/shapes/CollisionShape.h +++ b/src/collision/shapes/CollisionShape.h @@ -88,6 +88,21 @@ class CollisionShape { /// Raycast method with feedback information virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const=0; + /// Return the number of similar created shapes + uint getNbSimilarCreatedShapes() const; + + /// Allocate and return a copy of the object + virtual CollisionShape* clone(void* allocatedMemory) const=0; + + /// Return the number of bytes used by the collision shape + virtual size_t getSizeInBytes() const = 0; + + /// Increment the number of similar allocated collision shapes + void incrementNbSimilarCreatedShapes(); + + /// Decrement the number of similar allocated collision shapes + void decrementNbSimilarCreatedShapes(); + public : // -------------------- Methods -------------------- // @@ -98,21 +113,12 @@ class CollisionShape { /// Destructor virtual ~CollisionShape(); - /// Allocate and return a copy of the object - virtual CollisionShape* clone(void* allocatedMemory) const=0; - /// Return the type of the collision shapes CollisionShapeType getType() const; - /// Return the number of similar created shapes - uint getNbSimilarCreatedShapes() const; - /// Return the current object margin decimal getMargin() const; - /// Return the number of bytes used by the collision shape - virtual size_t getSizeInBytes() const = 0; - /// Return the local bounds of the shape in x, y and z directions virtual void getLocalBounds(Vector3& min, Vector3& max) const=0; @@ -122,12 +128,6 @@ class CollisionShape { /// Compute the world-space AABB of the collision shape given a transform virtual void computeAABB(AABB& aabb, const Transform& transform) const; - /// Increment the number of similar allocated collision shapes - void incrementNbSimilarCreatedShapes(); - - /// Decrement the number of similar allocated collision shapes - void decrementNbSimilarCreatedShapes(); - /// Equality operator between two collision shapes. bool operator==(const CollisionShape& otherCollisionShape) const; @@ -137,12 +137,16 @@ class CollisionShape { // -------------------- Friendship -------------------- // friend class ProxyShape; + friend class CollisionWorld; }; // Return the type of the collision shape +/** + * @return The type of the collision shape (box, sphere, cylinder, ...) + */ inline CollisionShapeType CollisionShape::getType() const { return mType; } @@ -152,7 +156,10 @@ inline uint CollisionShape::getNbSimilarCreatedShapes() const { return mNbSimilarCreatedShapes; } -// Return the current object margin +// Return the current collision shape margin +/** + * @return The margin (in meters) around the collision shape + */ inline decimal CollisionShape::getMargin() const { return mMargin; } diff --git a/src/collision/shapes/ConeShape.cpp b/src/collision/shapes/ConeShape.cpp index 83ff73c4..6390501c 100644 --- a/src/collision/shapes/ConeShape.cpp +++ b/src/collision/shapes/ConeShape.cpp @@ -32,6 +32,11 @@ using namespace reactphysics3d; // Constructor +/** + * @param radius Radius of the cone (in meters) + * @param height Height of the cone (in meters) + * @param margin Collision margin (in meters) around the collision shape + */ ConeShape::ConeShape(decimal radius, decimal height, decimal margin) : CollisionShape(CONE, margin), mRadius(radius), mHalfHeight(height * decimal(0.5)) { assert(mRadius > decimal(0.0)); diff --git a/src/collision/shapes/ConeShape.h b/src/collision/shapes/ConeShape.h index 74cdc8e1..4c1fd108 100644 --- a/src/collision/shapes/ConeShape.h +++ b/src/collision/shapes/ConeShape.h @@ -85,6 +85,12 @@ class ConeShape : public CollisionShape { /// Raycast method with feedback information virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const; + + /// Allocate and return a copy of the object + virtual ConeShape* clone(void* allocatedMemory) const; + + /// Return the number of bytes used by the collision shape + virtual size_t getSizeInBytes() const; public : @@ -96,18 +102,12 @@ class ConeShape : public CollisionShape { /// Destructor virtual ~ConeShape(); - /// Allocate and return a copy of the object - virtual ConeShape* clone(void* allocatedMemory) const; - /// Return the radius decimal getRadius() const; /// Return the height decimal getHeight() const; - /// Return the number of bytes used by the collision shape - virtual size_t getSizeInBytes() const; - /// Return the local bounds of the shape in x, y and z directions virtual void getLocalBounds(Vector3& min, Vector3& max) const; @@ -124,11 +124,17 @@ inline ConeShape* ConeShape::clone(void* allocatedMemory) const { } // Return the radius +/** + * @return Radius of the cone (in meters) + */ inline decimal ConeShape::getRadius() const { return mRadius; } // Return the height +/** + * @return Height of the cone (in meters) + */ inline decimal ConeShape::getHeight() const { return decimal(2.0) * mHalfHeight; } @@ -139,6 +145,10 @@ inline size_t ConeShape::getSizeInBytes() const { } // Return the local bounds of the shape in x, y and z directions +/** + * @param min The minimum bounds of the shape in local-space coordinates + * @param max The maximum bounds of the shape in local-space coordinates + */ inline void ConeShape::getLocalBounds(Vector3& min, Vector3& max) const { // Maximum bounds @@ -153,6 +163,11 @@ inline void ConeShape::getLocalBounds(Vector3& min, Vector3& max) const { } // Return the local inertia tensor of the collision shape +/** + * @param[out] tensor The 3x3 inertia tensor matrix of the shape in local-space + * coordinates + * @param mass Mass to use to compute the inertia tensor of the collision shape + */ inline void ConeShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const { decimal rSquare = mRadius * mRadius; decimal diagXZ = decimal(0.15) * mass * (rSquare + mHalfHeight); diff --git a/src/collision/shapes/ConvexMeshShape.cpp b/src/collision/shapes/ConvexMeshShape.cpp index b3567b4f..a6d3cf2a 100644 --- a/src/collision/shapes/ConvexMeshShape.cpp +++ b/src/collision/shapes/ConvexMeshShape.cpp @@ -32,6 +32,12 @@ using namespace reactphysics3d; // Constructor to initialize with a array of 3D vertices. /// This method creates an internal copy of the input vertices. +/** + * @param arrayVertices Array with the vertices of the convex mesh + * @param nbVertices Number of vertices in the convex mesh + * @param stride Stride between the beginning of two elements in the vertices array + * @param margin Collision margin (in meters) around the collision shape + */ ConvexMeshShape::ConvexMeshShape(const decimal* arrayVertices, uint nbVertices, int stride, decimal margin) : CollisionShape(CONVEX_MESH, margin), mNbVertices(nbVertices), mMinBounds(0, 0, 0), diff --git a/src/collision/shapes/ConvexMeshShape.h b/src/collision/shapes/ConvexMeshShape.h index c0bcd27f..385050ee 100644 --- a/src/collision/shapes/ConvexMeshShape.h +++ b/src/collision/shapes/ConvexMeshShape.h @@ -107,6 +107,12 @@ class ConvexMeshShape : public CollisionShape { /// Raycast method with feedback information virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const; + /// Allocate and return a copy of the object + virtual ConvexMeshShape* clone(void* allocatedMemory) const; + + /// Return the number of bytes used by the collision shape + virtual size_t getSizeInBytes() const; + public : // -------------------- Methods -------------------- // @@ -121,12 +127,6 @@ class ConvexMeshShape : public CollisionShape { /// Destructor virtual ~ConvexMeshShape(); - /// Allocate and return a copy of the object - virtual ConvexMeshShape* clone(void* allocatedMemory) const; - - /// Return the number of bytes used by the collision shape - virtual size_t getSizeInBytes() const; - /// Return the local bounds of the shape in x, y and z directions virtual void getLocalBounds(Vector3& min, Vector3& max) const; @@ -161,6 +161,10 @@ inline size_t ConvexMeshShape::getSizeInBytes() const { } // Return the local bounds of the shape in x, y and z directions +/** + * @param min The minimum bounds of the shape in local-space coordinates + * @param max The maximum bounds of the shape in local-space coordinates + */ inline void ConvexMeshShape::getLocalBounds(Vector3& min, Vector3& max) const { min = mMinBounds; max = mMaxBounds; @@ -169,6 +173,11 @@ inline void ConvexMeshShape::getLocalBounds(Vector3& min, Vector3& max) const { // Return the local inertia tensor of the collision shape. /// The local inertia tensor of the convex mesh is approximated using the inertia tensor /// of its bounding box. +/** +* @param[out] tensor The 3x3 inertia tensor matrix of the shape in local-space +* coordinates +* @param mass Mass to use to compute the inertia tensor of the collision shape +*/ inline void ConvexMeshShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const { decimal factor = (decimal(1.0) / decimal(3.0)) * mass; Vector3 realExtent = decimal(0.5) * (mMaxBounds - mMinBounds); @@ -182,6 +191,9 @@ inline void ConvexMeshShape::computeLocalInertiaTensor(Matrix3x3& tensor, decima } // Add a vertex into the convex mesh +/** + * @param vertex Vertex to be added + */ inline void ConvexMeshShape::addVertex(const Vector3& vertex) { // Add the vertex in to vertices array @@ -201,6 +213,10 @@ inline void ConvexMeshShape::addVertex(const Vector3& vertex) { /// Note that the vertex indices start at zero and need to correspond to the order of /// the vertices in the vertices array in the constructor or the order of the calls /// of the addVertex() methods that you use to add vertices into the convex mesh. +/** +* @param v1 Index of the first vertex of the edge to add +* @param v2 Index of the second vertex of the edge to add +*/ inline void ConvexMeshShape::addEdge(uint v1, uint v2) { assert(v1 >= 0); @@ -222,12 +238,19 @@ inline void ConvexMeshShape::addEdge(uint v1, uint v2) { } // Return true if the edges information is used to speed up the collision detection +/** + * @return True if the edges information is used and false otherwise + */ inline bool ConvexMeshShape::isEdgesInformationUsed() const { return mIsEdgesInformationUsed; } // Set the variable to know if the edges information is used to speed up the // collision detection +/** + * @param isEdgesUsed True if you want to use the edges information to speed up + * the collision detection with the convex mesh shape + */ inline void ConvexMeshShape::setIsEdgesInformationUsed(bool isEdgesUsed) { mIsEdgesInformationUsed = isEdgesUsed; } diff --git a/src/collision/shapes/CylinderShape.cpp b/src/collision/shapes/CylinderShape.cpp index 60247516..13a7f7d0 100644 --- a/src/collision/shapes/CylinderShape.cpp +++ b/src/collision/shapes/CylinderShape.cpp @@ -31,6 +31,11 @@ using namespace reactphysics3d; // Constructor +/** + * @param radius Radius of the cylinder (in meters) + * @param height Height of the cylinder (in meters) + * @param margin Collision margin (in meters) around the collision shape + */ CylinderShape::CylinderShape(decimal radius, decimal height, decimal margin) : CollisionShape(CYLINDER, margin), mRadius(radius), mHalfHeight(height/decimal(2.0)) { diff --git a/src/collision/shapes/CylinderShape.h b/src/collision/shapes/CylinderShape.h index 878278ea..87a8d190 100644 --- a/src/collision/shapes/CylinderShape.h +++ b/src/collision/shapes/CylinderShape.h @@ -83,6 +83,12 @@ class CylinderShape : public CollisionShape { /// Raycast method with feedback information virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const; + /// Allocate and return a copy of the object + virtual CylinderShape* clone(void* allocatedMemory) const; + + /// Return the number of bytes used by the collision shape + virtual size_t getSizeInBytes() const; + public : // -------------------- Methods -------------------- // @@ -93,18 +99,12 @@ class CylinderShape : public CollisionShape { /// Destructor virtual ~CylinderShape(); - /// Allocate and return a copy of the object - virtual CylinderShape* clone(void* allocatedMemory) const; - /// Return the radius decimal getRadius() const; /// Return the height decimal getHeight() const; - /// Return the number of bytes used by the collision shape - virtual size_t getSizeInBytes() const; - /// Return the local bounds of the shape in x, y and z directions virtual void getLocalBounds(Vector3& min, Vector3& max) const; @@ -121,11 +121,17 @@ inline CylinderShape* CylinderShape::clone(void* allocatedMemory) const { } // Return the radius +/** + * @return Radius of the cylinder (in meters) + */ inline decimal CylinderShape::getRadius() const { return mRadius; } // Return the height +/** + * @return Height of the cylinder (in meters) + */ inline decimal CylinderShape::getHeight() const { return mHalfHeight + mHalfHeight; } @@ -136,6 +142,10 @@ inline size_t CylinderShape::getSizeInBytes() const { } // Return the local bounds of the shape in x, y and z directions +/** + * @param min The minimum bounds of the shape in local-space coordinates + * @param max The maximum bounds of the shape in local-space coordinates + */ inline void CylinderShape::getLocalBounds(Vector3& min, Vector3& max) const { // Maximum bounds @@ -150,6 +160,11 @@ inline void CylinderShape::getLocalBounds(Vector3& min, Vector3& max) const { } // Return the local inertia tensor of the cylinder +/** + * @param[out] tensor The 3x3 inertia tensor matrix of the shape in local-space + * coordinates + * @param mass Mass to use to compute the inertia tensor of the collision shape + */ inline void CylinderShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const { decimal height = decimal(2.0) * mHalfHeight; decimal diag = (decimal(1.0) / decimal(12.0)) * mass * (3 * mRadius * mRadius + height * height); diff --git a/src/collision/shapes/SphereShape.cpp b/src/collision/shapes/SphereShape.cpp index 4c38fae5..374148be 100644 --- a/src/collision/shapes/SphereShape.cpp +++ b/src/collision/shapes/SphereShape.cpp @@ -32,6 +32,9 @@ using namespace reactphysics3d; // Constructor +/** + * @param radius Radius of the sphere (in meters) + */ SphereShape::SphereShape(decimal radius) : CollisionShape(SPHERE, radius), mRadius(radius) { assert(radius > decimal(0.0)); } diff --git a/src/collision/shapes/SphereShape.h b/src/collision/shapes/SphereShape.h index c9ee75e9..4ee3c163 100644 --- a/src/collision/shapes/SphereShape.h +++ b/src/collision/shapes/SphereShape.h @@ -73,6 +73,12 @@ class SphereShape : public CollisionShape { /// Raycast method with feedback information virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const; + /// Allocate and return a copy of the object + virtual SphereShape* clone(void* allocatedMemory) const; + + /// Return the number of bytes used by the collision shape + virtual size_t getSizeInBytes() const; + public : // -------------------- Methods -------------------- // @@ -83,15 +89,9 @@ class SphereShape : public CollisionShape { /// Destructor virtual ~SphereShape(); - /// Allocate and return a copy of the object - virtual SphereShape* clone(void* allocatedMemory) const; - /// Return the radius of the sphere decimal getRadius() const; - /// Return the number of bytes used by the collision shape - virtual size_t getSizeInBytes() const; - /// Return the local bounds of the shape in x, y and z directions. virtual void getLocalBounds(Vector3& min, Vector3& max) const; @@ -111,6 +111,9 @@ inline SphereShape* SphereShape::clone(void* allocatedMemory) const { } // Get the radius of the sphere +/** + * @return Radius of the sphere (in meters) + */ inline decimal SphereShape::getRadius() const { return mRadius; } @@ -146,6 +149,10 @@ inline Vector3 SphereShape::getLocalSupportPointWithoutMargin(const Vector3& dir // Return the local bounds of the shape in x, y and z directions. // This method is used to compute the AABB of the box +/** + * @param min The minimum bounds of the shape in local-space coordinates + * @param max The maximum bounds of the shape in local-space coordinates + */ inline void SphereShape::getLocalBounds(Vector3& min, Vector3& max) const { // Maximum bounds @@ -160,6 +167,11 @@ inline void SphereShape::getLocalBounds(Vector3& min, Vector3& max) const { } // Return the local inertia tensor of the sphere +/** + * @param[out] tensor The 3x3 inertia tensor matrix of the shape in local-space + * coordinates + * @param mass Mass to use to compute the inertia tensor of the collision shape + */ inline void SphereShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal mass) const { decimal diag = decimal(0.4) * mass * mRadius * mRadius; tensor.setAllValues(diag, 0.0, 0.0, @@ -168,6 +180,11 @@ inline void SphereShape::computeLocalInertiaTensor(Matrix3x3& tensor, decimal ma } // Update the AABB of a body using its collision shape +/** + * @param[out] aabb The axis-aligned bounding box (AABB) of the collision shape + * computed in world-space coordinates + * @param transform Transform used to compute the AABB of the collision shape + */ inline void SphereShape::computeAABB(AABB& aabb, const Transform& transform) { // Get the local extents in x,y and z direction diff --git a/src/constraint/BallAndSocketJoint.h b/src/constraint/BallAndSocketJoint.h index b194dc0d..69776fd6 100644 --- a/src/constraint/BallAndSocketJoint.h +++ b/src/constraint/BallAndSocketJoint.h @@ -47,6 +47,12 @@ struct BallAndSocketJointInfo : public JointInfo { Vector3 anchorPointWorldSpace; /// Constructor + /** + * @param rigidBody1 Pointer to the first body of the joint + * @param rigidBody2 Pointer to the second body of the joint + * @param initAnchorPointWorldSpace The anchor point in world-space + * coordinates + */ BallAndSocketJointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2, const Vector3& initAnchorPointWorldSpace) : JointInfo(rigidBody1, rigidBody2, BALLSOCKETJOINT), diff --git a/src/constraint/FixedJoint.h b/src/constraint/FixedJoint.h index 9a9e9bac..da2a0f56 100644 --- a/src/constraint/FixedJoint.h +++ b/src/constraint/FixedJoint.h @@ -47,6 +47,12 @@ struct FixedJointInfo : public JointInfo { Vector3 anchorPointWorldSpace; /// Constructor + /** + * @param rigidBody1 The first body of the joint + * @param rigidBody2 The second body of the joint + * @param initAnchorPointWorldSpace The initial anchor point of the joint in + * world-space coordinates + */ FixedJointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2, const Vector3& initAnchorPointWorldSpace) : JointInfo(rigidBody1, rigidBody2, FIXEDJOINT), diff --git a/src/constraint/HingeJoint.cpp b/src/constraint/HingeJoint.cpp index fce93901..1e30d3d3 100644 --- a/src/constraint/HingeJoint.cpp +++ b/src/constraint/HingeJoint.cpp @@ -613,6 +613,10 @@ void HingeJoint::solvePositionConstraint(const ConstraintSolverData& constraintS // Enable/Disable the limits of the joint +/** + * @param isLimitEnabled True if you want to enable the limits of the joint and + * false otherwise + */ void HingeJoint::enableLimit(bool isLimitEnabled) { if (isLimitEnabled != mIsLimitEnabled) { @@ -625,6 +629,10 @@ void HingeJoint::enableLimit(bool isLimitEnabled) { } // Enable/Disable the motor of the joint +/** + * @param isMotorEnabled True if you want to enable the motor of the joint and + * false otherwise + */ void HingeJoint::enableMotor(bool isMotorEnabled) { mIsMotorEnabled = isMotorEnabled; @@ -636,6 +644,9 @@ void HingeJoint::enableMotor(bool isMotorEnabled) { } // Set the minimum angle limit +/** + * @param lowerLimit The minimum limit angle of the joint (in radian) + */ void HingeJoint::setMinAngleLimit(decimal lowerLimit) { assert(mLowerLimit <= 0 && mLowerLimit >= -2.0 * PI); @@ -650,6 +661,9 @@ void HingeJoint::setMinAngleLimit(decimal lowerLimit) { } // Set the maximum angle limit +/** + * @param upperLimit The maximum limit angle of the joint (in radian) + */ void HingeJoint::setMaxAngleLimit(decimal upperLimit) { assert(upperLimit >= 0 && upperLimit <= 2.0 * PI); @@ -689,6 +703,9 @@ void HingeJoint::setMotorSpeed(decimal motorSpeed) { } // Set the maximum motor torque +/** + * @param maxMotorTorque The maximum torque (in Newtons) of the joint motor + */ void HingeJoint::setMaxMotorTorque(decimal maxMotorTorque) { if (maxMotorTorque != mMaxMotorTorque) { diff --git a/src/constraint/HingeJoint.h b/src/constraint/HingeJoint.h index 143cda4e..9ca1ba53 100644 --- a/src/constraint/HingeJoint.h +++ b/src/constraint/HingeJoint.h @@ -71,6 +71,14 @@ struct HingeJointInfo : public JointInfo { decimal maxMotorTorque; /// Constructor without limits and without motor + /** + * @param rigidBody1 The first body of the joint + * @param rigidBody2 The second body of the joint + * @param initAnchorPointWorldSpace The initial anchor point in world-space + * coordinates + * @param initRotationAxisWorld The initial rotation axis in world-space + * coordinates + */ HingeJointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2, const Vector3& initAnchorPointWorldSpace, const Vector3& initRotationAxisWorld) @@ -81,6 +89,14 @@ struct HingeJointInfo : public JointInfo { motorSpeed(0), maxMotorTorque(0) {} /// Constructor with limits but without motor + /** + * @param rigidBody1 The first body of the joint + * @param rigidBody2 The second body of the joint + * @param initAnchorPointWorldSpace The initial anchor point in world-space coordinates + * @param initRotationAxisWorld The intial rotation axis in world-space coordinates + * @param initMinAngleLimit The initial minimum limit angle (in radian) + * @param initMaxAngleLimit The initial maximum limit angle (in radian) + */ HingeJointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2, const Vector3& initAnchorPointWorldSpace, const Vector3& initRotationAxisWorld, @@ -93,6 +109,16 @@ struct HingeJointInfo : public JointInfo { maxMotorTorque(0) {} /// Constructor with limits and motor + /** + * @param rigidBody1 The first body of the joint + * @param rigidBody2 The second body of the joint + * @param initAnchorPointWorldSpace The initial anchor point in world-space + * @param initRotationAxisWorld The initial rotation axis in world-space + * @param initMinAngleLimit The initial minimum limit angle (in radian) + * @param initMaxAngleLimit The initial maximum limit angle (in radian) + * @param initMotorSpeed The initial motor speed of the joint (in radian per second) + * @param initMaxMotorTorque The initial maximum motor torque (in Newtons) + */ HingeJointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2, const Vector3& initAnchorPointWorldSpace, const Vector3& initRotationAxisWorld, @@ -204,7 +230,7 @@ class HingeJoint : public Joint { /// True if the motor of the joint in enabled bool mIsMotorEnabled; - /// Lower limit (minimum allowed rotation angle in radi) + /// Lower limit (minimum allowed rotation angle in radian) decimal mLowerLimit; /// Upper limit (maximum translation distance) @@ -216,7 +242,7 @@ class HingeJoint : public Joint { /// True if the upper limit is violated bool mIsUpperLimitViolated; - /// Motor speed + /// Motor speed (in rad/s) decimal mMotorSpeed; /// Maximum motor torque (in Newtons) that can be applied to reach to desired motor speed @@ -312,37 +338,59 @@ class HingeJoint : public Joint { decimal getMotorTorque(decimal timeStep) const; }; -// Return true if the limits or the joint are enabled +// Return true if the limits of the joint are enabled +/** + * @return True if the limits of the joint are enabled and false otherwise + */ inline bool HingeJoint::isLimitEnabled() const { return mIsLimitEnabled; } // Return true if the motor of the joint is enabled +/** + * @return True if the motor of joint is enabled and false otherwise + */ inline bool HingeJoint::isMotorEnabled() const { return mIsMotorEnabled; } // Return the minimum angle limit +/** + * @return The minimum limit angle of the joint (in radian) + */ inline decimal HingeJoint::getMinAngleLimit() const { return mLowerLimit; } // Return the maximum angle limit +/** + * @return The maximum limit angle of the joint (in radian) + */ inline decimal HingeJoint::getMaxAngleLimit() const { return mUpperLimit; } // Return the motor speed +/** + * @return The current speed of the joint motor (in radian per second) + */ inline decimal HingeJoint::getMotorSpeed() const { return mMotorSpeed; } // Return the maximum motor torque +/** + * @return The maximum torque of the joint motor (in Newtons) + */ inline decimal HingeJoint::getMaxMotorTorque() const { return mMaxMotorTorque; } // Return the intensity of the current torque applied for the joint motor +/** + * @param timeStep The current time step (in seconds) + * @return The intensity of the current torque (in Newtons) of the joint motor + */ inline decimal HingeJoint::getMotorTorque(decimal timeStep) const { return mImpulseMotor / timeStep; } diff --git a/src/constraint/Joint.h b/src/constraint/Joint.h index 082ffd4b..d2382148 100644 --- a/src/constraint/Joint.h +++ b/src/constraint/Joint.h @@ -203,26 +203,42 @@ class Joint { }; // Return the reference to the body 1 +/** + * @return The first body involved in the joint + */ inline RigidBody* const Joint::getBody1() const { return mBody1; } // Return the reference to the body 2 +/** + * @return The second body involved in the joint + */ inline RigidBody* const Joint::getBody2() const { return mBody2; } // Return true if the joint is active +/** + * @return True if the joint is active + */ inline bool Joint::isActive() const { return (mBody1->isActive() && mBody2->isActive()); } // Return the type of the joint +/** + * @return The type of the joint + */ inline JointType Joint::getType() const { return mType; } // Return true if the collision between the two bodies of the joint is enabled +/** + * @return True if the collision is enabled between the two bodies of the joint + * is enabled and false otherwise + */ inline bool Joint::isCollisionEnabled() const { return mIsCollisionEnabled; } diff --git a/src/constraint/SliderJoint.cpp b/src/constraint/SliderJoint.cpp index b3cfbb14..e51b1739 100644 --- a/src/constraint/SliderJoint.cpp +++ b/src/constraint/SliderJoint.cpp @@ -656,6 +656,10 @@ void SliderJoint::solvePositionConstraint(const ConstraintSolverData& constraint } // Enable/Disable the limits of the joint +/** + * @param isLimitEnabled True if you want to enable the joint limits and false + * otherwise + */ void SliderJoint::enableLimit(bool isLimitEnabled) { if (isLimitEnabled != mIsLimitEnabled) { @@ -668,6 +672,10 @@ void SliderJoint::enableLimit(bool isLimitEnabled) { } // Enable/Disable the motor of the joint +/** + * @param isMotorEnabled True if you want to enable the joint motor and false + * otherwise + */ void SliderJoint::enableMotor(bool isMotorEnabled) { mIsMotorEnabled = isMotorEnabled; @@ -679,9 +687,13 @@ void SliderJoint::enableMotor(bool isMotorEnabled) { } // Return the current translation value of the joint -// TODO : Check if we need to compare rigid body position or center of mass here +/** + * @return The current translation distance of the joint (in meters) + */ decimal SliderJoint::getTranslation() const { + // TODO : Check if we need to compare rigid body position or center of mass here + // Get the bodies positions and orientations const Vector3& x1 = mBody1->getTransform().getPosition(); const Vector3& x2 = mBody2->getTransform().getPosition(); @@ -704,6 +716,9 @@ decimal SliderJoint::getTranslation() const { } // Set the minimum translation limit +/** + * @param lowerLimit The minimum translation limit of the joint (in meters) + */ void SliderJoint::setMinTranslationLimit(decimal lowerLimit) { assert(lowerLimit <= mUpperLimit); @@ -718,6 +733,9 @@ void SliderJoint::setMinTranslationLimit(decimal lowerLimit) { } // Set the maximum translation limit +/** + * @param lowerLimit The maximum translation limit of the joint (in meters) + */ void SliderJoint::setMaxTranslationLimit(decimal upperLimit) { assert(mLowerLimit <= upperLimit); @@ -744,6 +762,9 @@ void SliderJoint::resetLimits() { } // Set the motor speed +/** + * @param motorSpeed The speed of the joint motor (in meters per second) + */ void SliderJoint::setMotorSpeed(decimal motorSpeed) { if (motorSpeed != mMotorSpeed) { @@ -757,6 +778,9 @@ void SliderJoint::setMotorSpeed(decimal motorSpeed) { } // Set the maximum motor force +/** + * @param maxMotorForce The maximum force of the joint motor (in Newton x meters) + */ void SliderJoint::setMaxMotorForce(decimal maxMotorForce) { if (maxMotorForce != mMaxMotorForce) { diff --git a/src/constraint/SliderJoint.h b/src/constraint/SliderJoint.h index 2938baac..512309ad 100644 --- a/src/constraint/SliderJoint.h +++ b/src/constraint/SliderJoint.h @@ -68,6 +68,12 @@ struct SliderJointInfo : public JointInfo { decimal maxMotorForce; /// Constructor without limits and without motor + /** + * @param rigidBody1 The first body of the joint + * @param rigidBody2 The second body of the joint + * @param initAnchorPointWorldSpace The initial anchor point in world-space + * @param initSliderAxisWorldSpace The initial slider axis in world-space + */ SliderJointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2, const Vector3& initAnchorPointWorldSpace, const Vector3& initSliderAxisWorldSpace) @@ -78,6 +84,14 @@ struct SliderJointInfo : public JointInfo { maxTranslationLimit(1.0), motorSpeed(0), maxMotorForce(0) {} /// Constructor with limits and no motor + /** + * @param rigidBody1 The first body of the joint + * @param rigidBody2 The second body of the joint + * @param initAnchorPointWorldSpace The initial anchor point in world-space + * @param initSliderAxisWorldSpace The initial slider axis in world-space + * @param initMinTranslationLimit The initial minimum translation limit (in meters) + * @param initMaxTranslationLimit The initial maximum translation limit (in meters) + */ SliderJointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2, const Vector3& initAnchorPointWorldSpace, const Vector3& initSliderAxisWorldSpace, @@ -91,6 +105,16 @@ struct SliderJointInfo : public JointInfo { maxMotorForce(0) {} /// Constructor with limits and motor + /** + * @param rigidBody1 The first body of the joint + * @param rigidBody2 The second body of the joint + * @param initAnchorPointWorldSpace The initial anchor point in world-space + * @param initSliderAxisWorldSpace The initial slider axis in world-space + * @param initMinTranslationLimit The initial minimum translation limit (in meters) + * @param initMaxTranslationLimit The initial maximum translation limit (in meters) + * @param initMotorSpeed The initial speed of the joint motor (in meters per second) + * @param initMaxMotorForce The initial maximum motor force of the joint (in Newtons x meters) + */ SliderJointInfo(RigidBody* rigidBody1, RigidBody* rigidBody2, const Vector3& initAnchorPointWorldSpace, const Vector3& initSliderAxisWorldSpace, @@ -230,7 +254,7 @@ class SliderJoint : public Joint { /// True if the upper limit is violated bool mIsUpperLimitViolated; - /// Motor speed + /// Motor speed (in m/s) decimal mMotorSpeed; /// Maximum motor force (in Newtons) that can be applied to reach to desired motor speed @@ -316,36 +340,58 @@ class SliderJoint : public Joint { }; // Return true if the limits or the joint are enabled +/** + * @return True if the joint limits are enabled + */ inline bool SliderJoint::isLimitEnabled() const { return mIsLimitEnabled; } // Return true if the motor of the joint is enabled +/** + * @return True if the joint motor is enabled + */ inline bool SliderJoint::isMotorEnabled() const { return mIsMotorEnabled; } // Return the minimum translation limit +/** + * @return The minimum translation limit of the joint (in meters) + */ inline decimal SliderJoint::getMinTranslationLimit() const { return mLowerLimit; } // Return the maximum translation limit +/** + * @return The maximum translation limit of the joint (in meters) + */ inline decimal SliderJoint::getMaxTranslationLimit() const { return mUpperLimit; } // Return the motor speed +/** + * @return The current motor speed of the joint (in meters per second) + */ inline decimal SliderJoint::getMotorSpeed() const { return mMotorSpeed; } // Return the maximum motor force +/** + * @return The maximum force of the joint motor (in Newton x meters) + */ inline decimal SliderJoint::getMaxMotorForce() const { return mMaxMotorForce; } // Return the intensity of the current force applied for the joint motor +/** + * @param timeStep Time step (in seconds) + * @return The current force of the joint motor (in Newton x meters) + */ inline decimal SliderJoint::getMotorForce(decimal timeStep) const { return mImpulseMotor / timeStep; } diff --git a/src/engine/CollisionWorld.cpp b/src/engine/CollisionWorld.cpp index c3747134..9b3dc54d 100644 --- a/src/engine/CollisionWorld.cpp +++ b/src/engine/CollisionWorld.cpp @@ -45,6 +45,10 @@ CollisionWorld::~CollisionWorld() { } // Create a collision body and add it to the world +/** + * @param transform Transformation mapping the local-space of the body to world-space + * @return A pointer to the body that has been created in the world + */ CollisionBody* CollisionWorld::createCollisionBody(const Transform& transform) { // Get the next available body ID @@ -67,6 +71,9 @@ CollisionBody* CollisionWorld::createCollisionBody(const Transform& transform) { } // Destroy a collision body +/** + * @param collisionBody Pointer to the body to destroy + */ void CollisionWorld::destroyCollisionBody(CollisionBody* collisionBody) { // Remove all the collision shapes of the body @@ -178,6 +185,11 @@ void CollisionWorld::resetContactManifoldListsOfBodies() { } // Test if the AABBs of two bodies overlap +/** + * @param body1 Pointer to the first body to test + * @param body2 Pointer to the second body to test + * @return True if the AABBs of the two bodies overlap and false otherwise + */ bool CollisionWorld::testAABBOverlap(const CollisionBody* body1, const CollisionBody* body2) const { @@ -194,6 +206,10 @@ bool CollisionWorld::testAABBOverlap(const CollisionBody* body1, // Test and report collisions between a given shape and all the others // shapes of the world. +/** + * @param shape Pointer to the proxy shape to test + * @param callback Pointer to the object with the callback method + */ void CollisionWorld::testCollision(const ProxyShape* shape, CollisionCallback* callback) { @@ -210,6 +226,11 @@ void CollisionWorld::testCollision(const ProxyShape* shape, } // Test and report collisions between two given shapes +/** + * @param shape1 Pointer to the first proxy shape to test + * @param shape2 Pointer to the second proxy shape to test + * @param callback Pointer to the object with the callback method + */ void CollisionWorld::testCollision(const ProxyShape* shape1, const ProxyShape* shape2, CollisionCallback* callback) { @@ -229,6 +250,10 @@ void CollisionWorld::testCollision(const ProxyShape* shape1, // Test and report collisions between a body and all the others bodies of the // world +/** + * @param body Pointer to the first body to test + * @param callback Pointer to the object with the callback method + */ void CollisionWorld::testCollision(const CollisionBody* body, CollisionCallback* callback) { @@ -251,6 +276,11 @@ void CollisionWorld::testCollision(const CollisionBody* body, } // Test and report collisions between two bodies +/** + * @param body1 Pointer to the first body to test + * @param body2 Pointer to the second body to test + * @param callback Pointer to the object with the callback method + */ void CollisionWorld::testCollision(const CollisionBody* body1, const CollisionBody* body2, CollisionCallback* callback) { @@ -276,6 +306,9 @@ void CollisionWorld::testCollision(const CollisionBody* body1, } // Test and report collisions between all shapes of the world +/** + * @param callback Pointer to the object with the callback method + */ void CollisionWorld::testCollision(CollisionCallback* callback) { // Reset all the contact manifolds lists of each body diff --git a/src/engine/CollisionWorld.h b/src/engine/CollisionWorld.h index 8a89ac35..a400b29e 100644 --- a/src/engine/CollisionWorld.h +++ b/src/engine/CollisionWorld.h @@ -167,16 +167,28 @@ class CollisionWorld { }; // Return an iterator to the beginning of the bodies of the physics world +/** + * @return An starting iterator to the set of bodies of the world + */ inline std::set::iterator CollisionWorld::getBodiesBeginIterator() { return mBodies.begin(); } // Return an iterator to the end of the bodies of the physics world +/** + * @return An ending iterator to the set of bodies of the world + */ inline std::set::iterator CollisionWorld::getBodiesEndIterator() { return mBodies.end(); } // Ray cast method +/** + * @param ray Ray to use for raycasting + * @param raycastCallback Pointer to the class with the callback method + * @param raycastWithCategoryMaskBits Bits mask corresponding to the category of + * bodies to be raycasted + */ inline void CollisionWorld::raycast(const Ray& ray, RaycastCallback* raycastCallback, unsigned short raycastWithCategoryMaskBits) const { @@ -184,6 +196,11 @@ inline void CollisionWorld::raycast(const Ray& ray, } // Test if the AABBs of two proxy shapes overlap +/** + * @param shape1 Pointer to the first proxy shape to test + * @param shape2 Pointer to the second proxy shape to test + * @return + */ inline bool CollisionWorld::testAABBOverlap(const ProxyShape* shape1, const ProxyShape* shape2) const { diff --git a/src/engine/DynamicsWorld.cpp b/src/engine/DynamicsWorld.cpp index c541e3eb..357ce125 100644 --- a/src/engine/DynamicsWorld.cpp +++ b/src/engine/DynamicsWorld.cpp @@ -35,6 +35,10 @@ using namespace reactphysics3d; using namespace std; // Constructor +/** + * @param gravity Gravity vector in the world (in meters per second squared) + * @param timeStep Time step for an internal physics tick (in seconds) + */ DynamicsWorld::DynamicsWorld(const Vector3 &gravity, decimal timeStep = DEFAULT_TIMESTEP) : CollisionWorld(), mTimer(timeStep), mContactSolver(mMapBodyToConstrainedVelocityIndex), @@ -453,6 +457,10 @@ void DynamicsWorld::solvePositionCorrection() { } // Create a rigid body into the physics world +/** + * @param transform Transformation from body local-space to world-space + * @return A pointer to the body that has been created in the world + */ RigidBody* DynamicsWorld::createRigidBody(const Transform& transform) { // Compute the body ID @@ -475,6 +483,9 @@ RigidBody* DynamicsWorld::createRigidBody(const Transform& transform) { } // Destroy a rigid body and all the joints which it belongs +/** + * @param rigidBody Pointer to the body you want to destroy + */ void DynamicsWorld::destroyRigidBody(RigidBody* rigidBody) { // Remove all the collision shapes of the body @@ -504,6 +515,10 @@ void DynamicsWorld::destroyRigidBody(RigidBody* rigidBody) { } // Create a joint between two bodies in the world and return a pointer to the new joint +/** + * @param jointInfo The information that is necessary to create the joint + * @return A pointer to the joint that has been created in the world + */ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { Joint* newJoint = NULL; @@ -573,6 +588,9 @@ Joint* DynamicsWorld::createJoint(const JointInfo& jointInfo) { } // Destroy a joint +/** + * @param joint Pointer to the joint you want to destroy + */ void DynamicsWorld::destroyJoint(Joint* joint) { assert(joint != NULL); @@ -842,7 +860,13 @@ void DynamicsWorld::updateSleepingBodies() { } } -// Enable/Disable the sleeping technique +// Enable/Disable the sleeping technique. +/// The sleeping technique is used to put bodies that are not moving into sleep +/// to speed up the simulation. +/** + * @param isSleepingEnabled True if you want to enable the sleeping technique + * and false otherwise + */ void DynamicsWorld::enableSleeping(bool isSleepingEnabled) { mIsSleepingEnabled = isSleepingEnabled; @@ -862,6 +886,10 @@ void DynamicsWorld::enableSleeping(bool isSleepingEnabled) { // shapes of the world. /// This method should be called after calling the /// DynamicsWorld::update() method that will compute the collisions. +/** + * @param shape Pointer to the proxy shape to test + * @param callback Pointer to the object with the callback method + */ void DynamicsWorld::testCollision(const ProxyShape* shape, CollisionCallback* callback) { @@ -877,6 +905,11 @@ void DynamicsWorld::testCollision(const ProxyShape* shape, // Test and report collisions between two given shapes. /// This method should be called after calling the /// DynamicsWorld::update() method that will compute the collisions. +/** + * @param shape1 Pointer to the first proxy shape to test + * @param shape2 Pointer to the second proxy shape to test + * @param callback Pointer to the object with the callback method + */ void DynamicsWorld::testCollision(const ProxyShape* shape1, const ProxyShape* shape2, CollisionCallback* callback) { @@ -895,6 +928,10 @@ void DynamicsWorld::testCollision(const ProxyShape* shape1, // world. /// This method should be called after calling the /// DynamicsWorld::update() method that will compute the collisions. +/** + * @param body Pointer to the first body to test + * @param callback Pointer to the object with the callback method + */ void DynamicsWorld::testCollision(const CollisionBody* body, CollisionCallback* callback) { @@ -916,6 +953,11 @@ void DynamicsWorld::testCollision(const CollisionBody* body, // Test and report collisions between two bodies. /// This method should be called after calling the /// DynamicsWorld::update() method that will compute the collisions. +/** + * @param body1 Pointer to the first body to test + * @param body2 Pointer to the second body to test + * @param callback Pointer to the object with the callback method + */ void DynamicsWorld::testCollision(const CollisionBody* body1, const CollisionBody* body2, CollisionCallback* callback) { @@ -940,6 +982,9 @@ void DynamicsWorld::testCollision(const CollisionBody* body1, // Test and report collisions between all shapes of the world. /// This method should be called after calling the /// DynamicsWorld::update() method that will compute the collisions. +/** + * @param callback Pointer to the object with the callback method + */ void DynamicsWorld::testCollision(CollisionCallback* callback) { std::set emptySet; diff --git a/src/engine/DynamicsWorld.h b/src/engine/DynamicsWorld.h index 83e5d6d2..4ffd08f9 100644 --- a/src/engine/DynamicsWorld.h +++ b/src/engine/DynamicsWorld.h @@ -174,6 +174,9 @@ class DynamicsWorld : public CollisionWorld { /// Put bodies to sleep if needed. void updateSleepingBodies(); + /// Add the joint to the list of joints of the two bodies involved in the joint + void addJointToBody(Joint* joint); + public : // -------------------- Methods -------------------- // @@ -221,9 +224,6 @@ class DynamicsWorld : public CollisionWorld { /// Destroy a joint void destroyJoint(Joint* joint); - /// Add the joint to the list of joints of the two bodies involved in the joint - void addJointToBody(Joint* joint); - /// Return the gravity vector of the world Vector3 getGravity() const; @@ -324,16 +324,25 @@ inline void DynamicsWorld::stop() { } // Set the number of iterations for the velocity constraint solver +/** + * @param nbIterations Number of iterations for the velocity solver + */ inline void DynamicsWorld::setNbIterationsVelocitySolver(uint nbIterations) { mNbVelocitySolverIterations = nbIterations; } // Set the number of iterations for the position constraint solver +/** + * @param nbIterations Number of iterations for the position solver + */ inline void DynamicsWorld::setNbIterationsPositionSolver(uint nbIterations) { mNbPositionSolverIterations = nbIterations; } // Set the position correction technique used for contacts +/** + * @param technique Technique used for the position correction (Baumgarte or Split Impulses) + */ inline void DynamicsWorld::setContactsPositionCorrectionTechnique( ContactsPositionCorrectionTechnique technique) { if (technique == BAUMGARTE_CONTACTS) { @@ -345,6 +354,9 @@ inline void DynamicsWorld::setContactsPositionCorrectionTechnique( } // Set the position correction technique used for joints +/** + * @param technique Technique used for the joins position correction (Baumgarte or Non Linear Gauss Seidel) + */ inline void DynamicsWorld::setJointsPositionCorrectionTechnique( JointsPositionCorrectionTechnique technique) { if (technique == BAUMGARTE_JOINTS) { @@ -357,56 +369,91 @@ inline void DynamicsWorld::setJointsPositionCorrectionTechnique( // Activate or deactivate the solving of friction constraints at the center of // the contact manifold instead of solving them at each contact point +/** + * @param isActive True if you want the friction to be solved at the center of + * the contact manifold and false otherwise + */ inline void DynamicsWorld::setIsSolveFrictionAtContactManifoldCenterActive(bool isActive) { mContactSolver.setIsSolveFrictionAtContactManifoldCenterActive(isActive); } // Return the gravity vector of the world +/** + * @return The current gravity vector (in meter per seconds squared) + */ inline Vector3 DynamicsWorld::getGravity() const { return mGravity; } // Return if the gravity is enaled +/** + * @return True if the gravity is enabled in the world + */ inline bool DynamicsWorld::isGravityEnabled() const { return mIsGravityEnabled; } // Enable/Disable the gravity +/** + * @param isGravityEnabled True if you want to enable the gravity in the world + * and false otherwise + */ inline void DynamicsWorld::setIsGratityEnabled(bool isGravityEnabled) { mIsGravityEnabled = isGravityEnabled; } // Return the number of rigid bodies in the world +/** + * @return Number of rigid bodies in the world + */ inline uint DynamicsWorld::getNbRigidBodies() const { return mRigidBodies.size(); } /// Return the number of joints in the world +/** + * @return Number of joints in the world + */ inline uint DynamicsWorld::getNbJoints() const { return mJoints.size(); } // Return an iterator to the beginning of the bodies of the physics world +/** + * @return Starting iterator of the set of rigid bodies + */ inline std::set::iterator DynamicsWorld::getRigidBodiesBeginIterator() { return mRigidBodies.begin(); } // Return an iterator to the end of the bodies of the physics world +/** + * @return Ending iterator of the set of rigid bodies + */ inline std::set::iterator DynamicsWorld::getRigidBodiesEndIterator() { return mRigidBodies.end(); } // Return the current physics time (in seconds) +/** + * @return The current physics time (in seconds) + */ inline long double DynamicsWorld::getPhysicsTime() const { return mTimer.getPhysicsTime(); } // Return true if the sleeping technique is enabled +/** + * @return True if the sleeping technique is enabled and false otherwise + */ inline bool DynamicsWorld::isSleepingEnabled() const { return mIsSleepingEnabled; } // Return the current sleep linear velocity +/** + * @return The sleep linear velocity (in meters per second) + */ inline decimal DynamicsWorld::getSleepLinearVelocity() const { return mSleepLinearVelocity; } @@ -415,12 +462,18 @@ inline decimal DynamicsWorld::getSleepLinearVelocity() const { /// When the velocity of a body becomes smaller than the sleep linear/angular /// velocity for a given amount of time, the body starts sleeping and does not need /// to be simulated anymore. +/** + * @param sleepLinearVelocity The sleep linear velocity (in meters per second) + */ inline void DynamicsWorld::setSleepLinearVelocity(decimal sleepLinearVelocity) { assert(sleepLinearVelocity >= decimal(0.0)); mSleepLinearVelocity = sleepLinearVelocity; } // Return the current sleep angular velocity +/** + * @return The sleep angular velocity (in radian per second) + */ inline decimal DynamicsWorld::getSleepAngularVelocity() const { return mSleepAngularVelocity; } @@ -429,18 +482,27 @@ inline decimal DynamicsWorld::getSleepAngularVelocity() const { /// When the velocity of a body becomes smaller than the sleep linear/angular /// velocity for a given amount of time, the body starts sleeping and does not need /// to be simulated anymore. +/** + * @param sleepAngularVelocity The sleep angular velocity (in radian per second) + */ inline void DynamicsWorld::setSleepAngularVelocity(decimal sleepAngularVelocity) { assert(sleepAngularVelocity >= decimal(0.0)); mSleepAngularVelocity = sleepAngularVelocity; } // Return the time a body is required to stay still before sleeping +/** + * @return Time a body is required to stay still before sleeping (in seconds) + */ inline decimal DynamicsWorld::getTimeBeforeSleep() const { return mTimeBeforeSleep; } // Set the time a body is required to stay still before sleeping +/** + * @param timeBeforeSleep Time a body is required to stay still before sleeping (in seconds) + */ inline void DynamicsWorld::setTimeBeforeSleep(decimal timeBeforeSleep) { assert(timeBeforeSleep >= decimal(0.0)); mTimeBeforeSleep = timeBeforeSleep; @@ -448,6 +510,10 @@ inline void DynamicsWorld::setTimeBeforeSleep(decimal timeBeforeSleep) { // Set an event listener object to receive events callbacks. /// If you use NULL as an argument, the events callbacks will be disabled. +/** + * @param eventListener Pointer to the event listener object that will receive + * event callbacks during the simulation + */ inline void DynamicsWorld::setEventListener(EventListener* eventListener) { mEventListener = eventListener; } diff --git a/src/engine/EventListener.h b/src/engine/EventListener.h index 1a8fca05..01ec87eb 100644 --- a/src/engine/EventListener.h +++ b/src/engine/EventListener.h @@ -50,9 +50,15 @@ class EventListener { virtual ~EventListener() {} /// Called when a new contact point is found between two bodies that were separated before + /** + * @param contact Information about the contact + */ virtual void beginContact(const ContactPointInfo& contact) {} /// Called when a new contact point is found between two bodies + /** + * @param contact Information about the contact + */ virtual void newContact(const ContactPointInfo& contact) {} /// Called at the beginning of an internal tick of the simulation step. diff --git a/src/engine/Material.h b/src/engine/Material.h index 3909c6b9..f924b9aa 100644 --- a/src/engine/Material.h +++ b/src/engine/Material.h @@ -80,6 +80,9 @@ class Material { }; // Return the bounciness +/** + * @return Bounciness factor (between 0 and 1) where 1 is very bouncy + */ inline decimal Material::getBounciness() const { return mBounciness; } @@ -87,12 +90,18 @@ inline decimal Material::getBounciness() const { // Set the bounciness. /// The bounciness should be a value between 0 and 1. The value 1 is used for a /// very bouncy body and zero is used for a body that is not bouncy at all. +/** + * @param bounciness Bounciness factor (between 0 and 1) where 1 is very bouncy + */ inline void Material::setBounciness(decimal bounciness) { assert(bounciness >= decimal(0.0) && bounciness <= decimal(1.0)); mBounciness = bounciness; } // Return the friction coefficient +/** + * @return Friction coefficient (positive value) + */ inline decimal Material::getFrictionCoefficient() const { return mFrictionCoefficient; } @@ -100,6 +109,9 @@ inline decimal Material::getFrictionCoefficient() const { // Set the friction coefficient. /// The friction coefficient has to be a positive value. The value zero is used for no /// friction at all. +/** + * @param frictionCoefficient Friction coefficient (positive value) + */ inline void Material::setFrictionCoefficient(decimal frictionCoefficient) { assert(frictionCoefficient >= decimal(0.0)); mFrictionCoefficient = frictionCoefficient;