Fix warnings
This commit is contained in:
parent
f39cad7482
commit
3050c83b0d
|
@ -186,7 +186,7 @@ RP3D_FORCE_INLINE Vector3 BoxShape::getLocalSupportPointWithoutMargin(const Vect
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if a point is inside the collision shape
|
// Return true if a point is inside the collision shape
|
||||||
RP3D_FORCE_INLINE bool BoxShape::testPointInside(const Vector3& localPoint, Collider* collider) const {
|
RP3D_FORCE_INLINE bool BoxShape::testPointInside(const Vector3& localPoint, Collider* /*collider*/) const {
|
||||||
return (localPoint.x < mHalfExtents[0] && localPoint.x > -mHalfExtents[0] &&
|
return (localPoint.x < mHalfExtents[0] && localPoint.x > -mHalfExtents[0] &&
|
||||||
localPoint.y < mHalfExtents[1] && localPoint.y > -mHalfExtents[1] &&
|
localPoint.y < mHalfExtents[1] && localPoint.y > -mHalfExtents[1] &&
|
||||||
localPoint.z < mHalfExtents[2] && localPoint.z > -mHalfExtents[2]);
|
localPoint.z < mHalfExtents[2] && localPoint.z > -mHalfExtents[2]);
|
||||||
|
|
|
@ -130,7 +130,7 @@ RP3D_FORCE_INLINE bool ConcaveShape::isPolyhedron() const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if a point is inside the collision shape
|
// Return true if a point is inside the collision shape
|
||||||
RP3D_FORCE_INLINE bool ConcaveShape::testPointInside(const Vector3& localPoint, Collider* collider) const {
|
RP3D_FORCE_INLINE bool ConcaveShape::testPointInside(const Vector3& /*localPoint*/, Collider* /*collider*/) const {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -145,7 +145,7 @@ RP3D_FORCE_INLINE size_t SphereShape::getSizeInBytes() const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return a local support point in a given direction without the object margin
|
// Return a local support point in a given direction without the object margin
|
||||||
RP3D_FORCE_INLINE Vector3 SphereShape::getLocalSupportPointWithoutMargin(const Vector3& direction) const {
|
RP3D_FORCE_INLINE Vector3 SphereShape::getLocalSupportPointWithoutMargin(const Vector3& /*direction*/) const {
|
||||||
|
|
||||||
// Return the center of the sphere (the radius is taken into account in the object margin)
|
// Return the center of the sphere (the radius is taken into account in the object margin)
|
||||||
return Vector3(0.0, 0.0, 0.0);
|
return Vector3(0.0, 0.0, 0.0);
|
||||||
|
@ -185,7 +185,7 @@ RP3D_FORCE_INLINE decimal SphereShape::getVolume() const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if a point is inside the collision shape
|
// Return true if a point is inside the collision shape
|
||||||
RP3D_FORCE_INLINE bool SphereShape::testPointInside(const Vector3& localPoint, Collider* collider) const {
|
RP3D_FORCE_INLINE bool SphereShape::testPointInside(const Vector3& localPoint, Collider* /*collider*/) const {
|
||||||
return (localPoint.lengthSquare() < mMargin * mMargin);
|
return (localPoint.lengthSquare() < mMargin * mMargin);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -224,12 +224,12 @@ RP3D_FORCE_INLINE void TriangleShape::getLocalBounds(Vector3& min, Vector3& max)
|
||||||
* coordinates
|
* coordinates
|
||||||
* @param mass Mass to use to compute the inertia tensor of the collision shape
|
* @param mass Mass to use to compute the inertia tensor of the collision shape
|
||||||
*/
|
*/
|
||||||
RP3D_FORCE_INLINE Vector3 TriangleShape::getLocalInertiaTensor(decimal mass) const {
|
RP3D_FORCE_INLINE Vector3 TriangleShape::getLocalInertiaTensor(decimal /*mass*/) const {
|
||||||
return Vector3(0, 0, 0);
|
return Vector3(0, 0, 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if a point is inside the collision shape
|
// Return true if a point is inside the collision shape
|
||||||
RP3D_FORCE_INLINE bool TriangleShape::testPointInside(const Vector3& localPoint, Collider* collider) const {
|
RP3D_FORCE_INLINE bool TriangleShape::testPointInside(const Vector3& /*localPoint*/, Collider* /*collider*/) const {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -83,8 +83,8 @@ class Map {
|
||||||
|
|
||||||
// -------------------- Methods -------------------- //
|
// -------------------- Methods -------------------- //
|
||||||
|
|
||||||
/// Return the index of the entry with a given key or -1 if there is no entry with this key
|
/// Return the index of the entry with a given key or INVALID_INDEX if there is no entry with this key
|
||||||
int findEntry(const K& key) const {
|
uint32 findEntry(const K& key) const {
|
||||||
|
|
||||||
if (mHashSize > 0) {
|
if (mHashSize > 0) {
|
||||||
|
|
||||||
|
|
|
@ -91,9 +91,6 @@ struct Entity {
|
||||||
/// Return the generation number of the entity
|
/// Return the generation number of the entity
|
||||||
uint32 getGeneration() const;
|
uint32 getGeneration() const;
|
||||||
|
|
||||||
/// Assignment operator
|
|
||||||
Entity& operator=(const Entity& entity);
|
|
||||||
|
|
||||||
/// Equality operator
|
/// Equality operator
|
||||||
bool operator==(const Entity& entity) const;
|
bool operator==(const Entity& entity) const;
|
||||||
|
|
||||||
|
|
|
@ -55,13 +55,13 @@ class EventListener : public CollisionCallback {
|
||||||
/**
|
/**
|
||||||
* @param callbackData Contains information about all the contacts
|
* @param callbackData Contains information about all the contacts
|
||||||
*/
|
*/
|
||||||
virtual void onContact(const CollisionCallback::CallbackData& callbackData) override {}
|
virtual void onContact(const CollisionCallback::CallbackData& /*callbackData*/) override {}
|
||||||
|
|
||||||
/// Called when some trigger events occur
|
/// Called when some trigger events occur
|
||||||
/**
|
/**
|
||||||
* @param callbackData Contains information about all the triggers that are colliding
|
* @param callbackData Contains information about all the triggers that are colliding
|
||||||
*/
|
*/
|
||||||
virtual void onTrigger(const OverlapCallback::CallbackData& callbackData) {}
|
virtual void onTrigger(const OverlapCallback::CallbackData& /*callbackData*/) {}
|
||||||
};
|
};
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -56,7 +56,7 @@ class DefaultAllocator : public MemoryAllocator {
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Release previously allocated memory.
|
/// Release previously allocated memory.
|
||||||
virtual void release(void* pointer, size_t size) override {
|
virtual void release(void* pointer, size_t /*size*/) override {
|
||||||
std::free(pointer);
|
std::free(pointer);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
|
@ -34,7 +34,7 @@ using namespace reactphysics3d;
|
||||||
// Compute the narrow-phase collision detection between two capsules
|
// Compute the narrow-phase collision detection between two capsules
|
||||||
// This technique is based on the "Robust Contact Creation for Physics Simulations" presentation
|
// This technique is based on the "Robust Contact Creation for Physics Simulations" presentation
|
||||||
// by Dirk Gregorius.
|
// by Dirk Gregorius.
|
||||||
bool CapsuleVsCapsuleAlgorithm::testCollision(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchStartIndex, uint batchNbItems, MemoryAllocator& memoryAllocator) {
|
bool CapsuleVsCapsuleAlgorithm::testCollision(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchStartIndex, uint batchNbItems, MemoryAllocator& /*memoryAllocator*/) {
|
||||||
|
|
||||||
bool isCollisionFound = false;
|
bool isCollisionFound = false;
|
||||||
|
|
||||||
|
|
|
@ -961,8 +961,8 @@ bool SATAlgorithm::computePolyhedronVsPolyhedronFaceContactPoints(bool isMinPene
|
||||||
// The clipping plane is perpendicular to the edge direction and the reference face normal
|
// The clipping plane is perpendicular to the edge direction and the reference face normal
|
||||||
const Vector3 planeNormal = axisReferenceSpace.cross(edgeDirection);
|
const Vector3 planeNormal = axisReferenceSpace.cross(edgeDirection);
|
||||||
|
|
||||||
assert(areVertices1Input && verticesTemp1.size() > 0 || !areVertices1Input);
|
assert((areVertices1Input && verticesTemp1.size() > 0) || !areVertices1Input);
|
||||||
assert(!areVertices1Input && verticesTemp2.size() > 0 || areVertices1Input);
|
assert((!areVertices1Input && verticesTemp2.size() > 0) || areVertices1Input);
|
||||||
|
|
||||||
// Clip the incident face with one adjacent plane (corresponding to one edge) of the reference face
|
// Clip the incident face with one adjacent plane (corresponding to one edge) of the reference face
|
||||||
clipPolygonWithPlane(areVertices1Input ? verticesTemp1 : verticesTemp2, edgeV1, planeNormal, areVertices1Input ? verticesTemp2 : verticesTemp1);
|
clipPolygonWithPlane(areVertices1Input ? verticesTemp1 : verticesTemp2, edgeV1, planeNormal, areVertices1Input ? verticesTemp2 : verticesTemp1);
|
||||||
|
|
|
@ -35,7 +35,7 @@ using namespace reactphysics3d;
|
||||||
// Compute the narrow-phase collision detection between a sphere and a capsule
|
// Compute the narrow-phase collision detection between a sphere and a capsule
|
||||||
// This technique is based on the "Robust Contact Creation for Physics Simulations" presentation
|
// This technique is based on the "Robust Contact Creation for Physics Simulations" presentation
|
||||||
// by Dirk Gregorius.
|
// by Dirk Gregorius.
|
||||||
bool SphereVsCapsuleAlgorithm::testCollision(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchStartIndex, uint batchNbItems, MemoryAllocator& memoryAllocator) {
|
bool SphereVsCapsuleAlgorithm::testCollision(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchStartIndex, uint batchNbItems, MemoryAllocator& /*memoryAllocator*/) {
|
||||||
|
|
||||||
bool isCollisionFound = false;
|
bool isCollisionFound = false;
|
||||||
|
|
||||||
|
|
|
@ -31,7 +31,7 @@
|
||||||
// We want to use the ReactPhysics3D namespace
|
// We want to use the ReactPhysics3D namespace
|
||||||
using namespace reactphysics3d;
|
using namespace reactphysics3d;
|
||||||
|
|
||||||
bool SphereVsSphereAlgorithm::testCollision(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchStartIndex, uint batchNbItems, MemoryAllocator& memoryAllocator) {
|
bool SphereVsSphereAlgorithm::testCollision(NarrowPhaseInfoBatch& narrowPhaseInfoBatch, uint batchStartIndex, uint batchNbItems, MemoryAllocator& /*memoryAllocator*/) {
|
||||||
|
|
||||||
bool isCollisionFound = false;
|
bool isCollisionFound = false;
|
||||||
|
|
||||||
|
|
|
@ -59,7 +59,7 @@ Vector3 BoxShape::getLocalInertiaTensor(decimal mass) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Raycast method with feedback information
|
// Raycast method with feedback information
|
||||||
bool BoxShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, Collider* collider, MemoryAllocator& allocator) const {
|
bool BoxShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, Collider* collider, MemoryAllocator& /*allocator*/) const {
|
||||||
|
|
||||||
Vector3 rayDirection = ray.point2 - ray.point1;
|
Vector3 rayDirection = ray.point2 - ray.point1;
|
||||||
decimal tMin = DECIMAL_SMALLEST;
|
decimal tMin = DECIMAL_SMALLEST;
|
||||||
|
|
|
@ -67,7 +67,7 @@ Vector3 CapsuleShape::getLocalInertiaTensor(decimal mass) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if a point is inside the collision shape
|
// Return true if a point is inside the collision shape
|
||||||
bool CapsuleShape::testPointInside(const Vector3& localPoint, Collider* collider) const {
|
bool CapsuleShape::testPointInside(const Vector3& localPoint, Collider* /*collider*/) const {
|
||||||
|
|
||||||
const decimal diffYCenterSphere1 = localPoint.y - mHalfHeight;
|
const decimal diffYCenterSphere1 = localPoint.y - mHalfHeight;
|
||||||
const decimal diffYCenterSphere2 = localPoint.y + mHalfHeight;
|
const decimal diffYCenterSphere2 = localPoint.y + mHalfHeight;
|
||||||
|
@ -83,7 +83,7 @@ bool CapsuleShape::testPointInside(const Vector3& localPoint, Collider* collider
|
||||||
}
|
}
|
||||||
|
|
||||||
// Raycast method with feedback information
|
// Raycast method with feedback information
|
||||||
bool CapsuleShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, Collider* collider, MemoryAllocator& allocator) const {
|
bool CapsuleShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, Collider* collider, MemoryAllocator& /*allocator*/) const {
|
||||||
|
|
||||||
const Vector3 n = ray.point2 - ray.point1;
|
const Vector3 n = ray.point2 - ray.point1;
|
||||||
|
|
||||||
|
|
|
@ -106,7 +106,7 @@ void ConvexMeshShape::recalculateBounds() {
|
||||||
// Raycast method with feedback information
|
// Raycast method with feedback information
|
||||||
/// This method implements the technique in the book "Real-time Collision Detection" by
|
/// This method implements the technique in the book "Real-time Collision Detection" by
|
||||||
/// Christer Ericson.
|
/// Christer Ericson.
|
||||||
bool ConvexMeshShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, Collider* collider, MemoryAllocator& allocator) const {
|
bool ConvexMeshShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, Collider* collider, MemoryAllocator& /*allocator*/) const {
|
||||||
|
|
||||||
// Ray direction
|
// Ray direction
|
||||||
Vector3 direction = ray.point2 - ray.point1;
|
Vector3 direction = ray.point2 - ray.point1;
|
||||||
|
@ -184,7 +184,7 @@ bool ConvexMeshShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, Collider
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return true if a point is inside the collision shape
|
// Return true if a point is inside the collision shape
|
||||||
bool ConvexMeshShape::testPointInside(const Vector3& localPoint, Collider* collider) const {
|
bool ConvexMeshShape::testPointInside(const Vector3& localPoint, Collider* /*collider*/) const {
|
||||||
|
|
||||||
const HalfEdgeStructure& halfEdgeStructure = mPolyhedronMesh->getHalfEdgeStructure();
|
const HalfEdgeStructure& halfEdgeStructure = mPolyhedronMesh->getHalfEdgeStructure();
|
||||||
|
|
||||||
|
|
|
@ -95,7 +95,7 @@ void HeightFieldShape::getLocalBounds(Vector3& min, Vector3& max) const {
|
||||||
// and then for each rectangle in the sub-grid we generate two triangles that we use to test collision.
|
// and then for each rectangle in the sub-grid we generate two triangles that we use to test collision.
|
||||||
void HeightFieldShape::computeOverlappingTriangles(const AABB& localAABB, Array<Vector3>& triangleVertices,
|
void HeightFieldShape::computeOverlappingTriangles(const AABB& localAABB, Array<Vector3>& triangleVertices,
|
||||||
Array<Vector3>& triangleVerticesNormals, Array<uint>& shapeIds,
|
Array<Vector3>& triangleVerticesNormals, Array<uint>& shapeIds,
|
||||||
MemoryAllocator& allocator) const {
|
MemoryAllocator& /*allocator*/) const {
|
||||||
|
|
||||||
RP3D_PROFILE("HeightFieldShape::computeOverlappingTriangles()", mProfiler);
|
RP3D_PROFILE("HeightFieldShape::computeOverlappingTriangles()", mProfiler);
|
||||||
|
|
||||||
|
@ -373,8 +373,11 @@ bool HeightFieldShape::computeEnteringRayGridCoordinates(const Ray& ray, int& i,
|
||||||
decimal stepI, stepJ;
|
decimal stepI, stepJ;
|
||||||
const Vector3 aabbSize = mAABB.getExtent();
|
const Vector3 aabbSize = mAABB.getExtent();
|
||||||
|
|
||||||
const uint32 nbCellsI = mNbColumns - 1;
|
assert(mNbColumns > 0);
|
||||||
const uint32 nbCellsJ = mNbRows - 1;
|
assert(mNbRows > 0);
|
||||||
|
|
||||||
|
const int nbCellsI = mNbColumns - 1;
|
||||||
|
const int nbCellsJ = mNbRows - 1;
|
||||||
|
|
||||||
if (mAABB.raycast(ray, outHitGridPoint)) {
|
if (mAABB.raycast(ray, outHitGridPoint)) {
|
||||||
|
|
||||||
|
|
|
@ -60,7 +60,7 @@ void SphereShape::computeAABB(AABB& aabb, const Transform& transform) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Raycast method with feedback information
|
// Raycast method with feedback information
|
||||||
bool SphereShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, Collider* collider, MemoryAllocator& allocator) const {
|
bool SphereShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, Collider* collider, MemoryAllocator& /*allocator*/) const {
|
||||||
|
|
||||||
const Vector3 m = ray.point1;
|
const Vector3 m = ray.point1;
|
||||||
decimal c = m.dot(m) - mMargin * mMargin;
|
decimal c = m.dot(m) - mMargin * mMargin;
|
||||||
|
|
|
@ -136,7 +136,7 @@ void TriangleShape::computeAABB(AABB& aabb, const Transform& transform) const {
|
||||||
// Raycast method with feedback information
|
// Raycast method with feedback information
|
||||||
/// This method use the line vs triangle raycasting technique described in
|
/// This method use the line vs triangle raycasting technique described in
|
||||||
/// Real-time Collision Detection by Christer Ericson.
|
/// Real-time Collision Detection by Christer Ericson.
|
||||||
bool TriangleShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, Collider* collider, MemoryAllocator& allocator) const {
|
bool TriangleShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, Collider* collider, MemoryAllocator& /*allocator*/) const {
|
||||||
|
|
||||||
RP3D_PROFILE("TriangleShape::raycast()", mProfiler);
|
RP3D_PROFILE("TriangleShape::raycast()", mProfiler);
|
||||||
|
|
||||||
|
|
|
@ -43,14 +43,3 @@ Entity::Entity(uint32 index, uint32 generation)
|
||||||
assert(getIndex() == index);
|
assert(getIndex() == index);
|
||||||
assert(getGeneration() == generation);
|
assert(getGeneration() == generation);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Assignment operator
|
|
||||||
Entity& Entity::operator=(const Entity& entity) {
|
|
||||||
|
|
||||||
if (&entity != this) {
|
|
||||||
|
|
||||||
id = entity.id;
|
|
||||||
}
|
|
||||||
|
|
||||||
return *this;
|
|
||||||
}
|
|
||||||
|
|
Loading…
Reference in New Issue
Block a user