Use default keyword for default constructors/destructors

This commit is contained in:
Daniel Chappuis 2016-07-19 06:52:18 +02:00
parent cfede8f179
commit 2932403ff4
92 changed files with 72 additions and 337 deletions

View File

@ -39,8 +39,3 @@ Body::Body(bodyindex id)
mIsSleeping(false), mSleepTime(0), mUserData(nullptr) {
}
// Destructor
Body::~Body() {
}

View File

@ -89,7 +89,7 @@ class Body {
Body& operator=(const Body& body) = delete;
/// Destructor
virtual ~Body();
virtual ~Body() = default;
/// Return the ID of the body
bodyindex getID() const;

View File

@ -53,11 +53,6 @@ CollisionDetection::CollisionDetection(CollisionWorld* world, MemoryAllocator& m
fillInCollisionMatrix();
}
// Destructor
CollisionDetection::~CollisionDetection() {
}
// Compute the collision detection
void CollisionDetection::computeCollisionDetection() {

View File

@ -143,7 +143,7 @@ class CollisionDetection : public NarrowPhaseCallback {
CollisionDetection(CollisionWorld* world, MemoryAllocator& memoryAllocator);
/// Destructor
~CollisionDetection();
~CollisionDetection() = default;
/// Deleted copy-constructor
CollisionDetection(const CollisionDetection& collisionDetection) = delete;

View File

@ -80,9 +80,7 @@ struct RaycastInfo {
}
/// Destructor
~RaycastInfo() {
}
~RaycastInfo() = default;
/// Deleted copy constructor
RaycastInfo(const RaycastInfo& raycastInfo) = delete;

View File

@ -27,13 +27,3 @@
#include "TriangleMesh.h"
using namespace reactphysics3d;
// Constructor
TriangleMesh::TriangleMesh() {
}
// Destructor
TriangleMesh::~TriangleMesh() {
}

View File

@ -51,10 +51,10 @@ class TriangleMesh {
public:
/// Constructor
TriangleMesh();
TriangleMesh() = default;
/// Destructor
~TriangleMesh();
~TriangleMesh() = default;
/// Add a subpart of the mesh
void addSubpart(TriangleVertexArray* triangleVertexArray);

View File

@ -54,8 +54,3 @@ TriangleVertexArray::TriangleVertexArray(uint nbVertices, void* verticesStart, i
mVertexDataType = vertexDataType;
mIndexDataType = indexDataType;
}
// Destructor
TriangleVertexArray::~TriangleVertexArray() {
}

View File

@ -87,7 +87,7 @@ class TriangleVertexArray {
VertexDataType vertexDataType, IndexDataType indexDataType);
/// Destructor
~TriangleVertexArray();
~TriangleVertexArray() = default;
/// Return the vertex data type
VertexDataType getVertexDataType() const;

View File

@ -110,7 +110,7 @@ class BroadPhaseRaycastCallback : public DynamicAABBTreeRaycastCallback {
}
// Destructor
virtual ~BroadPhaseRaycastCallback() override {}
virtual ~BroadPhaseRaycastCallback() override = default;
// Called for a broad-phase shape that has to be tested for raycast
virtual decimal raycastBroadPhaseShape(int32 nodeId, const Ray& ray) override;

View File

@ -103,7 +103,7 @@ class DynamicAABBTreeOverlapCallback {
virtual void notifyOverlappingNode(int nodeId)=0;
// Destructor
virtual ~DynamicAABBTreeOverlapCallback() {}
virtual ~DynamicAABBTreeOverlapCallback() = default;
};
// Class DynamicAABBTreeRaycastCallback
@ -118,7 +118,7 @@ class DynamicAABBTreeRaycastCallback {
// Called when the AABB of a leaf node is hit by a ray
virtual decimal raycastBroadPhaseShape(int32 nodeId, const Ray& ray)=0;
virtual ~DynamicAABBTreeRaycastCallback() {}
virtual ~DynamicAABBTreeRaycastCallback() = default;
};

View File

@ -44,10 +44,10 @@ class CollisionDispatch {
public:
/// Constructor
CollisionDispatch() {}
CollisionDispatch() = default;
/// Destructor
virtual ~CollisionDispatch() {}
virtual ~CollisionDispatch() = default;
/// Initialize the collision dispatch configuration
virtual void init(CollisionDetection* collisionDetection,

View File

@ -33,16 +33,6 @@
using namespace reactphysics3d;
// Constructor
ConcaveVsConvexAlgorithm::ConcaveVsConvexAlgorithm() {
}
// Destructor
ConcaveVsConvexAlgorithm::~ConcaveVsConvexAlgorithm() {
}
// Return true and compute a contact info if the two bounding volumes collide
void ConcaveVsConvexAlgorithm::testCollision(const CollisionShapeInfo& shape1Info,
const CollisionShapeInfo& shape2Info,

View File

@ -73,7 +73,7 @@ class ConvexVsTriangleCallback : public TriangleCallback {
public:
/// Destructor
virtual ~ConvexVsTriangleCallback() override {}
virtual ~ConvexVsTriangleCallback() override = default;
/// Set the collision detection pointer
void setCollisionDetection(CollisionDetection* collisionDetection) {
@ -191,12 +191,6 @@ class ConcaveVsConvexAlgorithm : public NarrowPhaseAlgorithm {
// -------------------- Methods -------------------- //
/// Private copy-constructor
ConcaveVsConvexAlgorithm(const ConcaveVsConvexAlgorithm& algorithm);
/// Private assignment operator
ConcaveVsConvexAlgorithm& operator=(const ConcaveVsConvexAlgorithm& algorithm);
/// Process the concave triangle mesh collision using the smooth mesh collision algorithm
void processSmoothMeshCollision(OverlappingPair* overlappingPair,
std::vector<SmoothMeshContactInfo> contactPoints,
@ -215,10 +209,16 @@ class ConcaveVsConvexAlgorithm : public NarrowPhaseAlgorithm {
// -------------------- Methods -------------------- //
/// Constructor
ConcaveVsConvexAlgorithm();
ConcaveVsConvexAlgorithm() = default;
/// Destructor
virtual ~ConcaveVsConvexAlgorithm() override;
virtual ~ConcaveVsConvexAlgorithm() override = default;
/// Private copy-constructor
ConcaveVsConvexAlgorithm(const ConcaveVsConvexAlgorithm& algorithm) = delete;
/// Private assignment operator
ConcaveVsConvexAlgorithm& operator=(const ConcaveVsConvexAlgorithm& algorithm) = delete;
/// Compute a contact info if the two bounding volume collide
virtual void testCollision(const CollisionShapeInfo& shape1Info,

View File

@ -29,16 +29,6 @@
using namespace reactphysics3d;
// Constructor
DefaultCollisionDispatch::DefaultCollisionDispatch() {
}
// Destructor
DefaultCollisionDispatch::~DefaultCollisionDispatch() {
}
/// Initialize the collision dispatch configuration
void DefaultCollisionDispatch::init(CollisionDetection* collisionDetection,
MemoryAllocator* memoryAllocator) {

View File

@ -56,10 +56,10 @@ class DefaultCollisionDispatch : public CollisionDispatch {
public:
/// Constructor
DefaultCollisionDispatch();
DefaultCollisionDispatch() = default;
/// Destructor
virtual ~DefaultCollisionDispatch() override;
virtual ~DefaultCollisionDispatch() override = default;
/// Initialize the collision dispatch configuration
virtual void init(CollisionDetection* collisionDetection,

View File

@ -32,16 +32,6 @@
// We want to use the ReactPhysics3D namespace
using namespace reactphysics3d;
// Constructor
EPAAlgorithm::EPAAlgorithm() {
}
// Destructor
EPAAlgorithm::~EPAAlgorithm() {
}
// Decide if the origin is in the tetrahedron.
/// Return 0 if the origin is in the tetrahedron and return the number (1,2,3 or 4) of
/// the vertex that is wrong if the origin is not in the tetrahedron

View File

@ -108,10 +108,10 @@ class EPAAlgorithm {
// -------------------- Methods -------------------- //
/// Constructor
EPAAlgorithm();
EPAAlgorithm() = default;
/// Destructor
~EPAAlgorithm();
~EPAAlgorithm() = default;
/// Deleted copy-constructor
EPAAlgorithm(const EPAAlgorithm& algorithm) = delete;

View File

@ -32,11 +32,6 @@
// We want to use the ReactPhysics3D namespace
using namespace reactphysics3d;
// Constructor
EdgeEPA::EdgeEPA() {
}
// Constructor
EdgeEPA::EdgeEPA(TriangleEPA* ownerTriangle, int index)
: mOwnerTriangle(ownerTriangle), mIndex(index) {
@ -49,11 +44,6 @@ EdgeEPA::EdgeEPA(const EdgeEPA& edge) {
mIndex = edge.mIndex;
}
// Destructor
EdgeEPA::~EdgeEPA() {
}
// Return the index of the source vertex of the edge (vertex starting the edge)
uint EdgeEPA::getSourceVertexIndex() const {
return (*mOwnerTriangle)[mIndex];

View File

@ -59,7 +59,7 @@ class EdgeEPA {
// -------------------- Methods -------------------- //
/// Constructor
EdgeEPA();
EdgeEPA() = default;
/// Constructor
EdgeEPA(TriangleEPA* ownerTriangle, int index);
@ -68,7 +68,7 @@ class EdgeEPA {
EdgeEPA(const EdgeEPA& edge);
/// Destructor
~EdgeEPA();
~EdgeEPA() = default;
/// Return the pointer to the owner triangle
TriangleEPA* getOwnerTriangle() const;

View File

@ -32,11 +32,6 @@
// We use the ReactPhysics3D namespace
using namespace reactphysics3d;
// Constructor
TriangleEPA::TriangleEPA() {
}
// Constructor
TriangleEPA::TriangleEPA(uint indexVertex1, uint indexVertex2, uint indexVertex3)
: mIsObsolete(false) {
@ -45,11 +40,6 @@ TriangleEPA::TriangleEPA(uint indexVertex1, uint indexVertex2, uint indexVertex3
mIndicesVertices[2] = indexVertex3;
}
// Destructor
TriangleEPA::~TriangleEPA() {
}
// Compute the point v closest to the origin of this triangle
bool TriangleEPA::computeClosestPoint(const Vector3* vertices) {
const Vector3& p0 = vertices[mIndicesVertices[0]];

View File

@ -79,13 +79,13 @@ class TriangleEPA {
// -------------------- Methods -------------------- //
/// Constructor
TriangleEPA();
TriangleEPA() = default;
/// Constructor
TriangleEPA(uint v1, uint v2, uint v3);
/// Destructor
~TriangleEPA();
~TriangleEPA() = default;
/// Deleted copy-constructor
TriangleEPA(const TriangleEPA& triangle) = delete;

View File

@ -33,8 +33,3 @@ using namespace reactphysics3d;
TrianglesStore::TrianglesStore() : mNbTriangles(0) {
}
// Destructor
TrianglesStore::~TrianglesStore() {
}

View File

@ -62,7 +62,7 @@ class TrianglesStore {
TrianglesStore();
/// Destructor
~TrianglesStore();
~TrianglesStore() = default;
/// Deleted copy-constructor
TrianglesStore(const TrianglesStore& triangleStore) = delete;

View File

@ -42,11 +42,6 @@ GJKAlgorithm::GJKAlgorithm() : NarrowPhaseAlgorithm() {
}
// Destructor
GJKAlgorithm::~GJKAlgorithm() {
}
// Compute a contact info if the two collision shapes collide.
/// This method implements the Hybrid Technique for computing the penetration depth by
/// running the GJK algorithm on original objects (without margin). If the shapes intersect

View File

@ -84,7 +84,7 @@ class GJKAlgorithm : public NarrowPhaseAlgorithm {
GJKAlgorithm();
/// Destructor
~GJKAlgorithm();
~GJKAlgorithm() = default;
/// Deleted copy-constructor
GJKAlgorithm(const GJKAlgorithm& algorithm) = delete;

View File

@ -35,11 +35,6 @@ NarrowPhaseAlgorithm::NarrowPhaseAlgorithm()
}
// Destructor
NarrowPhaseAlgorithm::~NarrowPhaseAlgorithm() {
}
// Initalize the algorithm
void NarrowPhaseAlgorithm::init(CollisionDetection* collisionDetection, MemoryAllocator* memoryAllocator) {
mCollisionDetection = collisionDetection;

View File

@ -47,7 +47,7 @@ class NarrowPhaseCallback {
public:
virtual ~NarrowPhaseCallback() {}
virtual ~NarrowPhaseCallback() = default;
/// Called by a narrow-phase collision algorithm when a new contact has been found
virtual void notifyContact(OverlappingPair* overlappingPair,
@ -84,7 +84,7 @@ class NarrowPhaseAlgorithm {
NarrowPhaseAlgorithm();
/// Destructor
virtual ~NarrowPhaseAlgorithm();
virtual ~NarrowPhaseAlgorithm() = default;
/// Deleted copy-constructor
NarrowPhaseAlgorithm(const NarrowPhaseAlgorithm& algorithm) = delete;

View File

@ -28,17 +28,7 @@
#include "collision/shapes/SphereShape.h"
// We want to use the ReactPhysics3D namespace
using namespace reactphysics3d;
// Constructor
SphereVsSphereAlgorithm::SphereVsSphereAlgorithm() : NarrowPhaseAlgorithm() {
}
// Destructor
SphereVsSphereAlgorithm::~SphereVsSphereAlgorithm() {
}
using namespace reactphysics3d;
void SphereVsSphereAlgorithm::testCollision(const CollisionShapeInfo& shape1Info,
const CollisionShapeInfo& shape2Info,

View File

@ -49,10 +49,10 @@ class SphereVsSphereAlgorithm : public NarrowPhaseAlgorithm {
// -------------------- Methods -------------------- //
/// Constructor
SphereVsSphereAlgorithm();
SphereVsSphereAlgorithm() = default;
/// Destructor
virtual ~SphereVsSphereAlgorithm() override;
virtual ~SphereVsSphereAlgorithm() override = default;
/// Deleted copy-constructor
SphereVsSphereAlgorithm(const SphereVsSphereAlgorithm& algorithm) = delete;

View File

@ -31,11 +31,6 @@
using namespace reactphysics3d;
using namespace std;
// Constructor
AABB::AABB() {
}
// Constructor
AABB::AABB(const Vector3& minCoordinates, const Vector3& maxCoordinates)
:mMinCoordinates(minCoordinates), mMaxCoordinates(maxCoordinates) {
@ -48,11 +43,6 @@ AABB::AABB(const AABB& aabb)
}
// Destructor
AABB::~AABB() {
}
// Merge the AABB in parameter with the current one
void AABB::mergeWithAABB(const AABB& aabb) {
mMinCoordinates.x = std::min(mMinCoordinates.x, aabb.mMinCoordinates.x);

View File

@ -56,7 +56,7 @@ class AABB {
// -------------------- Methods -------------------- //
/// Constructor
AABB();
AABB() = default;
/// Constructor
AABB(const Vector3& minCoordinates, const Vector3& maxCoordinates);
@ -65,7 +65,7 @@ class AABB {
AABB(const AABB& aabb);
/// Destructor
~AABB();
~AABB() = default;
/// Return the center point
Vector3 getCenter() const;

View File

@ -44,11 +44,6 @@ BoxShape::BoxShape(const Vector3& extent, decimal margin)
assert(extent.z > decimal(0.0) && extent.z > margin);
}
// Destructor
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

View File

@ -82,7 +82,7 @@ class BoxShape : public ConvexShape {
BoxShape(const Vector3& extent, decimal margin = OBJECT_MARGIN);
/// Destructor
virtual ~BoxShape() override;
virtual ~BoxShape() override = default;
/// Deleted copy-constructor
BoxShape(const BoxShape& shape) = delete;

View File

@ -42,11 +42,6 @@ CapsuleShape::CapsuleShape(decimal radius, decimal height)
assert(height > decimal(0.0));
}
// Destructor
CapsuleShape::~CapsuleShape() {
}
// Return the local inertia tensor of the capsule
/**
* @param[out] tensor The 3x3 inertia tensor matrix of the shape in local-space

View File

@ -81,7 +81,7 @@ class CapsuleShape : public ConvexShape {
CapsuleShape(decimal radius, decimal height);
/// Destructor
virtual ~CapsuleShape() override;
virtual ~CapsuleShape() override = default;
/// Deleted copy-constructor
CapsuleShape(const CapsuleShape& shape) = delete;

View File

@ -36,11 +36,6 @@ CollisionShape::CollisionShape(CollisionShapeType type) : mType(type), mScaling(
}
// Destructor
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

View File

@ -84,7 +84,7 @@ class CollisionShape {
CollisionShape(CollisionShapeType type);
/// Destructor
virtual ~CollisionShape();
virtual ~CollisionShape() = default;
/// Deleted copy-constructor
CollisionShape(const CollisionShape& shape) = delete;

View File

@ -38,11 +38,6 @@ ConcaveMeshShape::ConcaveMeshShape(TriangleMesh* triangleMesh)
initBVHTree();
}
// Destructor
ConcaveMeshShape::~ConcaveMeshShape() {
}
// Insert all the triangles into the dynamic AABB tree
void ConcaveMeshShape::initBVHTree() {

View File

@ -140,7 +140,7 @@ class ConcaveMeshShape : public ConcaveShape {
ConcaveMeshShape(TriangleMesh* triangleMesh);
/// Destructor
virtual ~ConcaveMeshShape();
virtual ~ConcaveMeshShape() = default;
/// Deleted copy-constructor
ConcaveMeshShape(const ConcaveMeshShape& shape) = delete;

View File

@ -36,8 +36,3 @@ ConcaveShape::ConcaveShape(CollisionShapeType type)
mTriangleMargin(0), mRaycastTestType(TriangleRaycastSide::FRONT) {
}
// Destructor
ConcaveShape::~ConcaveShape() {
}

View File

@ -43,7 +43,7 @@ class TriangleCallback {
public:
/// Destructor
virtual ~TriangleCallback() {}
virtual ~TriangleCallback() = default;
/// Report a triangle
virtual void testTriangle(const Vector3* trianglePoints)=0;
@ -84,7 +84,7 @@ class ConcaveShape : public CollisionShape {
ConcaveShape(CollisionShapeType type);
/// Destructor
virtual ~ConcaveShape() override;
virtual ~ConcaveShape() override = default;
/// Deleted copy-constructor
ConcaveShape(const ConcaveShape& shape) = delete;

View File

@ -46,11 +46,6 @@ ConeShape::ConeShape(decimal radius, decimal height, decimal margin)
mSinTheta = mRadius / (sqrt(mRadius * mRadius + height * height));
}
// Destructor
ConeShape::~ConeShape() {
}
// Return a local support point in a given direction without the object margin
Vector3 ConeShape::getLocalSupportPointWithoutMargin(const Vector3& direction,
void** cachedCollisionData) const {

View File

@ -87,7 +87,7 @@ class ConeShape : public ConvexShape {
ConeShape(decimal mRadius, decimal height, decimal margin = OBJECT_MARGIN);
/// Destructor
virtual ~ConeShape() override;
virtual ~ConeShape() override = default;
/// Deleted copy-constructor
ConeShape(const ConeShape& shape) = delete;

View File

@ -140,11 +140,6 @@ ConvexMeshShape::ConvexMeshShape(decimal margin)
}
// Destructor
ConvexMeshShape::~ConvexMeshShape() {
}
// Return a local support point in a given direction without the object margin.
/// If the edges information is not used for collision detection, this method will go through
/// the whole vertices list and pick up the vertex with the largest dot product in the support

View File

@ -120,7 +120,7 @@ class ConvexMeshShape : public ConvexShape {
ConvexMeshShape(decimal margin = OBJECT_MARGIN);
/// Destructor
virtual ~ConvexMeshShape() override;
virtual ~ConvexMeshShape() override = default;
/// Deleted copy-constructor
ConvexMeshShape(const ConvexMeshShape& shape) = delete;

View File

@ -36,11 +36,6 @@ ConvexShape::ConvexShape(CollisionShapeType type, decimal margin)
}
// Destructor
ConvexShape::~ConvexShape() {
}
// Return a local support point in a given direction with the object margin
Vector3 ConvexShape::getLocalSupportPointWithMargin(const Vector3& direction,
void** cachedCollisionData) const {

View File

@ -56,9 +56,6 @@ class ConvexShape : public CollisionShape {
virtual Vector3 getLocalSupportPointWithoutMargin(const Vector3& direction,
void** cachedCollisionData) const=0;
/// Return true if a point is inside the collision shape
virtual bool testPointInside(const Vector3& worldPoint, ProxyShape* proxyShape) const=0;
public :
// -------------------- Methods -------------------- //
@ -67,7 +64,7 @@ class ConvexShape : public CollisionShape {
ConvexShape(CollisionShapeType type, decimal margin);
/// Destructor
virtual ~ConvexShape() override;
virtual ~ConvexShape() override = default;
/// Deleted copy-constructor
ConvexShape(const ConvexShape& shape) = delete;

View File

@ -43,11 +43,6 @@ CylinderShape::CylinderShape(decimal radius, decimal height, decimal margin)
assert(height > decimal(0.0));
}
// Destructor
CylinderShape::~CylinderShape() {
}
// Return a local support point in a given direction without the object margin
Vector3 CylinderShape::getLocalSupportPointWithoutMargin(const Vector3& direction,
void** cachedCollisionData) const {

View File

@ -84,7 +84,7 @@ class CylinderShape : public ConvexShape {
CylinderShape(decimal radius, decimal height, decimal margin = OBJECT_MARGIN);
/// Destructor
virtual ~CylinderShape() override;
virtual ~CylinderShape() override = default;
/// Deleted copy-constructor
CylinderShape(const CylinderShape& shape) = delete;

View File

@ -74,11 +74,6 @@ HeightFieldShape::HeightFieldShape(int nbGridColumns, int nbGridRows, decimal mi
}
}
// Destructor
HeightFieldShape::~HeightFieldShape() {
}
// Return the local bounds of the shape in x, y and z directions.
// This method is used to compute the AABB of the box
/**

View File

@ -159,7 +159,7 @@ class HeightFieldShape : public ConcaveShape {
int upAxis = 1, decimal integerHeightScale = 1.0f);
/// Destructor
virtual ~HeightFieldShape() override;
virtual ~HeightFieldShape() override = default;
/// Deleted copy-constructor
HeightFieldShape(const HeightFieldShape& shape) = delete;

View File

@ -39,11 +39,6 @@ SphereShape::SphereShape(decimal radius) : ConvexShape(CollisionShapeType::SPHER
assert(radius > decimal(0.0));
}
// Destructor
SphereShape::~SphereShape() {
}
// Raycast method with feedback information
bool SphereShape::raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const {

View File

@ -46,9 +46,6 @@ class SphereShape : public ConvexShape {
protected :
// -------------------- Attributes -------------------- //
// -------------------- Methods -------------------- //
/// Return a local support point in a given direction without the object margin
@ -72,7 +69,7 @@ class SphereShape : public ConvexShape {
SphereShape(decimal radius);
/// Destructor
virtual ~SphereShape() override;
virtual ~SphereShape() override = default;
/// Deleted copy-constructor
SphereShape(const SphereShape& shape) = delete;

View File

@ -47,11 +47,6 @@ TriangleShape::TriangleShape(const Vector3& point1, const Vector3& point2, const
mRaycastTestType = TriangleRaycastSide::FRONT;
}
// Destructor
TriangleShape::~TriangleShape() {
}
// Raycast method with feedback information
/// This method use the line vs triangle raycasting technique described in
/// Real-time Collision Detection by Christer Ericson.

View File

@ -87,7 +87,7 @@ class TriangleShape : public ConvexShape {
decimal margin = OBJECT_MARGIN);
/// Destructor
virtual ~TriangleShape() override;
virtual ~TriangleShape() override = default;
/// Deleted copy-constructor
TriangleShape(const TriangleShape& shape) = delete;

View File

@ -41,11 +41,6 @@ BallAndSocketJoint::BallAndSocketJoint(const BallAndSocketJointInfo& jointInfo)
mLocalAnchorPointBody2 = mBody2->getTransform().getInverse() * jointInfo.anchorPointWorldSpace;
}
// Destructor
BallAndSocketJoint::~BallAndSocketJoint() {
}
// Initialize before solving the constraint
void BallAndSocketJoint::initBeforeSolve(const ConstraintSolverData& constraintSolverData) {

View File

@ -128,7 +128,7 @@ class BallAndSocketJoint : public Joint {
BallAndSocketJoint(const BallAndSocketJointInfo& jointInfo);
/// Destructor
virtual ~BallAndSocketJoint() override;
virtual ~BallAndSocketJoint() override = default;
/// Deleted copy-constructor
BallAndSocketJoint(const BallAndSocketJoint& constraint) = delete;

View File

@ -51,8 +51,3 @@ ContactPoint::ContactPoint(const ContactPointInfo& contactInfo)
assert(mPenetrationDepth > 0.0);
}
// Destructor
ContactPoint::~ContactPoint() {
}

View File

@ -151,7 +151,7 @@ class ContactPoint {
ContactPoint(const ContactPointInfo& contactInfo);
/// Destructor
~ContactPoint();
~ContactPoint() = default;
/// Deleted copy-constructor
ContactPoint(const ContactPoint& contact) = delete;

View File

@ -49,11 +49,6 @@ FixedJoint::FixedJoint(const FixedJointInfo& jointInfo)
mInitOrientationDifferenceInv.inverse();
}
// Destructor
FixedJoint::~FixedJoint() {
}
// Initialize before solving the constraint
void FixedJoint::initBeforeSolve(const ConstraintSolverData& constraintSolverData) {

View File

@ -139,7 +139,7 @@ class FixedJoint : public Joint {
FixedJoint(const FixedJointInfo& jointInfo);
/// Destructor
virtual ~FixedJoint() override;
virtual ~FixedJoint() override = default;
/// Deleted copy-constructor
FixedJoint(const FixedJoint& constraint) = delete;

View File

@ -64,11 +64,6 @@ HingeJoint::HingeJoint(const HingeJointInfo& jointInfo)
mInitOrientationDifferenceInv.inverse();
}
// Destructor
HingeJoint::~HingeJoint() {
}
// Initialize before solving the constraint
void HingeJoint::initBeforeSolve(const ConstraintSolverData& constraintSolverData) {

View File

@ -290,7 +290,7 @@ class HingeJoint : public Joint {
HingeJoint(const HingeJointInfo& jointInfo);
/// Destructor
virtual ~HingeJoint() override;
virtual ~HingeJoint() override = default;
/// Deleted copy-constructor
HingeJoint(const HingeJoint& constraint) = delete;

View File

@ -37,8 +37,3 @@ Joint::Joint(const JointInfo& jointInfo)
assert(mBody1 != nullptr);
assert(mBody2 != nullptr);
}
// Destructor
Joint::~Joint() {
}

View File

@ -106,7 +106,7 @@ struct JointInfo {
}
/// Destructor
virtual ~JointInfo() {}
virtual ~JointInfo() = default;
};
@ -172,7 +172,7 @@ class Joint {
Joint(const JointInfo& jointInfo);
/// Destructor
virtual ~Joint();
virtual ~Joint() = default;
/// Deleted copy-constructor
Joint(const Joint& constraint) = delete;

View File

@ -63,11 +63,6 @@ SliderJoint::SliderJoint(const SliderJointInfo& jointInfo)
mSliderAxisBody1.normalize();
}
// Destructor
SliderJoint::~SliderJoint() {
}
// Initialize before solving the constraint
void SliderJoint::initBeforeSolve(const ConstraintSolverData& constraintSolverData) {

View File

@ -288,7 +288,7 @@ class SliderJoint : public Joint {
SliderJoint(const SliderJointInfo& jointInfo);
/// Destructor
virtual ~SliderJoint() override;
virtual ~SliderJoint() override = default;
/// Deleted copy-constructor
SliderJoint(const SliderJoint& constraint) = delete;

View File

@ -36,11 +36,6 @@ ConstraintSolver::ConstraintSolver(const std::map<RigidBody*, uint>& mapBodyToVe
}
// Destructor
ConstraintSolver::~ConstraintSolver() {
}
// Initialize the constraint solver for a given island
void ConstraintSolver::initializeForIsland(decimal dt, Island* island) {

View File

@ -173,7 +173,7 @@ class ConstraintSolver {
ConstraintSolver(const std::map<RigidBody*, uint>& mapBodyToVelocityIndex);
/// Destructor
~ConstraintSolver();
~ConstraintSolver() = default;
/// Initialize the constraint solver for a given island
void initializeForIsland(decimal dt, Island* island);

View File

@ -48,11 +48,6 @@ ContactSolver::ContactSolver(const std::map<RigidBody*, uint>& mapBodyToVelocity
}
// Destructor
ContactSolver::~ContactSolver() {
}
// Initialize the constraint solver for a given island
void ContactSolver::initializeForIsland(decimal dt, Island* island) {

View File

@ -413,7 +413,7 @@ class ContactSolver {
ContactSolver(const std::map<RigidBody*, uint>& mapBodyToVelocityIndex);
/// Destructor
virtual ~ContactSolver();
~ContactSolver() = default;
/// Initialize the constraint solver for a given island
void initializeForIsland(decimal dt, Island* island);

View File

@ -44,10 +44,10 @@ class EventListener {
public :
/// Constructor
EventListener() {}
EventListener() = default;
/// Destructor
virtual ~EventListener() {}
virtual ~EventListener() = default;
/// Called when a new contact point is found between two bodies that were separated before
/**

View File

@ -42,8 +42,3 @@ Material::Material(const Material& material)
mRollingResistance(material.mRollingResistance), mBounciness(material.mBounciness) {
}
// Destructor
Material::~Material() {
}

View File

@ -64,7 +64,7 @@ class Material {
Material(const Material& material);
/// Destructor
~Material();
~Material() = default;
/// Return the bounciness
decimal getBounciness() const;

View File

@ -35,9 +35,4 @@ OverlappingPair::OverlappingPair(ProxyShape* shape1, ProxyShape* shape2,
: mContactManifoldSet(shape1, shape2, memoryAllocator, nbMaxContactManifolds),
mCachedSeparatingAxis(1.0, 1.0, 1.0) {
}
// Destructor
OverlappingPair::~OverlappingPair() {
}
}

View File

@ -66,7 +66,7 @@ class OverlappingPair {
int nbMaxContactManifolds, MemoryAllocator& memoryAllocator);
/// Destructor
~OverlappingPair();
~OverlappingPair() = default;
/// Deleted copy-constructor
OverlappingPair(const OverlappingPair& pair) = delete;

View File

@ -34,11 +34,6 @@ Timer::Timer(double timeStep) : mTimeStep(timeStep), mIsRunning(false) {
assert(timeStep > 0.0);
}
// Destructor
Timer::~Timer() {
}
// Return the current time of the system in seconds
long double Timer::getCurrentSystemTime() {

View File

@ -79,7 +79,7 @@ class Timer {
Timer(double timeStep);
/// Destructor
~Timer();
~Timer() = default;
/// Deleted copy-constructor
Timer(const Timer& timer) = delete;

View File

@ -47,11 +47,6 @@ Matrix2x2::Matrix2x2(decimal a1, decimal a2, decimal b1, decimal b2) {
setAllValues(a1, a2, b1, b2);
}
// Destructor
Matrix2x2::~Matrix2x2() {
}
// Copy-constructor
Matrix2x2::Matrix2x2(const Matrix2x2& matrix) {
setAllValues(matrix.mRows[0][0], matrix.mRows[0][1],

View File

@ -60,7 +60,7 @@ class Matrix2x2 {
Matrix2x2(decimal a1, decimal a2, decimal b1, decimal b2);
/// Destructor
~Matrix2x2();
~Matrix2x2() = default;
/// Copy-constructor
Matrix2x2(const Matrix2x2& matrix);

View File

@ -49,11 +49,6 @@ Matrix3x3::Matrix3x3(decimal a1, decimal a2, decimal a3,
setAllValues(a1, a2, a3, b1, b2, b3, c1, c2, c3);
}
// Destructor
Matrix3x3::~Matrix3x3() {
}
// Copy-constructor
Matrix3x3::Matrix3x3(const Matrix3x3& matrix) {
setAllValues(matrix.mRows[0][0], matrix.mRows[0][1], matrix.mRows[0][2],

View File

@ -63,7 +63,7 @@ class Matrix3x3 {
decimal c1, decimal c2, decimal c3);
/// Destructor
~Matrix3x3();
~Matrix3x3() = default;
/// Copy-constructor
Matrix3x3(const Matrix3x3& matrix);

View File

@ -128,11 +128,6 @@ Quaternion::Quaternion(const Matrix3x3& matrix) {
}
}
// Destructor
Quaternion::~Quaternion() {
}
// Compute the rotation angle (in radians) and the rotation axis
/// This method is used to get the rotation angle (in radian) and the unit
/// rotation axis of an orientation quaternion.

View File

@ -82,7 +82,7 @@ struct Quaternion {
Quaternion(const Matrix3x3& matrix);
/// Destructor
~Quaternion();
~Quaternion() = default;
/// Set all the values
void setAllValues(decimal newX, decimal newY, decimal newZ, decimal newW);

View File

@ -67,9 +67,7 @@ struct Ray {
}
/// Destructor
~Ray() {
}
~Ray() = default;
/// Overloaded assignment operator
Ray& operator=(const Ray& ray) {

View File

@ -51,8 +51,3 @@ Transform::Transform(const Transform& transform)
: mPosition(transform.mPosition), mOrientation(transform.mOrientation) {
}
// Destructor
Transform::~Transform() {
}

View File

@ -65,7 +65,7 @@ class Transform {
Transform(const Vector3& position, const Quaternion& orientation);
/// Destructor
~Transform();
~Transform() = default;
/// Copy-constructor
Transform(const Transform& transform);

View File

@ -45,11 +45,6 @@ Vector2::Vector2(const Vector2& vector) : x(vector.x), y(vector.y) {
}
// Destructor
Vector2::~Vector2() {
}
// Return the corresponding unit vector
Vector2 Vector2::getUnit() const {
decimal lengthVector = length();

View File

@ -64,7 +64,7 @@ struct Vector2 {
Vector2(const Vector2& vector);
/// Destructor
~Vector2();
~Vector2() = default;
/// Set all the values of the vector
void setAllValues(decimal newX, decimal newY);

View File

@ -46,11 +46,6 @@ Vector3::Vector3(const Vector3& vector) : x(vector.x), y(vector.y), z(vector.z)
}
// Destructor
Vector3::~Vector3() {
}
// Return the corresponding unit vector
Vector3 Vector3::getUnit() const {
decimal lengthVector = length();

View File

@ -67,7 +67,7 @@ struct Vector3 {
Vector3(const Vector3& vector);
/// Destructor
~Vector3();
~Vector3() = default;
/// Set all the values of the vector
void setAllValues(decimal newX, decimal newY, decimal newZ);