Fix warnings
This commit is contained in:
parent
3050c83b0d
commit
c237cecf68
|
@ -63,6 +63,7 @@ do not hesitate to take a look at the user manual.
|
|||
- Issue with wrong linear velocity update computed in RigidBody::updateLocalCenterOfMassFromColliders() method
|
||||
- Issue with wrong linear velocity update computed in RigidBody::updateMassPropertiesFromColliders() method
|
||||
- Issue in copy-constructors in Map and Set classes
|
||||
- A lot of code warnings have been fixed
|
||||
|
||||
|
||||
## Version 0.8.0 (May 31, 2020)
|
||||
|
|
|
@ -75,7 +75,7 @@ class CollisionBody {
|
|||
void removeAllColliders();
|
||||
|
||||
/// Update the broad-phase state for this body (because it has moved for instance)
|
||||
void updateBroadPhaseState(decimal timeStep) const;
|
||||
void updateBroadPhaseState() const;
|
||||
|
||||
/// Ask the broad-phase to test again the collision shapes of the body for collision
|
||||
/// (as if the body has moved).
|
||||
|
|
|
@ -75,7 +75,7 @@ struct ContactPair {
|
|||
uint32 contactManifoldsIndex;
|
||||
|
||||
/// Number of contact manifolds
|
||||
int8 nbContactManifolds;
|
||||
uint32 nbContactManifolds;
|
||||
|
||||
/// Index of the first contact point in the array of contact points
|
||||
uint32 contactPointsIndex;
|
||||
|
|
|
@ -61,12 +61,6 @@ class AABB {
|
|||
/// Constructor
|
||||
AABB(const Vector3& minCoordinates, const Vector3& maxCoordinates);
|
||||
|
||||
/// Copy-constructor
|
||||
AABB(const AABB& aabb);
|
||||
|
||||
/// Destructor
|
||||
~AABB() = default;
|
||||
|
||||
/// Return the center point
|
||||
Vector3 getCenter() const;
|
||||
|
||||
|
@ -121,9 +115,6 @@ class AABB {
|
|||
/// Create and return an AABB for a triangle
|
||||
static AABB createAABBForTriangle(const Vector3* trianglePoints);
|
||||
|
||||
/// Assignment operator
|
||||
AABB& operator=(const AABB& aabb);
|
||||
|
||||
// -------------------- Friendship -------------------- //
|
||||
|
||||
friend class DynamicAABBTree;
|
||||
|
@ -211,15 +202,6 @@ RP3D_FORCE_INLINE void AABB::applyScale(const Vector3& scale) {
|
|||
mMaxCoordinates = mMaxCoordinates * scale;
|
||||
}
|
||||
|
||||
// Assignment operator
|
||||
RP3D_FORCE_INLINE AABB& AABB::operator=(const AABB& aabb) {
|
||||
if (this != &aabb) {
|
||||
mMinCoordinates = aabb.mMinCoordinates;
|
||||
mMaxCoordinates = aabb.mMaxCoordinates;
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
|
||||
// Merge the AABB in parameter with the current one
|
||||
RP3D_FORCE_INLINE void AABB::mergeWithAABB(const AABB& aabb) {
|
||||
mMinCoordinates.x = std::min(mMinCoordinates.x, aabb.mMinCoordinates.x);
|
||||
|
|
|
@ -100,7 +100,6 @@ struct Entity {
|
|||
// -------------------- Friendship -------------------- //
|
||||
|
||||
friend class EntityManager;
|
||||
|
||||
};
|
||||
|
||||
// Return the lookup index of the entity in a array
|
||||
|
|
|
@ -59,15 +59,6 @@ class Matrix2x2 {
|
|||
/// Constructor
|
||||
Matrix2x2(decimal a1, decimal a2, decimal b1, decimal b2);
|
||||
|
||||
/// Destructor
|
||||
~Matrix2x2() = default;
|
||||
|
||||
/// Copy-constructor
|
||||
Matrix2x2(const Matrix2x2& matrix);
|
||||
|
||||
/// Assignment operator
|
||||
Matrix2x2& operator=(const Matrix2x2& matrix);
|
||||
|
||||
/// Set all the values in the matrix
|
||||
void setAllValues(decimal a1, decimal a2, decimal b1, decimal b2);
|
||||
|
||||
|
@ -172,12 +163,6 @@ RP3D_FORCE_INLINE Matrix2x2::Matrix2x2(decimal a1, decimal a2, decimal b1, decim
|
|||
setAllValues(a1, a2, b1, b2);
|
||||
}
|
||||
|
||||
// Copy-constructor
|
||||
RP3D_FORCE_INLINE Matrix2x2::Matrix2x2(const Matrix2x2& matrix) {
|
||||
setAllValues(matrix.mRows[0][0], matrix.mRows[0][1],
|
||||
matrix.mRows[1][0], matrix.mRows[1][1]);
|
||||
}
|
||||
|
||||
// Method to set all the values in the matrix
|
||||
RP3D_FORCE_INLINE void Matrix2x2::setAllValues(decimal a1, decimal a2,
|
||||
decimal b1, decimal b2) {
|
||||
|
|
|
@ -61,15 +61,6 @@ class Matrix3x3 {
|
|||
Matrix3x3(decimal a1, decimal a2, decimal a3, decimal b1, decimal b2, decimal b3,
|
||||
decimal c1, decimal c2, decimal c3);
|
||||
|
||||
/// Destructor
|
||||
~Matrix3x3() = default;
|
||||
|
||||
/// Copy-constructor
|
||||
Matrix3x3(const Matrix3x3& matrix);
|
||||
|
||||
/// Assignment operator
|
||||
Matrix3x3& operator=(const Matrix3x3& matrix);
|
||||
|
||||
/// Set all the values in the matrix
|
||||
void setAllValues(decimal a1, decimal a2, decimal a3, decimal b1, decimal b2, decimal b3,
|
||||
decimal c1, decimal c2, decimal c3);
|
||||
|
@ -179,13 +170,6 @@ RP3D_FORCE_INLINE Matrix3x3::Matrix3x3(decimal a1, decimal a2, decimal a3,
|
|||
setAllValues(a1, a2, a3, b1, b2, b3, c1, c2, c3);
|
||||
}
|
||||
|
||||
// Copy-constructor
|
||||
RP3D_FORCE_INLINE Matrix3x3::Matrix3x3(const Matrix3x3& matrix) {
|
||||
setAllValues(matrix.mRows[0][0], matrix.mRows[0][1], matrix.mRows[0][2],
|
||||
matrix.mRows[1][0], matrix.mRows[1][1], matrix.mRows[1][2],
|
||||
matrix.mRows[2][0], matrix.mRows[2][1], matrix.mRows[2][2]);
|
||||
}
|
||||
|
||||
// Method to set all the values in the matrix
|
||||
RP3D_FORCE_INLINE void Matrix3x3::setAllValues(decimal a1, decimal a2, decimal a3,
|
||||
decimal b1, decimal b2, decimal b3,
|
||||
|
|
|
@ -73,15 +73,9 @@ struct Quaternion {
|
|||
/// Constructor with the component w and the vector v=(x y z)
|
||||
Quaternion(const Vector3& v, decimal newW);
|
||||
|
||||
/// Copy-constructor
|
||||
Quaternion(const Quaternion& quaternion);
|
||||
|
||||
/// Create a unit quaternion from a rotation matrix
|
||||
Quaternion(const Matrix3x3& matrix);
|
||||
|
||||
/// Destructor
|
||||
~Quaternion() = default;
|
||||
|
||||
/// Set all the values
|
||||
void setAllValues(decimal newX, decimal newY, decimal newZ, decimal newW);
|
||||
|
||||
|
@ -166,9 +160,6 @@ struct Quaternion {
|
|||
/// Overloaded operator for the multiplication with a vector
|
||||
Vector3 operator*(const Vector3& point) const;
|
||||
|
||||
/// Overloaded operator for assignment
|
||||
Quaternion& operator=(const Quaternion& quaternion);
|
||||
|
||||
/// Overloaded operator for equality condition
|
||||
bool operator==(const Quaternion& quaternion) const;
|
||||
|
||||
|
@ -387,21 +378,6 @@ RP3D_FORCE_INLINE Vector3 Quaternion::operator*(const Vector3& point) const {
|
|||
w * prodZ - prodX * y + prodY * x - prodW * z);
|
||||
}
|
||||
|
||||
// Overloaded operator for the assignment
|
||||
RP3D_FORCE_INLINE Quaternion& Quaternion::operator=(const Quaternion& quaternion) {
|
||||
|
||||
// Check for self-assignment
|
||||
if (this != &quaternion) {
|
||||
x = quaternion.x;
|
||||
y = quaternion.y;
|
||||
z = quaternion.z;
|
||||
w = quaternion.w;
|
||||
}
|
||||
|
||||
// Return this quaternion
|
||||
return *this;
|
||||
}
|
||||
|
||||
// Overloaded operator for equality condition
|
||||
RP3D_FORCE_INLINE bool Quaternion::operator==(const Quaternion& quaternion) const {
|
||||
return (x == quaternion.x && y == quaternion.y &&
|
||||
|
|
|
@ -60,24 +60,6 @@ struct Ray {
|
|||
: point1(p1), point2(p2), maxFraction(maxFrac) {
|
||||
|
||||
}
|
||||
|
||||
/// Copy-constructor
|
||||
Ray(const Ray& ray) : point1(ray.point1), point2(ray.point2), maxFraction(ray.maxFraction) {
|
||||
|
||||
}
|
||||
|
||||
/// Destructor
|
||||
~Ray() = default;
|
||||
|
||||
/// Overloaded assignment operator
|
||||
Ray& operator=(const Ray& ray) {
|
||||
if (&ray != this) {
|
||||
point1 = ray.point1;
|
||||
point2 = ray.point2;
|
||||
maxFraction = ray.maxFraction;
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
};
|
||||
|
||||
}
|
||||
|
|
|
@ -63,12 +63,6 @@ class Transform {
|
|||
/// Constructor
|
||||
Transform(const Vector3& position, const Quaternion& orientation);
|
||||
|
||||
/// Destructor
|
||||
~Transform() = default;
|
||||
|
||||
/// Copy-constructor
|
||||
Transform(const Transform& transform);
|
||||
|
||||
/// Return the origin of the transform
|
||||
const Vector3& getPosition() const;
|
||||
|
||||
|
@ -116,9 +110,6 @@ class Transform {
|
|||
/// Return true if the two transforms are different
|
||||
bool operator!=(const Transform& transform2) const;
|
||||
|
||||
/// Assignment operator
|
||||
Transform& operator=(const Transform& transform);
|
||||
|
||||
/// Return the string representation
|
||||
std::string to_string() const;
|
||||
|
||||
|
@ -141,12 +132,6 @@ RP3D_FORCE_INLINE Transform::Transform(const Vector3& position, const Quaternion
|
|||
|
||||
}
|
||||
|
||||
// Copy-constructor
|
||||
RP3D_FORCE_INLINE Transform::Transform(const Transform& transform)
|
||||
: mPosition(transform.mPosition), mOrientation(transform.mOrientation) {
|
||||
|
||||
}
|
||||
|
||||
// Return the position of the transform
|
||||
RP3D_FORCE_INLINE const Vector3& Transform::getPosition() const {
|
||||
return mPosition;
|
||||
|
@ -248,15 +233,6 @@ RP3D_FORCE_INLINE bool Transform::operator!=(const Transform& transform2) const
|
|||
return !(*this == transform2);
|
||||
}
|
||||
|
||||
// Assignment operator
|
||||
RP3D_FORCE_INLINE Transform& Transform::operator=(const Transform& transform) {
|
||||
if (&transform != this) {
|
||||
mPosition = transform.mPosition;
|
||||
mOrientation = transform.mOrientation;
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
|
||||
// Get the string representation
|
||||
RP3D_FORCE_INLINE std::string Transform::to_string() const {
|
||||
return "Transform(" + mPosition.to_string() + "," + mOrientation.to_string() + ")";
|
||||
|
|
|
@ -58,12 +58,6 @@ struct Vector2 {
|
|||
/// Constructor with arguments
|
||||
Vector2(decimal newX, decimal newY);
|
||||
|
||||
/// Copy-constructor
|
||||
Vector2(const Vector2& vector);
|
||||
|
||||
/// Destructor
|
||||
~Vector2() = default;
|
||||
|
||||
/// Set all the values of the vector
|
||||
void setAllValues(decimal newX, decimal newY);
|
||||
|
||||
|
@ -130,9 +124,6 @@ struct Vector2 {
|
|||
/// Overloaded operator for value access
|
||||
const decimal& operator[] (int index) const;
|
||||
|
||||
/// Overloaded operator
|
||||
Vector2& operator=(const Vector2& vector);
|
||||
|
||||
/// Overloaded less than operator for ordering to be used inside std::set for instance
|
||||
bool operator<(const Vector2& vector) const;
|
||||
|
||||
|
@ -170,12 +161,6 @@ RP3D_FORCE_INLINE Vector2::Vector2(decimal newX, decimal newY) : x(newX), y(newY
|
|||
|
||||
}
|
||||
|
||||
// Copy-constructor
|
||||
RP3D_FORCE_INLINE Vector2::Vector2(const Vector2& vector) : x(vector.x), y(vector.y) {
|
||||
|
||||
}
|
||||
|
||||
|
||||
// Set the vector to zero
|
||||
RP3D_FORCE_INLINE void Vector2::setToZero() {
|
||||
x = 0;
|
||||
|
@ -335,15 +320,6 @@ RP3D_FORCE_INLINE Vector2 operator*(decimal number, const Vector2& vector) {
|
|||
return vector * number;
|
||||
}
|
||||
|
||||
// Assignment operator
|
||||
RP3D_FORCE_INLINE Vector2& Vector2::operator=(const Vector2& vector) {
|
||||
if (&vector != this) {
|
||||
x = vector.x;
|
||||
y = vector.y;
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
|
||||
// Overloaded less than operator for ordering to be used inside std::set for instance
|
||||
RP3D_FORCE_INLINE bool Vector2::operator<(const Vector2& vector) const {
|
||||
return (x == vector.x ? y < vector.y : x < vector.x);
|
||||
|
|
|
@ -64,12 +64,6 @@ struct Vector3 {
|
|||
/// Constructor with arguments
|
||||
Vector3(decimal newX, decimal newY, decimal newZ);
|
||||
|
||||
/// Copy-constructor
|
||||
Vector3(const Vector3& vector);
|
||||
|
||||
/// Destructor
|
||||
~Vector3() = default;
|
||||
|
||||
/// Set all the values of the vector
|
||||
void setAllValues(decimal newX, decimal newY, decimal newZ);
|
||||
|
||||
|
@ -145,9 +139,6 @@ struct Vector3 {
|
|||
/// Overloaded operator for value access
|
||||
const decimal& operator[] (int index) const;
|
||||
|
||||
/// Overloaded operator
|
||||
Vector3& operator=(const Vector3& vector);
|
||||
|
||||
/// Overloaded less than operator for ordering to be used inside std::set for instance
|
||||
bool operator<(const Vector3& vector) const;
|
||||
|
||||
|
@ -185,11 +176,6 @@ RP3D_FORCE_INLINE Vector3::Vector3(decimal newX, decimal newY, decimal newZ) : x
|
|||
|
||||
}
|
||||
|
||||
// Copy-constructor
|
||||
RP3D_FORCE_INLINE Vector3::Vector3(const Vector3& vector) : x(vector.x), y(vector.y), z(vector.z) {
|
||||
|
||||
}
|
||||
|
||||
// Set the vector to zero
|
||||
RP3D_FORCE_INLINE void Vector3::setToZero() {
|
||||
x = 0;
|
||||
|
@ -364,16 +350,6 @@ RP3D_FORCE_INLINE Vector3 operator*(const Vector3& vector1, const Vector3& vecto
|
|||
return Vector3(vector1.x * vector2.x, vector1.y * vector2.y, vector1.z * vector2.z);
|
||||
}
|
||||
|
||||
// Assignment operator
|
||||
RP3D_FORCE_INLINE Vector3& Vector3::operator=(const Vector3& vector) {
|
||||
if (&vector != this) {
|
||||
x = vector.x;
|
||||
y = vector.y;
|
||||
z = vector.z;
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
|
||||
// Overloaded less than operator for ordering to be used inside std::set for instance
|
||||
RP3D_FORCE_INLINE bool Vector3::operator<(const Vector3& vector) const {
|
||||
return (x == vector.x ? (y == vector.y ? z < vector.z : y < vector.y) : x < vector.x);
|
||||
|
|
|
@ -144,7 +144,7 @@ class BroadPhaseSystem {
|
|||
bool forceReInsert);
|
||||
|
||||
/// Update the broad-phase state of some colliders components
|
||||
void updateCollidersComponents(uint32 startIndex, uint32 nbItems, decimal timeStep);
|
||||
void updateCollidersComponents(uint32 startIndex, uint32 nbItems);
|
||||
|
||||
public :
|
||||
|
||||
|
@ -170,10 +170,10 @@ class BroadPhaseSystem {
|
|||
void removeCollider(Collider* collider);
|
||||
|
||||
/// Update the broad-phase state of a single collider
|
||||
void updateCollider(Entity colliderEntity, decimal timeStep);
|
||||
void updateCollider(Entity colliderEntity);
|
||||
|
||||
/// Update the broad-phase state of all the enabled colliders
|
||||
void updateColliders(decimal timeStep);
|
||||
void updateColliders();
|
||||
|
||||
/// Add a collider in the array of colliders that have moved in the last simulation step
|
||||
/// and that need to be tested again for broad-phase overlapping.
|
||||
|
|
|
@ -323,10 +323,10 @@ class CollisionDetectionSystem {
|
|||
void removeCollider(Collider* collider);
|
||||
|
||||
/// Update a collider (that has moved for instance)
|
||||
void updateCollider(Entity colliderEntity, decimal timeStep);
|
||||
void updateCollider(Entity colliderEntity);
|
||||
|
||||
/// Update all the enabled colliders
|
||||
void updateColliders(decimal timeStep);
|
||||
void updateColliders();
|
||||
|
||||
/// Add a pair of bodies that cannot collide with each other
|
||||
void addNoCollisionPair(Entity body1Entity, Entity body2Entity);
|
||||
|
@ -445,15 +445,15 @@ RP3D_FORCE_INLINE MemoryManager& CollisionDetectionSystem::getMemoryManager() co
|
|||
}
|
||||
|
||||
// Update a collider (that has moved for instance)
|
||||
RP3D_FORCE_INLINE void CollisionDetectionSystem::updateCollider(Entity colliderEntity, decimal timeStep) {
|
||||
RP3D_FORCE_INLINE void CollisionDetectionSystem::updateCollider(Entity colliderEntity) {
|
||||
|
||||
// Update the collider component
|
||||
mBroadPhaseSystem.updateCollider(colliderEntity, timeStep);
|
||||
mBroadPhaseSystem.updateCollider(colliderEntity);
|
||||
}
|
||||
|
||||
// Update all the enabled colliders
|
||||
RP3D_FORCE_INLINE void CollisionDetectionSystem::updateColliders(decimal timeStep) {
|
||||
mBroadPhaseSystem.updateColliders(timeStep);
|
||||
RP3D_FORCE_INLINE void CollisionDetectionSystem::updateColliders() {
|
||||
mBroadPhaseSystem.updateColliders();
|
||||
}
|
||||
|
||||
#ifdef IS_RP3D_PROFILING_ENABLED
|
||||
|
|
|
@ -219,7 +219,7 @@ const Transform& CollisionBody::getTransform() const {
|
|||
}
|
||||
|
||||
// Update the broad-phase state for this body (because it has moved for instance)
|
||||
void CollisionBody::updateBroadPhaseState(decimal timeStep) const {
|
||||
void CollisionBody::updateBroadPhaseState() const {
|
||||
|
||||
// For all the colliders of the body
|
||||
const Array<Entity>& colliderEntities = mWorld.mCollisionBodyComponents.getColliders(mEntity);
|
||||
|
@ -232,7 +232,7 @@ void CollisionBody::updateBroadPhaseState(decimal timeStep) const {
|
|||
mWorld.mCollidersComponents.getLocalToBodyTransform(colliderEntities[i]));
|
||||
|
||||
// Update the collider
|
||||
mWorld.mCollisionDetection.updateCollider(colliderEntities[i], timeStep);
|
||||
mWorld.mCollisionDetection.updateCollider(colliderEntities[i]);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -400,7 +400,7 @@ void CollisionBody::setTransform(const Transform& transform) {
|
|||
mWorld.mTransformComponents.setTransform(mEntity, transform);
|
||||
|
||||
// Update the broad-phase state of the body
|
||||
updateBroadPhaseState(0);
|
||||
updateBroadPhaseState();
|
||||
|
||||
RP3D_LOG(mWorld.mConfig.worldName, Logger::Level::Information, Logger::Category::Body,
|
||||
"Body " + std::to_string(mEntity.id) + ": Set transform=" + transform.to_string(), __FILE__, __LINE__);
|
||||
|
|
|
@ -117,7 +117,7 @@ void Collider::setLocalToBodyTransform(const Transform& transform) {
|
|||
rigidBody->setIsSleeping(false);
|
||||
}
|
||||
|
||||
mBody->mWorld.mCollisionDetection.updateCollider(mEntity, 0);
|
||||
mBody->mWorld.mCollisionDetection.updateCollider(mEntity);
|
||||
|
||||
RP3D_LOG(mBody->mWorld.mConfig.worldName, Logger::Level::Information, Logger::Category::Collider,
|
||||
"Collider " + std::to_string(getBroadPhaseId()) + ": Set localToBodyTransform=" +
|
||||
|
|
|
@ -36,9 +36,3 @@ AABB::AABB(const Vector3& minCoordinates, const Vector3& maxCoordinates)
|
|||
:mMinCoordinates(minCoordinates), mMaxCoordinates(maxCoordinates) {
|
||||
|
||||
}
|
||||
|
||||
// Copy-constructor
|
||||
AABB::AABB(const AABB& aabb)
|
||||
: mMinCoordinates(aabb.mMinCoordinates), mMaxCoordinates(aabb.mMaxCoordinates) {
|
||||
|
||||
}
|
||||
|
|
|
@ -55,7 +55,7 @@ Entity EntityManager::createEntity() {
|
|||
// Create a new indice
|
||||
index = mGenerations.size() - 1;
|
||||
|
||||
assert(index < (1 << Entity::ENTITY_INDEX_BITS));
|
||||
assert(index < (uint32(1) << Entity::ENTITY_INDEX_BITS));
|
||||
}
|
||||
|
||||
// Return a new entity
|
||||
|
|
|
@ -346,7 +346,7 @@ void PhysicsWorld::update(decimal timeStep) {
|
|||
mDynamicsSystem.updateBodiesState();
|
||||
|
||||
// Update the colliders components
|
||||
mCollisionDetection.updateColliders(timeStep);
|
||||
mCollisionDetection.updateColliders();
|
||||
|
||||
if (mIsSleepingEnabled) updateSleepingBodies(timeStep);
|
||||
|
||||
|
|
|
@ -28,17 +28,6 @@
|
|||
|
||||
using namespace reactphysics3d;
|
||||
|
||||
// Assignment operator
|
||||
Matrix2x2& Matrix2x2::operator=(const Matrix2x2& matrix) {
|
||||
|
||||
// Check for self-assignment
|
||||
if (&matrix != this) {
|
||||
setAllValues(matrix.mRows[0][0], matrix.mRows[0][1],
|
||||
matrix.mRows[1][0], matrix.mRows[1][1]);
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
|
||||
// Return the inverse matrix
|
||||
Matrix2x2 Matrix2x2::getInverse(decimal determinant) const {
|
||||
|
||||
|
|
|
@ -29,18 +29,6 @@
|
|||
// Namespaces
|
||||
using namespace reactphysics3d;
|
||||
|
||||
// Assignment operator
|
||||
Matrix3x3& Matrix3x3::operator=(const Matrix3x3& matrix) {
|
||||
|
||||
// Check for self-assignment
|
||||
if (&matrix != this) {
|
||||
setAllValues(matrix.mRows[0][0], matrix.mRows[0][1], matrix.mRows[0][2],
|
||||
matrix.mRows[1][0], matrix.mRows[1][1], matrix.mRows[1][2],
|
||||
matrix.mRows[2][0], matrix.mRows[2][1], matrix.mRows[2][2]);
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
|
||||
// Return the inverse matrix
|
||||
Matrix3x3 Matrix3x3::getInverse(decimal determinant) const {
|
||||
|
||||
|
|
|
@ -51,12 +51,6 @@ Quaternion Quaternion::fromEulerAngles(const Vector3& eulerAngles) {
|
|||
return quaternion;
|
||||
}
|
||||
|
||||
// Copy-constructor
|
||||
Quaternion::Quaternion(const Quaternion& quaternion)
|
||||
:x(quaternion.x), y(quaternion.y), z(quaternion.z), w(quaternion.w) {
|
||||
|
||||
}
|
||||
|
||||
// Create a unit quaternion from a rotation matrix
|
||||
Quaternion::Quaternion(const Matrix3x3& matrix) {
|
||||
|
||||
|
|
|
@ -30,7 +30,6 @@
|
|||
// Namespaces
|
||||
using namespace reactphysics3d;
|
||||
|
||||
|
||||
// Set the transform from an OpenGL transform matrix
|
||||
void Transform::setFromOpenGL(decimal* openglMatrix) {
|
||||
Matrix3x3 matrix(openglMatrix[0], openglMatrix[4], openglMatrix[8],
|
||||
|
|
|
@ -62,9 +62,11 @@ HeapAllocator::~HeapAllocator() {
|
|||
|
||||
MemoryUnitHeader* nextUnit = unit->nextUnit;
|
||||
|
||||
const size_t unitSize = unit->size;
|
||||
|
||||
// Destroy the unit
|
||||
unit->~MemoryUnitHeader();
|
||||
mBaseAllocator.release(static_cast<void*>(unit), unit->size + sizeof(MemoryUnitHeader));
|
||||
mBaseAllocator.release(static_cast<void*>(unit), unitSize + sizeof(MemoryUnitHeader));
|
||||
|
||||
unit = nextUnit;
|
||||
}
|
||||
|
|
|
@ -114,7 +114,7 @@ void BroadPhaseSystem::removeCollider(Collider* collider) {
|
|||
}
|
||||
|
||||
// Update the broad-phase state of a single collider
|
||||
void BroadPhaseSystem::updateCollider(Entity colliderEntity, decimal timeStep) {
|
||||
void BroadPhaseSystem::updateCollider(Entity colliderEntity) {
|
||||
|
||||
assert(mCollidersComponents.mMapEntityToComponentIndex.containsKey(colliderEntity));
|
||||
|
||||
|
@ -122,17 +122,17 @@ void BroadPhaseSystem::updateCollider(Entity colliderEntity, decimal timeStep) {
|
|||
uint32 index = mCollidersComponents.mMapEntityToComponentIndex[colliderEntity];
|
||||
|
||||
// Update the collider component
|
||||
updateCollidersComponents(index, 1, timeStep);
|
||||
updateCollidersComponents(index, 1);
|
||||
}
|
||||
|
||||
// Update the broad-phase state of all the enabled colliders
|
||||
void BroadPhaseSystem::updateColliders(decimal timeStep) {
|
||||
void BroadPhaseSystem::updateColliders() {
|
||||
|
||||
RP3D_PROFILE("BroadPhaseSystem::updateColliders()", mProfiler);
|
||||
|
||||
// Update all the enabled collider components
|
||||
if (mCollidersComponents.getNbEnabledComponents() > 0) {
|
||||
updateCollidersComponents(0, mCollidersComponents.getNbEnabledComponents(), timeStep);
|
||||
updateCollidersComponents(0, mCollidersComponents.getNbEnabledComponents());
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -156,7 +156,7 @@ void BroadPhaseSystem::updateColliderInternal(int32 broadPhaseId, Collider* coll
|
|||
}
|
||||
|
||||
// Update the broad-phase state of some colliders components
|
||||
void BroadPhaseSystem::updateCollidersComponents(uint32 startIndex, uint32 nbItems, decimal timeStep) {
|
||||
void BroadPhaseSystem::updateCollidersComponents(uint32 startIndex, uint32 nbItems) {
|
||||
|
||||
RP3D_PROFILE("BroadPhaseSystem::updateCollidersComponents()", mProfiler);
|
||||
|
||||
|
|
|
@ -844,7 +844,7 @@ void CollisionDetectionSystem::createContacts() {
|
|||
contactPair.contactPointsIndex = mCurrentContactPoints->size();
|
||||
|
||||
// For each potential contact manifold of the pair
|
||||
for (uint m=0; m < contactPair.nbContactManifolds; m++) {
|
||||
for (uint32 m=0; m < contactPair.nbContactManifolds; m++) {
|
||||
|
||||
ContactManifoldInfo& potentialManifold = mPotentialContactManifolds[contactPair.potentialContactManifoldsIndices[m]];
|
||||
|
||||
|
|
Loading…
Reference in New Issue
Block a user