Fix some warnings
This commit is contained in:
parent
dac5a2729a
commit
f38803d75a
|
@ -153,7 +153,7 @@ class RigidBody : public CollisionBody {
|
|||
decimal getRestitution() const;
|
||||
|
||||
/// Set the restitution coefficient
|
||||
void setRestitution(decimal restitution) throw(std::invalid_argument);
|
||||
void setRestitution(decimal restitution);
|
||||
|
||||
/// Get the friction coefficient
|
||||
decimal getFrictionCoefficient() const;
|
||||
|
@ -273,15 +273,9 @@ inline decimal RigidBody::getRestitution() const {
|
|||
}
|
||||
|
||||
// Set the restitution coefficient
|
||||
inline void RigidBody::setRestitution(decimal restitution) throw(std::invalid_argument) {
|
||||
|
||||
// Check if the restitution coefficient is between 0 and 1
|
||||
if (restitution >= 0.0 && restitution <= 1.0) {
|
||||
mRestitution = restitution;
|
||||
}
|
||||
else {
|
||||
throw std::invalid_argument("Error : the restitution coefficent must be between 0 and 1");
|
||||
}
|
||||
inline void RigidBody::setRestitution(decimal restitution) {
|
||||
assert(restitution >= 0.0 && restitution <= 1.0);
|
||||
mRestitution = restitution;
|
||||
}
|
||||
|
||||
// Get the friction coefficient
|
||||
|
|
|
@ -73,7 +73,8 @@ void CollisionDetection::computeCollisionDetection() {
|
|||
void CollisionDetection::computeBroadPhase() {
|
||||
|
||||
// Notify the broad-phase algorithm about the bodies that have moved since last frame
|
||||
for (set<CollisionBody*>::iterator it = mWorld->getBodiesBeginIterator(); it != mWorld->getBodiesEndIterator(); it++) {
|
||||
for (set<CollisionBody*>::iterator it = mWorld->getBodiesBeginIterator();
|
||||
it != mWorld->getBodiesEndIterator(); it++) {
|
||||
|
||||
// If the body has moved
|
||||
if ((*it)->getHasMoved()) {
|
||||
|
@ -102,14 +103,18 @@ void CollisionDetection::computeNarrowPhase() {
|
|||
mWorld->updateOverlappingPair(pair);
|
||||
|
||||
// Select the narrow phase algorithm to use according to the two collision shapes
|
||||
NarrowPhaseAlgorithm& narrowPhaseAlgorithm = SelectNarrowPhaseAlgorithm(body1->getCollisionShape(), body2->getCollisionShape());
|
||||
NarrowPhaseAlgorithm& narrowPhaseAlgorithm = SelectNarrowPhaseAlgorithm(
|
||||
body1->getCollisionShape(),
|
||||
body2->getCollisionShape());
|
||||
|
||||
// Notify the narrow-phase algorithm about the overlapping pair we are going to test
|
||||
narrowPhaseAlgorithm.setCurrentOverlappingPair(pair);
|
||||
|
||||
// Use the narrow-phase collision detection algorithm to check if there really is a collision
|
||||
// Use the narrow-phase collision detection algorithm to check
|
||||
// if there really is a collision
|
||||
if (narrowPhaseAlgorithm.testCollision(body1->getCollisionShape(), body1->getTransform(),
|
||||
body2->getCollisionShape(), body2->getTransform(), contactInfo)) {
|
||||
body2->getCollisionShape(), body2->getTransform(),
|
||||
contactInfo)) {
|
||||
assert(contactInfo != NULL);
|
||||
|
||||
// Notify the world about the new narrow-phase contact
|
||||
|
@ -130,11 +135,14 @@ void CollisionDetection::broadPhaseNotifyAddedOverlappingPair(BodyPair* addedPai
|
|||
bodyindexpair indexPair = addedPair->getBodiesIndexPair();
|
||||
|
||||
// Create the corresponding broad-phase pair object
|
||||
BroadPhasePair* broadPhasePair = new (mMemoryPoolBroadPhasePairs.allocateObject()) BroadPhasePair(addedPair->body1, addedPair->body2);
|
||||
BroadPhasePair* broadPhasePair = new (mMemoryPoolBroadPhasePairs.allocateObject())
|
||||
BroadPhasePair(addedPair->body1, addedPair->body2);
|
||||
assert(broadPhasePair != NULL);
|
||||
|
||||
// Add the pair into the set of overlapping pairs (if not there yet)
|
||||
pair<map<bodyindexpair, BroadPhasePair*>::iterator, bool> check = mOverlappingPairs.insert(make_pair(indexPair, broadPhasePair));
|
||||
pair<map<bodyindexpair, BroadPhasePair*>::iterator, bool> check = mOverlappingPairs.insert(
|
||||
make_pair(indexPair,
|
||||
broadPhasePair));
|
||||
assert(check.second);
|
||||
|
||||
// Notify the world about the new broad-phase overlapping pair
|
||||
|
|
|
@ -101,8 +101,8 @@ void SweepAndPruneAlgorithm::addObject(CollisionBody* body, const AABB& aabb) {
|
|||
// Create a new box
|
||||
BoxAABB* box = &mBoxes[boxIndex];
|
||||
box->body = body;
|
||||
const uint minEndPointValue = encodeFloatIntoInteger(DECIMAL_LARGEST - 2.0);
|
||||
const uint maxEndPointValue = encodeFloatIntoInteger(DECIMAL_LARGEST - 1.0);
|
||||
const uint minEndPointValue = encodeFloatIntoInteger(FLT_MAX - 2.0f);
|
||||
const uint maxEndPointValue = encodeFloatIntoInteger(FLT_MAX - 1.0f);
|
||||
for (uint axis=0; axis<3; axis++) {
|
||||
box->min[axis] = indexLimitEndPoint;
|
||||
box->max[axis] = indexLimitEndPoint + 1;
|
||||
|
|
|
@ -72,7 +72,7 @@ bool TriangleEPA::computeClosestPoint(const Vector3* vertices) {
|
|||
// If the determinant is positive
|
||||
if (mDet > 0.0) {
|
||||
// Compute the closest point v
|
||||
mClosestPoint = p0 + 1.0 / mDet * (mLambda1 * v1 + mLambda2 * v2);
|
||||
mClosestPoint = p0 + decimal(1.0) / mDet * (mLambda1 * v1 + mLambda2 * v2);
|
||||
|
||||
// Compute the square distance of closest point to the origin
|
||||
mDistSquare = mClosestPoint.dot(mClosestPoint);
|
||||
|
|
|
@ -184,7 +184,7 @@ inline bool TriangleEPA::isVisibleFromVertex(const Vector3* vertices, uint index
|
|||
// Compute the point of an object closest to the origin
|
||||
inline Vector3 TriangleEPA::computeClosestPointOfObject(const Vector3* supportPointsOfObject) const{
|
||||
const Vector3& p0 = supportPointsOfObject[mIndicesVertices[0]];
|
||||
return p0 + 1.0/mDet * (mLambda1 * (supportPointsOfObject[mIndicesVertices[1]] - p0) +
|
||||
return p0 + decimal(1.0)/mDet * (mLambda1 * (supportPointsOfObject[mIndicesVertices[1]] - p0) +
|
||||
mLambda2 * (supportPointsOfObject[mIndicesVertices[2]] - p0));
|
||||
}
|
||||
|
||||
|
|
|
@ -309,7 +309,7 @@ void Simplex::computeClosestPointsOfAandB(Vector3& pA, Vector3& pB) const {
|
|||
}
|
||||
|
||||
assert(deltaX > 0.0);
|
||||
decimal factor = 1.0 / deltaX;
|
||||
decimal factor = decimal(1.0) / deltaX;
|
||||
pA *= factor;
|
||||
pB *= factor;
|
||||
}
|
||||
|
@ -390,5 +390,5 @@ Vector3 Simplex::computeClosestPointForSubset(Bits subset) {
|
|||
assert(deltaX > 0.0);
|
||||
|
||||
// Return the closet point "v" in the convex hull for the given subset
|
||||
return (1.0 / deltaX) * v;
|
||||
return (decimal(1.0) / deltaX) * v;
|
||||
}
|
||||
|
|
|
@ -44,7 +44,7 @@ using namespace reactphysics3d;
|
|||
|
||||
// Constructor
|
||||
CylinderShape::CylinderShape(decimal radius, decimal height)
|
||||
: CollisionShape(CYLINDER), mRadius(radius), mHalfHeight(height/2.0) {
|
||||
: CollisionShape(CYLINDER), mRadius(radius), mHalfHeight(height/decimal(2.0)) {
|
||||
|
||||
}
|
||||
|
||||
|
|
|
@ -116,7 +116,7 @@ inline void CylinderShape::setRadius(decimal radius) {
|
|||
|
||||
// Return the height
|
||||
inline decimal CylinderShape::getHeight() const {
|
||||
return mHalfHeight * 2.0;
|
||||
return mHalfHeight * decimal(2.0);
|
||||
}
|
||||
|
||||
// Set the height
|
||||
|
|
|
@ -48,7 +48,7 @@ namespace reactphysics3d {
|
|||
|
||||
typedef unsigned int uint;
|
||||
typedef long unsigned int luint;
|
||||
typedef short unsigned int bodyindex;
|
||||
typedef luint bodyindex;
|
||||
typedef std::pair<bodyindex, bodyindex> bodyindexpair;
|
||||
|
||||
// ------------------- Constants ------------------- //
|
||||
|
|
|
@ -35,7 +35,7 @@ Constraint::Constraint(RigidBody* const body1, RigidBody* const body2,
|
|||
mNbConstraints(nbConstraints), mType(type) {
|
||||
|
||||
// Initialize the cached lambda values
|
||||
for (int i=0; i<nbConstraints; i++) {
|
||||
for (uint i=0; i<nbConstraints; i++) {
|
||||
mCachedLambdas.push_back(0.0);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -103,10 +103,10 @@ class Constraint {
|
|||
unsigned int getNbConstraints() const;
|
||||
|
||||
/// Get one cached lambda value
|
||||
decimal getCachedLambda(int index) const;
|
||||
decimal getCachedLambda(uint index) const;
|
||||
|
||||
/// Set on cached lambda value
|
||||
void setCachedLambda(int index, decimal lambda);
|
||||
void setCachedLambda(uint index, decimal lambda);
|
||||
};
|
||||
|
||||
// Return the reference to the body 1
|
||||
|
@ -136,14 +136,14 @@ inline uint Constraint::getNbConstraints() const {
|
|||
}
|
||||
|
||||
// Get one previous lambda value
|
||||
inline decimal Constraint::getCachedLambda(int index) const {
|
||||
assert(index >= 0 && index < mNbConstraints);
|
||||
inline decimal Constraint::getCachedLambda(uint index) const {
|
||||
assert(index < mNbConstraints);
|
||||
return mCachedLambdas[index];
|
||||
}
|
||||
|
||||
// Set on cached lambda value
|
||||
inline void Constraint::setCachedLambda(int index, decimal lambda) {
|
||||
assert(index >= 0 && index < mNbConstraints);
|
||||
inline void Constraint::setCachedLambda(uint index, decimal lambda) {
|
||||
assert(index < mNbConstraints);
|
||||
mCachedLambdas[index] = lambda;
|
||||
}
|
||||
|
||||
|
|
|
@ -24,6 +24,7 @@
|
|||
********************************************************************************/
|
||||
|
||||
// Libraries
|
||||
#include <iostream>
|
||||
#include "ContactManifold.h"
|
||||
|
||||
using namespace reactphysics3d;
|
||||
|
@ -77,8 +78,8 @@ void ContactManifold::addContactPoint(ContactPoint* contact) {
|
|||
}
|
||||
|
||||
// Remove a contact point from the manifold
|
||||
void ContactManifold::removeContactPoint(int index) {
|
||||
assert(index >= 0 && index < mNbContactPoints);
|
||||
void ContactManifold::removeContactPoint(uint index) {
|
||||
assert(index < mNbContactPoints);
|
||||
assert(mNbContactPoints > 0);
|
||||
|
||||
// Call the destructor explicitly and tell the memory pool that
|
||||
|
@ -101,10 +102,11 @@ void ContactManifold::removeContactPoint(int index) {
|
|||
/// the contacts with a too large distance between the contact points in the plane orthogonal to the
|
||||
/// contact normal.
|
||||
void ContactManifold::update(const Transform& transform1, const Transform& transform2) {
|
||||
|
||||
if (mNbContactPoints == 0) return;
|
||||
|
||||
// Update the world coordinates and penetration depth of the contact points in the manifold
|
||||
for (int i=0; i<mNbContactPoints; i++) {
|
||||
for (uint i=0; i<mNbContactPoints; i++) {
|
||||
mContactPoints[i]->setWorldPointOnBody1(transform1 * mContactPoints[i]->getLocalPointOnBody1());
|
||||
mContactPoints[i]->setWorldPointOnBody2(transform2 * mContactPoints[i]->getLocalPointOnBody2());
|
||||
mContactPoints[i]->setPenetrationDepth((mContactPoints[i]->getWorldPointOnBody1() - mContactPoints[i]->getWorldPointOnBody2()).dot(mContactPoints[i]->getNormal()));
|
||||
|
@ -114,8 +116,8 @@ void ContactManifold::update(const Transform& transform1, const Transform& trans
|
|||
PERSISTENT_CONTACT_DIST_THRESHOLD;
|
||||
|
||||
// Remove the contact points that don't represent very well the contact manifold
|
||||
for (int i=mNbContactPoints-1; i>=0; i--) {
|
||||
assert(i>= 0 && i < mNbContactPoints);
|
||||
for (int i=static_cast<int>(mNbContactPoints)-1; i>=0; i--) {
|
||||
assert(i < static_cast<int>(mNbContactPoints));
|
||||
|
||||
// Compute the distance between contact points in the normal direction
|
||||
decimal distanceNormal = -mContactPoints[i]->getPenetrationDepth();
|
||||
|
|
|
@ -106,7 +106,7 @@ class ContactManifold {
|
|||
int getIndexToRemove(int indexMaxPenetration, const Vector3& newPoint) const;
|
||||
|
||||
/// Remove a contact point from the manifold
|
||||
void removeContactPoint(int index);
|
||||
void removeContactPoint(uint index);
|
||||
|
||||
/// Return true if two vectors are approximatively equal
|
||||
bool isApproxEqual(const Vector3& vector1, const Vector3& vector2) const;
|
||||
|
|
|
@ -81,7 +81,7 @@ void DynamicsWorld::update() {
|
|||
if (!mContactManifolds.empty()) {
|
||||
|
||||
// Solve the contacts
|
||||
mContactSolver.solve(mTimer.getTimeStep());
|
||||
mContactSolver.solve(static_cast<decimal>(mTimer.getTimeStep()));
|
||||
}
|
||||
|
||||
// Update the timer
|
||||
|
@ -106,7 +106,7 @@ void DynamicsWorld::update() {
|
|||
|
||||
// Update the position and orientation of the rigid bodies
|
||||
void DynamicsWorld::updateRigidBodiesPositionAndOrientation() {
|
||||
decimal dt = mTimer.getTimeStep();
|
||||
decimal dt = static_cast<decimal>(mTimer.getTimeStep());
|
||||
|
||||
// For each rigid body of the world
|
||||
set<RigidBody*>::iterator it;
|
||||
|
|
|
@ -120,7 +120,7 @@ class Timer {
|
|||
void nextStep();
|
||||
|
||||
/// Compute the interpolation factor
|
||||
double computeInterpolationFactor();
|
||||
decimal computeInterpolationFactor();
|
||||
};
|
||||
|
||||
// Return the timestep of the physics engine
|
||||
|
@ -189,8 +189,8 @@ inline void Timer::nextStep() {
|
|||
}
|
||||
|
||||
// Compute the interpolation factor
|
||||
inline double Timer::computeInterpolationFactor() {
|
||||
return (mAccumulator / mTimeStep);
|
||||
inline decimal Timer::computeInterpolationFactor() {
|
||||
return (decimal(mAccumulator / mTimeStep));
|
||||
}
|
||||
|
||||
// Compute the time since the last update() call and add it to the accumulator
|
||||
|
|
|
@ -65,56 +65,56 @@ Quaternion::Quaternion(const Matrix3x3& matrix) {
|
|||
if (trace < 0.0) {
|
||||
if (matrix[1][1] > matrix[0][0]) {
|
||||
if(matrix[2][2] > matrix[1][1]) {
|
||||
r = sqrt(matrix[2][2] - matrix[0][0] - matrix[1][1] + 1.0);
|
||||
s = 0.5 / r;
|
||||
r = sqrt(matrix[2][2] - matrix[0][0] - matrix[1][1] + decimal(1.0));
|
||||
s = decimal(0.5) / r;
|
||||
|
||||
// Compute the quaternion
|
||||
x = (matrix[2][0] + matrix[0][2])*s;
|
||||
y = (matrix[1][2] + matrix[2][1])*s;
|
||||
z = 0.5*r;
|
||||
w = (matrix[1][0] - matrix[0][1])*s;
|
||||
x = (matrix[2][0] + matrix[0][2]) * s;
|
||||
y = (matrix[1][2] + matrix[2][1]) * s;
|
||||
z = decimal(0.5) * r;
|
||||
w = (matrix[1][0] - matrix[0][1]) * s;
|
||||
}
|
||||
else {
|
||||
r = sqrt(matrix[1][1] - matrix[2][2] - matrix[0][0] + 1.0);
|
||||
s = 0.5 / r;
|
||||
r = sqrt(matrix[1][1] - matrix[2][2] - matrix[0][0] + decimal(1.0));
|
||||
s = decimal(0.5) / r;
|
||||
|
||||
// Compute the quaternion
|
||||
x = (matrix[0][1] + matrix[1][0])*s;
|
||||
y = 0.5 * r;
|
||||
z = (matrix[1][2] + matrix[2][1])*s;
|
||||
w = (matrix[0][2] - matrix[2][0])*s;
|
||||
x = (matrix[0][1] + matrix[1][0]) * s;
|
||||
y = decimal(0.5) * r;
|
||||
z = (matrix[1][2] + matrix[2][1]) * s;
|
||||
w = (matrix[0][2] - matrix[2][0]) * s;
|
||||
}
|
||||
}
|
||||
else if (matrix[2][2] > matrix[0][0]) {
|
||||
r = sqrt(matrix[2][2] - matrix[0][0] - matrix[1][1] + 1.0);
|
||||
s = 0.5 / r;
|
||||
r = sqrt(matrix[2][2] - matrix[0][0] - matrix[1][1] + decimal(1.0));
|
||||
s = decimal(0.5) / r;
|
||||
|
||||
// Compute the quaternion
|
||||
x = (matrix[2][0] + matrix[0][2])*s;
|
||||
y = (matrix[1][2] + matrix[2][1])*s;
|
||||
z = 0.5 * r;
|
||||
w = (matrix[1][0] - matrix[0][1])*s;
|
||||
x = (matrix[2][0] + matrix[0][2]) * s;
|
||||
y = (matrix[1][2] + matrix[2][1]) * s;
|
||||
z = decimal(0.5) * r;
|
||||
w = (matrix[1][0] - matrix[0][1]) * s;
|
||||
}
|
||||
else {
|
||||
r = sqrt(matrix[0][0] - matrix[1][1] - matrix[2][2] + 1.0);
|
||||
s = 0.5 / r;
|
||||
r = sqrt(matrix[0][0] - matrix[1][1] - matrix[2][2] + decimal(1.0));
|
||||
s = decimal(0.5) / r;
|
||||
|
||||
// Compute the quaternion
|
||||
x = 0.5 * r;
|
||||
y = (matrix[0][1] + matrix[1][0])*s;
|
||||
z = (matrix[2][0] - matrix[0][2])*s;
|
||||
w = (matrix[2][1] - matrix[1][2])*s;
|
||||
x = decimal(0.5) * r;
|
||||
y = (matrix[0][1] + matrix[1][0]) * s;
|
||||
z = (matrix[2][0] - matrix[0][2]) * s;
|
||||
w = (matrix[2][1] - matrix[1][2]) * s;
|
||||
}
|
||||
}
|
||||
else {
|
||||
r = sqrt(trace + 1.0);
|
||||
s = 0.5/r;
|
||||
r = sqrt(trace + decimal(1.0));
|
||||
s = decimal(0.5) / r;
|
||||
|
||||
// Compute the quaternion
|
||||
x = (matrix[2][1] - matrix[1][2]) * s;
|
||||
y = (matrix[0][2] - matrix[2][0]) * s;
|
||||
z = (matrix[1][0] - matrix[0][1]) * s;
|
||||
w = 0.5 * r;
|
||||
w = decimal(0.5) * r;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -139,7 +139,7 @@ void Quaternion::getRotationAngleAxis(decimal& angle, Vector3& axis) const {
|
|||
}
|
||||
|
||||
// Compute the roation angle
|
||||
angle = acos(quaternion.w) * 2.0;
|
||||
angle = acos(quaternion.w) * decimal(2.0);
|
||||
|
||||
// Compute the 3D rotation axis
|
||||
Vector3 rotationAxis(quaternion.x, quaternion.y, quaternion.z);
|
||||
|
@ -158,7 +158,7 @@ Matrix3x3 Quaternion::getMatrix() const {
|
|||
decimal s = 0.0;
|
||||
|
||||
if (nQ > 0.0) {
|
||||
s = 2.0/nQ;
|
||||
s = decimal(2.0) / nQ;
|
||||
}
|
||||
|
||||
// Computations used for optimization (less multiplications)
|
||||
|
@ -176,9 +176,9 @@ Matrix3x3 Quaternion::getMatrix() const {
|
|||
decimal zzs = z*zs;
|
||||
|
||||
// Create the matrix corresponding to the quaternion
|
||||
return Matrix3x3(1.0-yys-zzs, xys-wzs, xzs + wys,
|
||||
xys + wzs, 1.0-xxs-zzs, yzs-wxs,
|
||||
xzs-wys, yzs + wxs, 1.0-xxs-yys);
|
||||
return Matrix3x3(decimal(1.0) - yys - zzs, xys-wzs, xzs + wys,
|
||||
xys + wzs, decimal(1.0) - xxs - zzs, yzs-wxs,
|
||||
xzs-wys, yzs + wxs, decimal(1.0) - xxs - yys);
|
||||
}
|
||||
|
||||
// Compute the spherical linear interpolation between two quaternions.
|
||||
|
@ -201,9 +201,9 @@ Quaternion Quaternion::slerp(const Quaternion& quaternion1,
|
|||
// Because of precision, if cos(theta) is nearly 1,
|
||||
// therefore theta is nearly 0 and we can write
|
||||
// sin((1-t)*theta) as (1-t) and sin(t*theta) as t
|
||||
const decimal epsilon = 0.00001;
|
||||
const decimal epsilon = decimal(0.00001);
|
||||
if(1-cosineTheta < epsilon) {
|
||||
return quaternion1 * (1.0-t) + quaternion2 * (t * invert);
|
||||
return quaternion1 * (decimal(1.0)-t) + quaternion2 * (t * invert);
|
||||
}
|
||||
|
||||
// Compute the theta angle
|
||||
|
@ -213,7 +213,7 @@ Quaternion Quaternion::slerp(const Quaternion& quaternion1,
|
|||
decimal sineTheta = sin(theta);
|
||||
|
||||
// Compute the two coefficients that are in the spherical linear interpolation formula
|
||||
decimal coeff1 = sin((1.0-t)*theta) / sineTheta;
|
||||
decimal coeff1 = sin((decimal(1.0)-t)*theta) / sineTheta;
|
||||
decimal coeff2 = sin(t*theta) / sineTheta * invert;
|
||||
|
||||
// Compute and return the interpolated quaternion
|
||||
|
|
|
@ -58,7 +58,7 @@ Vector3 Vector3::getUnit() const {
|
|||
assert(lengthVector > MACHINE_EPSILON);
|
||||
|
||||
// Compute and return the unit vector
|
||||
decimal lengthInv = 1.0 / lengthVector;
|
||||
decimal lengthInv = decimal(1.0) / lengthVector;
|
||||
return Vector3(x * lengthInv, y * lengthInv, z * lengthInv);
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue
Block a user