[DEV] start to be good

This commit is contained in:
Edouard DUPIN 2017-06-23 22:19:30 +02:00
parent aa25f1fd11
commit 0d7b7b7465
31 changed files with 235 additions and 328 deletions

View File

@ -32,9 +32,9 @@ namespace ephysics {
float m_sleepTime; //!< Elapsed time since the body velocity was bellow the sleep velocity
void* m_userData; //!< Pointer that can be used to attach user data to the body
/// Private copy-constructor
Body(const Body& body);
Body(const Body& body) = delete;
/// Private assignment operator
Body& operator=(const Body& body);
Body& operator=(const Body& body) = delete;
public :
/**
* @brief Constructor

View File

@ -122,7 +122,7 @@ namespace ephysics {
* @param[in] transform The transformation of the collision shape that transforms the local-space of the collision shape int32_to 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.
*/
virtual ProxyShape* addCollisionShape(CollisionShape* _collisionShape, const etk::Transform3D& _transform);
ProxyShape* addCollisionShape(CollisionShape* _collisionShape, const etk::Transform3D& _transform);
/**
* @brief 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

View File

@ -56,10 +56,7 @@ namespace ephysics {
// Translate the body according to the translation of the center of mass position
m_transform.setPosition(m_centerOfMassWorld - m_transform.getOrientation() * m_centerOfMassLocal);
}
/**
* @brief Update the broad-phase state for this body (because it has moved for instance)
*/
virtual void updateBroadPhaseState() const;
void updateBroadPhaseState() const override;
public :
/**
* @brief Constructor
@ -72,7 +69,7 @@ namespace ephysics {
* @brief Virtual Destructor
*/
virtual ~RigidBody();
void setType(BodyType _type); // TODO: override
void setType(BodyType _type) override;
/**
* @brief Set the current position and orientation
* @param[in] _transform The transformation of the body that transforms the local-space of the body int32_to world-space
@ -279,15 +276,10 @@ namespace ephysics {
* @param[in] _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.
*/
virtual ProxyShape* addCollisionShape(CollisionShape* _collisionShape,
const etk::Transform3D& _transform,
float _mass);
/**
* @brief 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[in] _proxyShape The pointer of the proxy shape you want to remove
*/
virtual void removeCollisionShape(const ProxyShape* _proxyShape);
ProxyShape* addCollisionShape(CollisionShape* _collisionShape,
const etk::Transform3D& _transform,
float _mass);
virtual void removeCollisionShape(const ProxyShape* _proxyShape) override;
/**
* @brief Recompute the center of mass, total mass and inertia tensor of the body using all the collision shapes attached to the body.
*/

View File

@ -133,7 +133,7 @@ namespace ephysics {
/// Return a reference to the world memory allocator
MemoryAllocator& getWorldMemoryAllocator();
/// Called by a narrow-phase collision algorithm when a new contact has been found
virtual void notifyContact(OverlappingPair* _overlappingPair, const ContactPointInfo& _contactInfo);
virtual void notifyContact(OverlappingPair* _overlappingPair, const ContactPointInfo& _contactInfo) override;
/// Create a new contact
void createContact(OverlappingPair* _overlappingPair, const ContactPointInfo& _contactInfo);
friend class DynamicsWorld;

View File

@ -15,11 +15,6 @@ DefaultCollisionDispatch::DefaultCollisionDispatch() {
}
// Destructor
DefaultCollisionDispatch::~DefaultCollisionDispatch() {
}
/// Initialize the collision dispatch configuration
void DefaultCollisionDispatch::init(CollisionDetection* collisionDetection,
MemoryAllocator* memoryAllocator) {

View File

@ -24,13 +24,8 @@ class DefaultCollisionDispatch : public CollisionDispatch {
public:
/// Constructor
DefaultCollisionDispatch();
/// Destructor
virtual ~DefaultCollisionDispatch();
/// Initialize the collision dispatch configuration
virtual void init(CollisionDetection* _collisionDetection, MemoryAllocator* _memoryAllocator);
/// Select and return the narrow-phase collision detection algorithm to
/// use between two types of collision shapes.
virtual NarrowPhaseAlgorithm* selectAlgorithm(int32_t _type1, int32_t _type2);
void init(CollisionDetection* _collisionDetection, MemoryAllocator* _memoryAllocator) override;
NarrowPhaseAlgorithm* selectAlgorithm(int32_t _type1, int32_t _type2) override;
};
}

View File

@ -29,31 +29,21 @@ class BoxShape : public ConvexShape {
protected :
vec3 m_extent; //!< Extent sizes of the box in the x, y and z direction
/// Private copy-constructor
BoxShape(const BoxShape& shape);
BoxShape(const BoxShape& _shape) = delete;
/// Private assignment operator
BoxShape& operator=(const BoxShape& shape);
/// Return a local support point in a given direction without the object margin
virtual vec3 getLocalSupportPointWithoutMargin(const vec3& direction,
void** cachedCollisionData) const;
/// Return true if a point is inside the collision shape
virtual bool testPointInside(const vec3& localPoint, ProxyShape* proxyShape) const;
/// Raycast method with feedback information
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const;
/// Return the number of bytes used by the collision shape
virtual size_t getSizeInBytes() const;
BoxShape& operator=(const BoxShape& _shape) = delete;
vec3 getLocalSupportPointWithoutMargin(const vec3& _direction, void** _cachedCollisionData) const override;
bool testPointInside(const vec3& _localPoint, ProxyShape* _proxyShape) const override;
bool raycast(const Ray& _ray, RaycastInfo& _raycastInfo, ProxyShape* _proxyShape) const override;
size_t getSizeInBytes() const override;
public :
/// Constructor
BoxShape(const vec3& extent, float margin = OBJECT_MARGIN);
/// Destructor
virtual ~BoxShape() = default;
BoxShape(const vec3& _extent, float _margin = OBJECT_MARGIN);
/// Return the extents of the box
vec3 getExtent() const;
/// Set the scaling vector of the collision shape
virtual void setLocalScaling(const vec3& scaling);
/// Return the local bounds of the shape in x, y and z directions
virtual void getLocalBounds(vec3& _min, vec3& _max) const;
/// Return the local inertia tensor of the collision shape
virtual void computeLocalInertiaTensor(etk::Matrix3x3& tensor, float mass) const;
void setLocalScaling(const vec3& _scaling) override;
void getLocalBounds(vec3& _min, vec3& _max) const override;
void computeLocalInertiaTensor(etk::Matrix3x3& _tensor, float _mass) const override;
};
}

View File

@ -23,22 +23,17 @@ namespace ephysics {
protected:
float m_halfHeight; //!< Half height of the capsule (height = distance between the centers of the two spheres)
/// Private copy-constructor
CapsuleShape(const CapsuleShape& shape);
CapsuleShape(const CapsuleShape& _shape);
/// Private assignment operator
CapsuleShape& operator=(const CapsuleShape& shape);
/// Return a local support point in a given direction without the object margin
virtual vec3 getLocalSupportPointWithoutMargin(const vec3& direction,
void** cachedCollisionData) const;
/// Return true if a point is inside the collision shape
virtual bool testPointInside(const vec3& localPoint, ProxyShape* proxyShape) const;
/// Raycast method with feedback information
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const;
CapsuleShape& operator=(const CapsuleShape& _shape);
vec3 getLocalSupportPointWithoutMargin(const vec3& _direction, void** _cachedCollisionData) const override;
bool testPointInside(const vec3& _localPoint, ProxyShape* _proxyShape) const override;
bool raycast(const Ray& _ray, RaycastInfo& _raycastInfo, ProxyShape* _proxyShape) const override;
/// Raycasting method between a ray one of the two spheres end cap of the capsule
bool raycastWithSphereEndCap(const vec3& point1, const vec3& point2,
const vec3& sphereCenter, float maxFraction,
vec3& hitLocalPoint, float& hitFraction) const;
/// Return the number of bytes used by the collision shape
virtual size_t getSizeInBytes() const;
bool raycastWithSphereEndCap(const vec3& _point1, const vec3& _point2,
const vec3& _sphereCenter, float _maxFraction,
vec3& _hitLocalPoint, float& _hitFraction) const;
size_t getSizeInBytes() const override;
public :
/// Constructor
CapsuleShape(float _radius, float _height);
@ -48,11 +43,8 @@ namespace ephysics {
float getRadius() const;
/// Return the height of the capsule
float getHeight() const;
/// Set the scaling vector of the collision shape
virtual void setLocalScaling(const vec3& scaling);
/// Return the local bounds of the shape in x, y and z directions
virtual void getLocalBounds(vec3& min, vec3& max) const;
/// Return the local inertia tensor of the collision shape
virtual void computeLocalInertiaTensor(etk::Matrix3x3& tensor, float mass) const;
void setLocalScaling(const vec3& _scaling) override;
void getLocalBounds(vec3& _min, vec3& _max) const override;
void computeLocalInertiaTensor(etk::Matrix3x3& _tensor, float _mass) const override;
};
}

View File

@ -58,19 +58,34 @@ class CollisionShape {
* @return false If it is concave
*/
virtual bool isConvex() const = 0;
/// Return the local bounds of the shape in x, y and z directions
/**
* @brief Get 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
*/
virtual void getLocalBounds(vec3& _min, vec3& _max) const=0;
/// Return the scaling vector of the collision shape
vec3 getScaling() const {
return m_scaling;
}
/// Set the local scaling vector of the collision shape
/**
* @brief Set the scaling vector of the collision shape
*/
virtual void setLocalScaling(const vec3& _scaling) {
m_scaling = _scaling;
}
/// Return the local inertia tensor of the collision shapes
/**
* @brief Compute the local inertia tensor of the sphere
* @param[out] _tensor The 3x3 inertia tensor matrix of the shape in local-space coordinates
* @param[in] _mass Mass to use to compute the inertia tensor of the collision shape
*/
virtual void computeLocalInertiaTensor(etk::Matrix3x3& _tensor, float _mass) const=0;
/// Compute the world-space AABB of the collision shape given a transform
/**
* @brief 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[in] _transform etk::Transform3D used to compute the AABB of the collision shape
*/
virtual void computeAABB(AABB& _aabb, const etk::Transform3D& _transform) const;
/**
* @brief Check if the shape is convex

View File

@ -33,8 +33,7 @@ namespace ephysics {
ConcaveShape(const ConcaveShape& _shape) = delete;
/// Private assignment operator
ConcaveShape& operator=(const ConcaveShape& _shape) = delete;
/// Return true if a point is inside the collision shape
virtual bool testPointInside(const vec3& _localPoint, ProxyShape* _proxyShape) const;
virtual bool testPointInside(const vec3& _localPoint, ProxyShape* _proxyShape) const override;
public :
/// Constructor
ConcaveShape(CollisionShapeType _type);
@ -47,7 +46,7 @@ namespace ephysics {
// Set the raycast test type (front, back, front-back)
void setRaycastTestType(TriangleRaycastSide _testType);
/// Return true if the collision shape is convex, false if it is concave
virtual bool isConvex() const;
virtual bool isConvex() const override;
/// Use a callback method on all triangles of the concave shape inside a given AABB
virtual void testAllTriangles(TriangleCallback& _callback, const AABB& _localAABB) const=0;
/// Return true if the smooth mesh collision is enabled

View File

@ -33,15 +33,10 @@ namespace ephysics {
ConeShape(const ConeShape& _shape) = delete;
/// Private assignment operator
ConeShape& operator=(const ConeShape& _shape) = delete;
/// Return a local support point in a given direction without the object margin
virtual vec3 getLocalSupportPointWithoutMargin(const vec3& _direction,
void** _cachedCollisionData) const;
/// Return true if a point is inside the collision shape
virtual bool testPointInside(const vec3& _localPoint, ProxyShape* _proxyShape) const;
/// Raycast method with feedback information
virtual bool raycast(const Ray& _ray, RaycastInfo& _raycastInfo, ProxyShape* _proxyShape) const;
/// Return the number of bytes used by the collision shape
virtual size_t getSizeInBytes() const;
virtual vec3 getLocalSupportPointWithoutMargin(const vec3& _direction, void** _cachedCollisionData) const override;
bool testPointInside(const vec3& _localPoint, ProxyShape* _proxyShape) const override;
bool raycast(const Ray& _ray, RaycastInfo& _raycastInfo, ProxyShape* _proxyShape) const override;
size_t getSizeInBytes() const override;
public :
/// Constructor
ConeShape(float _radius, float _height, float _margin = OBJECT_MARGIN);
@ -49,11 +44,9 @@ namespace ephysics {
float getRadius() const;
/// Return the height
float getHeight() const;
/// Set the scaling vector of the collision shape
virtual void setLocalScaling(const vec3& _scaling);
/// Return the local bounds of the shape in x, y and z directions
virtual void getLocalBounds(vec3& _min, vec3& _max) const;
/// Return the local inertia tensor of the collision shape
virtual void computeLocalInertiaTensor(etk::Matrix3x3& _tensor, float _mass) const;
void setLocalScaling(const vec3& _scaling) override;
void getLocalBounds(vec3& _min, vec3& _max) const override;
void computeLocalInertiaTensor(etk::Matrix3x3& _tensor, float _mass) const override;
};
}

View File

@ -120,12 +120,6 @@ ConvexMeshShape::ConvexMeshShape(float margin)
m_maxBounds(0, 0, 0), m_isEdgesInformationUsed(false) {
}
// 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

@ -40,46 +40,39 @@ namespace ephysics {
bool m_isEdgesInformationUsed; //!< True if the shape contains the edges of the convex mesh in order to make the collision detection faster
std::map<uint32_t, std::set<uint32_t> > m_edgesAdjacencyList; //!< Adjacency list representing the edges of the mesh
/// Private copy-constructor
ConvexMeshShape(const ConvexMeshShape& shape);
ConvexMeshShape(const ConvexMeshShape& _shape);
/// Private assignment operator
ConvexMeshShape& operator=(const ConvexMeshShape& shape);
ConvexMeshShape& operator=(const ConvexMeshShape& _shape);
/// Recompute the bounds of the mesh
void recalculateBounds();
/// Set the scaling vector of the collision shape
virtual void setLocalScaling(const vec3& scaling);
/// Return a local support point in a given direction without the object margin.
virtual vec3 getLocalSupportPointWithoutMargin(const vec3& direction,
void** cachedCollisionData) const;
/// Return true if a point is inside the collision shape
virtual bool testPointInside(const vec3& localPoint, ProxyShape* proxyShape) const;
/// Raycast method with feedback information
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const;
/// Return the number of bytes used by the collision shape
virtual size_t getSizeInBytes() const;
void setLocalScaling(const vec3& _scaling) override;
vec3 getLocalSupportPointWithoutMargin(const vec3& _direction, void** _cachedCollisionData) const override;
bool testPointInside(const vec3& _localPoint, ProxyShape* _proxyShape) const override;
bool raycast(const Ray& _ray, RaycastInfo& _raycastInfo, ProxyShape* _proxyShape) const override;
size_t getSizeInBytes() const override;
public :
/// Constructor to initialize with an array of 3D vertices.
ConvexMeshShape(const float* arrayVertices, uint32_t nbVertices, int32_t stride,
float margin = OBJECT_MARGIN);
ConvexMeshShape(const float* _arrayVertices,
uint32_t _nbVertices,
int32_t _stride,
float _margin = OBJECT_MARGIN);
/// Constructor to initialize with a triangle vertex array
ConvexMeshShape(TriangleVertexArray* triangleVertexArray, bool isEdgesInformationUsed = true,
float margin = OBJECT_MARGIN);
ConvexMeshShape(TriangleVertexArray* _triangleVertexArray,
bool _isEdgesInformationUsed = true,
float _margin = OBJECT_MARGIN);
/// Constructor.
ConvexMeshShape(float margin = OBJECT_MARGIN);
/// Destructor
virtual ~ConvexMeshShape();
/// Return the local bounds of the shape in x, y and z directions
virtual void getLocalBounds(vec3& min, vec3& max) const;
/// Return the local inertia tensor of the collision shape.
virtual void computeLocalInertiaTensor(etk::Matrix3x3& tensor, float mass) const;
ConvexMeshShape(float _margin = OBJECT_MARGIN);
void getLocalBounds(vec3& _min, vec3& _max) const override;
void computeLocalInertiaTensor(etk::Matrix3x3& _tensor, float _mass) const override;
/// Add a vertex int32_to the convex mesh
void addVertex(const vec3& vertex);
void addVertex(const vec3& _vertex);
/// Add an edge int32_to the convex mesh by specifying the two vertex indices of the edge.
void addEdge(uint32_t v1, uint32_t v2);
void addEdge(uint32_t _v1, uint32_t _v2);
/// Return true if the edges information is used to speed up the collision detection
bool isEdgesInformationUsed() const;
/// Set the variable to know if the edges information is used to speed up the
/// collision detection
void setIsEdgesInformationUsed(bool isEdgesUsed);
void setIsEdgesInformationUsed(bool _isEdgesUsed);
};
}

View File

@ -15,17 +15,14 @@ class ConvexShape : public CollisionShape {
protected :
float m_margin; //!< Margin used for the GJK collision detection algorithm
/// Private copy-constructor
ConvexShape(const ConvexShape& shape);
ConvexShape(const ConvexShape& shape) = delete;
/// Private assignment operator
ConvexShape& operator=(const ConvexShape& shape);
ConvexShape& operator=(const ConvexShape& shape) = delete;
// Return a local support point in a given direction with the object margin
vec3 getLocalSupportPointWithMargin(const vec3& direction,
void** cachedCollisionData) const;
virtual vec3 getLocalSupportPointWithMargin(const vec3& _direction, void** _cachedCollisionData) const;
/// Return a local support point in a given direction without the object margin
virtual vec3 getLocalSupportPointWithoutMargin(const vec3& direction,
void** cachedCollisionData) const=0;
/// Return true if a point is inside the collision shape
virtual bool testPointInside(const vec3& worldPoint, ProxyShape* proxyShape) const=0;
virtual vec3 getLocalSupportPointWithoutMargin(const vec3& _direction, void** _cachedCollisionData) const=0;
bool testPointInside(const vec3& _worldPoint, ProxyShape* _proxyShape) const override = 0;
public :
/// Constructor
ConvexShape(CollisionShapeType type, float margin);

View File

@ -4,14 +4,12 @@
* @license BSD 3 clauses (see license file)
*/
// Libraries
#include <ephysics/collision/shapes/CylinderShape.hpp>
#include <ephysics/collision/ProxyShape.hpp>
#include <ephysics/configuration.hpp>
using namespace ephysics;
// Constructor
/**
* @param radius Radius of the cylinder (in meters)
* @param height Height of the cylinder (in meters)
@ -24,10 +22,6 @@ CylinderShape::CylinderShape(float radius, float height, float margin)
assert(height > 0.0f);
}
// Destructor
CylinderShape::~CylinderShape() {
}
// Return a local support point in a given direction without the object margin
vec3 CylinderShape::getLocalSupportPointWithoutMargin(const vec3& _direction, void** _cachedCollisionData) const {

View File

@ -28,33 +28,23 @@ class CylinderShape : public ConvexShape {
float mRadius; //!< Radius of the base
float m_halfHeight; //!< Half height of the cylinder
/// Private copy-constructor
CylinderShape(const CylinderShape& shape);
CylinderShape(const CylinderShape&) = delete;
/// Private assignment operator
CylinderShape& operator=(const CylinderShape& shape);
/// Return a local support point in a given direction without the object margin
virtual vec3 getLocalSupportPointWithoutMargin(const vec3& direction,
void** cachedCollisionData) const;
/// Return true if a point is inside the collision shape
virtual bool testPointInside(const vec3& localPoint, ProxyShape* proxyShape) const;
/// Raycast method with feedback information
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const;
/// Return the number of bytes used by the collision shape
virtual size_t getSizeInBytes() const;
CylinderShape& operator=(const CylinderShape&) = delete;
vec3 getLocalSupportPointWithoutMargin(const vec3& _direction, void** _cachedCollisionData) const override;
bool testPointInside(const vec3& _localPoint, ProxyShape* _proxyShape) const override;
bool raycast(const Ray& _ray, RaycastInfo& _raycastInfo, ProxyShape* _proxyShape) const override;
size_t getSizeInBytes() const override;
public :
/// Constructor
CylinderShape(float radius, float height, float margin = OBJECT_MARGIN);
/// Destructor
virtual ~CylinderShape();
CylinderShape(float _radius, float _height, float _margin = OBJECT_MARGIN);
/// Return the radius
float getRadius() const;
/// Return the height
float getHeight() const;
/// Set the scaling vector of the collision shape
virtual void setLocalScaling(const vec3& scaling);
/// Return the local bounds of the shape in x, y and z directions
virtual void getLocalBounds(vec3& min, vec3& max) const;
/// Return the local inertia tensor of the collision shape
virtual void computeLocalInertiaTensor(etk::Matrix3x3& tensor, float mass) const;
void setLocalScaling(const vec3& _scaling) override;
void getLocalBounds(vec3& _min, vec3& _max) const override;
void computeLocalInertiaTensor(etk::Matrix3x3& _tensor, float _mass) const override;
};
}

View File

@ -55,10 +55,6 @@ HeightFieldShape::HeightFieldShape(int32_t nbGridColumns, int32_t nbGridRows, fl
}
}
// 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

@ -75,13 +75,11 @@ namespace ephysics {
const void* m_heightFieldData; //!< Array of data with all the height values of the height field
AABB m_AABB; //!< Local AABB of the height field (without scaling)
/// Private copy-constructor
HeightFieldShape(const HeightFieldShape& _shape);
HeightFieldShape(const HeightFieldShape&) = delete;
/// Private assignment operator
HeightFieldShape& operator=(const HeightFieldShape& _shape);
/// Raycast method with feedback information
virtual bool raycast(const Ray& _ray, RaycastInfo& _raycastInfo, ProxyShape* _proxyShape) const;
/// Return the number of bytes used by the collision shape
virtual size_t getSizeInBytes() const;
HeightFieldShape& operator=(const HeightFieldShape&) = delete;
bool raycast(const Ray& _ray, RaycastInfo& _raycastInfo, ProxyShape* _proxyShape) const override;
size_t getSizeInBytes() const override;
/// Insert all the triangles int32_to the dynamic AABB tree
void initBVHTree();
/// Return the three vertices coordinates (in the array outTriangleVertices) of a triangle
@ -106,22 +104,16 @@ namespace ephysics {
const void* _heightFieldData,
HeightDataType _dataType,
int32_t _upAxis = 1, float _integerHeightScale = 1.0f);
/// Destructor
~HeightFieldShape();
/// Return the number of rows in the height field
int32_t getNbRows() const;
/// Return the number of columns in the height field
int32_t getNbColumns() const;
/// Return the type of height value in the height field
HeightDataType getHeightDataType() const;
/// Return the local bounds of the shape in x, y and z directions.
virtual void getLocalBounds(vec3& _min, vec3& _max) const;
/// Set the local scaling vector of the collision shape
virtual void setLocalScaling(const vec3& _scaling);
/// Return the local inertia tensor of the collision shape
virtual void computeLocalInertiaTensor(etk::Matrix3x3& _tensor, float _mass) const;
/// Use a callback method on all triangles of the concave shape inside a given AABB
virtual void testAllTriangles(TriangleCallback& _callback, const AABB& _localAABB) const;
void getLocalBounds(vec3& _min, vec3& _max) const override;
void setLocalScaling(const vec3& _scaling) override;
void computeLocalInertiaTensor(etk::Matrix3x3& _tensor, float _mass) const override;
virtual void testAllTriangles(TriangleCallback& _callback, const AABB& _localAABB) const override;
friend class ConvexTriangleAABBOverlapCallback;
friend class ConcaveMeshRaycastCallback;
};

View File

@ -20,11 +20,6 @@ SphereShape::SphereShape(float radius) : ConvexShape(SPHERE, radius) {
assert(radius > 0.0f);
}
// Destructor
SphereShape::~SphereShape() {
}
void SphereShape::setLocalScaling(const vec3& _scaling) {
m_margin = (m_margin / m_scaling.x()) * _scaling.x();

View File

@ -22,37 +22,19 @@ namespace ephysics {
protected :
SphereShape(const SphereShape& _shape);
SphereShape& operator=(const SphereShape& _shape) = delete;
/**
* @brief Get a local support point in a given direction without the object margin
* @param[in] _direction
* @param[in] _cachedCollisionData
* @return the center of the sphere (the radius is taken int32_to account in the object margin)
*/
vec3 getLocalSupportPointWithoutMargin(const vec3& _direction, void** _cachedCollisionData) const {
vec3 getLocalSupportPointWithoutMargin(const vec3& _direction, void** _cachedCollisionData) const override {
return vec3(0.0, 0.0, 0.0);
}
/**
* @brief Test if a point is inside a shape
* @param[in] _localPoint Point to check
* @param[in] _proxyShape Shape to check
* @return true if a point is inside the collision shape
*/
bool testPointInside(const vec3& _localPoint, ProxyShape* _proxyShape) const {
bool testPointInside(const vec3& _localPoint, ProxyShape* _proxyShape) const override {
return (_localPoint.length2() < m_margin * m_margin);
}
/// Raycast method with feedback information
virtual bool raycast(const Ray& _ray, RaycastInfo& _raycastInfo, ProxyShape* _proxyShape) const;
/**
* @brief Return the number of bytes used by the collision shape
*/
virtual size_t getSizeInBytes() const {
bool raycast(const Ray& _ray, RaycastInfo& _raycastInfo, ProxyShape* _proxyShape) const override;
size_t getSizeInBytes() const override {
return sizeof(SphereShape);
}
public :
/// Constructor
SphereShape(float _radius);
/// Destructor
virtual ~SphereShape();
/**
* @brief Get the radius of the sphere
* @return Radius of the sphere (in meters)
@ -60,29 +42,10 @@ namespace ephysics {
float getRadius() const {
return m_margin;
}
/**
* @brief Set the scaling vector of the collision shape
*/
virtual void setLocalScaling(const vec3& _scaling);
/**
* @brief Get 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
*/
virtual void getLocalBounds(vec3& _min, vec3& _max) const;
/**
* @brief Compute the local inertia tensor of the sphere
* @param[out] _tensor The 3x3 inertia tensor matrix of the shape in local-space coordinates
* @param[in] _mass Mass to use to compute the inertia tensor of the collision shape
*/
virtual void computeLocalInertiaTensor(etk::Matrix3x3& _tensor, float _mass) const;
/**
* @brief 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[in] _transform etk::Transform3D used to compute the AABB of the collision shape
*/
virtual void computeAABB(AABB& _aabb, const etk::Transform3D& _transform) const;
void setLocalScaling(const vec3& _scaling) override;
void getLocalBounds(vec3& _min, vec3& _max) const override;
void computeLocalInertiaTensor(etk::Matrix3x3& _tensor, float _mass) const override;
void computeAABB(AABB& _aabb, const etk::Transform3D& _transform) const override;
};
}

View File

@ -30,29 +30,20 @@ namespace ephysics {
TriangleShape(const TriangleShape& shape);
/// Private assignment operator
TriangleShape& operator=(const TriangleShape& shape);
/// Return a local support point in a given direction without the object margin
virtual vec3 getLocalSupportPointWithoutMargin(const vec3& direction,
void** cachedCollisionData) const;
/// Return true if a point is inside the collision shape
virtual bool testPointInside(const vec3& localPoint, ProxyShape* proxyShape) const;
/// Raycast method with feedback information
virtual bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const;
/// Return the number of bytes used by the collision shape
virtual size_t getSizeInBytes() const;
vec3 getLocalSupportPointWithoutMargin(const vec3& _direction, void** _cachedCollisionData) const override;
bool testPointInside(const vec3& _localPoint, ProxyShape* _proxyShape) const override;
bool raycast(const Ray& ray, RaycastInfo& raycastInfo, ProxyShape* proxyShape) const override;
size_t getSizeInBytes() const override;
public:
/// Constructor
TriangleShape(const vec3& point1, const vec3& point2, const vec3& point3,
float margin = OBJECT_MARGIN);
/// Destructor
virtual ~TriangleShape();
/// Return the local bounds of the shape in x, y and z directions.
virtual void getLocalBounds(vec3& min, vec3& max) const;
/// Set the local scaling vector of the collision shape
virtual void setLocalScaling(const vec3& scaling);
/// Return the local inertia tensor of the collision shape
virtual void computeLocalInertiaTensor(etk::Matrix3x3& tensor, float mass) const;
/// Update the AABB of a body using its collision shape
virtual void computeAABB(AABB& aabb, const etk::Transform3D& transform) const;
void getLocalBounds(vec3& min, vec3& max) const override;
void setLocalScaling(const vec3& scaling) override;
void computeLocalInertiaTensor(etk::Matrix3x3& tensor, float mass) const override;
void computeAABB(AABB& aabb, const etk::Transform3D& transform) const override;
/// Return the raycast test type (front, back, front-back)
TriangleRaycastSide getRaycastTestType() const;
// Set the raycast test type (front, back, front-back)

View File

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

View File

@ -51,22 +51,15 @@ namespace ephysics {
BallAndSocketJoint(const BallAndSocketJoint& constraint);
/// Private assignment operator
BallAndSocketJoint& operator=(const BallAndSocketJoint& constraint);
/// Return the number of bytes used by the joint
virtual size_t getSizeInBytes() const {
size_t getSizeInBytes() const override {
return sizeof(BallAndSocketJoint);
}
/// Initialize before solving the constraint
virtual void initBeforeSolve(const ConstraintSolverData& constraintSolverData);
/// Warm start the constraint (apply the previous impulse at the beginning of the step)
virtual void warmstart(const ConstraintSolverData& constraintSolverData);
/// Solve the velocity constraint
virtual void solveVelocityConstraint(const ConstraintSolverData& constraintSolverData);
/// Solve the position constraint (for position error correction)
virtual void solvePositionConstraint(const ConstraintSolverData& constraintSolverData);
void initBeforeSolve(const ConstraintSolverData& _constraintSolverData) override;
void warmstart(const ConstraintSolverData& _constraintSolverData) override;
void solveVelocityConstraint(const ConstraintSolverData& _constraintSolverData) override;
void solvePositionConstraint(const ConstraintSolverData& _constraintSolverData) override;
public:
/// Constructor
BallAndSocketJoint(const BallAndSocketJointInfo& jointInfo);
/// Destructor
virtual ~BallAndSocketJoint();
BallAndSocketJoint(const BallAndSocketJointInfo& _jointInfo);
};
}

View File

@ -4,7 +4,6 @@
* @license BSD 3 clauses (see license file)
*/
// Libraries
#include <ephysics/constraint/FixedJoint.hpp>
#include <ephysics/engine/ConstraintSolver.hpp>

View File

@ -38,7 +38,7 @@ namespace ephysics {
* between two bodies.
*/
class FixedJoint : public Joint {
private :
private:
static const float BETA; //!< Beta value for the bias factor of position correction
vec3 m_localAnchorPointBody1; //!< Anchor point of body 1 (in local-space coordinates of body 1)
vec3 m_localAnchorPointBody2; //!< Anchor point of body 2 (in local-space coordinates of body 2)
@ -54,24 +54,20 @@ namespace ephysics {
vec3 m_biasRotation; //!< Bias vector for the 3 rotation constraints
etk::Quaternion m_initOrientationDifferenceInv; //!< Inverse of the initial orientation difference between the two bodies
/// Private copy-constructor
FixedJoint(const FixedJoint& constraint);
FixedJoint(const FixedJoint& _constraint) = delete;
/// Private assignment operator
FixedJoint& operator=(const FixedJoint& constraint);
/// Return the number of bytes used by the joint
virtual size_t getSizeInBytes() const override {
FixedJoint& operator=(const FixedJoint& _constraint) = delete;
size_t getSizeInBytes() const override {
return sizeof(FixedJoint);
}
/// Initialize before solving the constraint
virtual void initBeforeSolve(const ConstraintSolverData& constraintSolverData);
/// Warm start the constraint (apply the previous impulse at the beginning of the step)
virtual void warmstart(const ConstraintSolverData& constraintSolverData);
/// Solve the velocity constraint
virtual void solveVelocityConstraint(const ConstraintSolverData& constraintSolverData);
/// Solve the position constraint (for position error correction)
virtual void solvePositionConstraint(const ConstraintSolverData& constraintSolverData);
public :
void initBeforeSolve(const ConstraintSolverData& _constraintSolverData) override;
void warmstart(const ConstraintSolverData& _constraintSolverData) override;
void solveVelocityConstraint(const ConstraintSolverData& _constraintSolverData) override;
void solvePositionConstraint(const ConstraintSolverData& _constraintSolverData) override;
public:
/// Constructor
FixedJoint(const FixedJointInfo& jointInfo);
FixedJoint(const FixedJointInfo& _jointInfo);
/// Destructor
virtual ~FixedJoint();
};

View File

@ -160,18 +160,12 @@ namespace ephysics {
float _lowerLimitAngle,
float _upperLimitAngle) const;
/// Compute the current angle around the hinge axis
float computeCurrentHingeAngle(const etk::Quaternion& _orientationBody1,
const etk::Quaternion& _orientationBody2);
/// Return the number of bytes used by the joint
virtual size_t getSizeInBytes() const;
/// Initialize before solving the constraint
virtual void initBeforeSolve(const ConstraintSolverData& _constraintSolverData);
/// Warm start the constraint (apply the previous impulse at the beginning of the step)
virtual void warmstart(const ConstraintSolverData& _constraintSolverData);
/// Solve the velocity constraint
virtual void solveVelocityConstraint(const ConstraintSolverData& _constraintSolverData);
/// Solve the position constraint (for position error correction)
virtual void solvePositionConstraint(const ConstraintSolverData& _constraintSolverData);
float computeCurrentHingeAngle(const etk::Quaternion& _orientationBody1, const etk::Quaternion& _orientationBody2);
size_t getSizeInBytes() const override;
void initBeforeSolve(const ConstraintSolverData& _constraintSolverData) override;
void warmstart(const ConstraintSolverData& _constraintSolverData) override;
void solveVelocityConstraint(const ConstraintSolverData& _constraintSolverData) override;
void solvePositionConstraint(const ConstraintSolverData& _constraintSolverData) override;
public :
/// Constructor
HingeJoint(const HingeJointInfo& _jointInfo);

View File

@ -3,24 +3,19 @@
* @copyright 2010-2016 Daniel Chappuis
* @license BSD 3 clauses (see license file)
*/
#pragma once
// Libraries
#include <ephysics/constraint/Joint.hpp>
using namespace ephysics;
// Constructor
Joint::Joint(const JointInfo& jointInfo)
:m_body1(jointInfo.body1), m_body2(jointInfo.body2), m_type(jointInfo.type),
m_positionCorrectionTechnique(jointInfo.positionCorrectionTechnique),
m_isCollisionEnabled(jointInfo.isCollisionEnabled), m_isAlreadyInIsland(false) {
assert(m_body1 != NULL);
assert(m_body2 != NULL);
assert(m_body1 != nullptr);
assert(m_body2 != nullptr);
}
// Destructor
Joint::~Joint() {
}

View File

@ -156,16 +156,11 @@ namespace ephysics {
SliderJoint& operator=(const SliderJoint& _constraint);
/// Reset the limits
void resetLimits();
/// Return the number of bytes used by the joint
virtual size_t getSizeInBytes() const;
/// Initialize before solving the constraint
virtual void initBeforeSolve(const ConstraintSolverData& _constraintSolverData);
/// Warm start the constraint (apply the previous impulse at the beginning of the step)
virtual void warmstart(const ConstraintSolverData& _constraintSolverData);
/// Solve the velocity constraint
virtual void solveVelocityConstraint(const ConstraintSolverData& _constraintSolverData);
/// Solve the position constraint (for position error correction)
virtual void solvePositionConstraint(const ConstraintSolverData& _constraintSolverData);
size_t getSizeInBytes() const override;
void initBeforeSolve(const ConstraintSolverData& _constraintSolverData) override;
void warmstart(const ConstraintSolverData& _constraintSolverData) override;
void solveVelocityConstraint(const ConstraintSolverData& _constraintSolverData) override;
void solvePositionConstraint(const ConstraintSolverData& _constraintSolverData) override;
public :
/// Constructor
SliderJoint(const SliderJointInfo& _jointInfo);

View File

@ -142,24 +142,18 @@ namespace ephysics {
void setTimeBeforeSleep(float timeBeforeSleep);
/// Set an event listener object to receive events callbacks.
void setEventListener(EventListener* eventListener);
/// Test and report collisions between a given shape and all the others
/// shapes of the world
virtual void testCollision(const ProxyShape* shape,
CollisionCallback* callback);
/// Test and report collisions between two given shapes
virtual void testCollision(const ProxyShape* shape1,
const ProxyShape* shape2,
CollisionCallback* callback);
/// Test and report collisions between a body and all
/// the others bodies of the world
virtual void testCollision(const CollisionBody* body,
CollisionCallback* callback);
/// Test and report collisions between two bodies
virtual void testCollision(const CollisionBody* body1,
const CollisionBody* body2,
CollisionCallback* callback);
void testCollision(const ProxyShape* _shape,
CollisionCallback* _callback) override;
virtual void testCollision(const ProxyShape* _shape1,
const ProxyShape* _shape2,
CollisionCallback* _callback) override;
virtual void testCollision(const CollisionBody* _body,
CollisionCallback* _callback) override;
virtual void testCollision(const CollisionBody* _body1,
const CollisionBody* _body2,
CollisionCallback* _callback) override;
/// Test and report collisions between all shapes of the world
virtual void testCollision(CollisionCallback* callback);
virtual void testCollision(CollisionCallback* _callback) override;
/// Return the list of all contacts of the world
std::vector<const ContactManifold*> getContactsList() const;
friend class RigidBody;

View File

@ -16,3 +16,73 @@ OverlappingPair::OverlappingPair(ProxyShape* shape1, ProxyShape* shape2, int32_t
m_cachedSeparatingAxis(1.0, 1.0, 1.0) {
}
// Return the pointer to first body
ProxyShape* OverlappingPair::getShape1() const {
return m_contactManifoldSet.getShape1();
}
// Return the pointer to second body
ProxyShape* OverlappingPair::getShape2() const {
return m_contactManifoldSet.getShape2();
}
// Add a contact to the contact manifold
void OverlappingPair::addContact(ContactPoint* contact) {
m_contactManifoldSet.addContactPoint(contact);
}
// Update the contact manifold
void OverlappingPair::update() {
m_contactManifoldSet.update();
}
// Return the cached separating axis
vec3 OverlappingPair::getCachedSeparatingAxis() const {
return m_cachedSeparatingAxis;
}
// Set the cached separating axis
void OverlappingPair::setCachedSeparatingAxis(const vec3& _axis) {
m_cachedSeparatingAxis = _axis;
}
// Return the number of contact points in the contact manifold
uint32_t OverlappingPair::getNbContactPoints() const {
return m_contactManifoldSet.getTotalNbContactPoints();
}
// Return the contact manifold
const ContactManifoldSet& OverlappingPair::getContactManifoldSet() {
return m_contactManifoldSet;
}
// Return the pair of bodies index
overlappingpairid OverlappingPair::computeID(ProxyShape* _shape1, ProxyShape* _shape2) {
assert( _shape1->m_broadPhaseID >= 0
&& _shape2->m_broadPhaseID >= 0);
// Construct the pair of body index
overlappingpairid pairID = _shape1->m_broadPhaseID < _shape2->m_broadPhaseID ?
std::make_pair(_shape1->m_broadPhaseID, _shape2->m_broadPhaseID) :
std::make_pair(_shape2->m_broadPhaseID, _shape1->m_broadPhaseID);
assert(pairID.first != pairID.second);
return pairID;
}
// Return the pair of bodies index
bodyindexpair OverlappingPair::computeBodiesIndexPair(CollisionBody* _body1,
CollisionBody* _body2) {
// Construct the pair of body index
bodyindexpair indexPair = _body1->getID() < _body2->getID() ?
std::make_pair(_body1->getID(), _body2->getID()) :
std::make_pair(_body2->getID(), _body1->getID());
assert(indexPair.first != indexPair.second);
return indexPair;
}
// Clear the contact points of the contact manifold
void OverlappingPair::clearContactPoints() {
m_contactManifoldSet.clear();
}

View File

@ -159,8 +159,8 @@ def configure(target, my_module):
'ememory'
])
# TODO: Remove this ...
my_module.add_flag('c++', "-Wno-overloaded-virtual", export=True)
my_module.add_path(".")
#my_module.add_flag('c++', "-Wno-overloaded-virtual", export=True)
#my_module.add_path(".")
return True