Physics2D tests (#129)

* Quaternion: Fix singularity on Z axis when converting to euler angles

* CollisionComponent2D: Add method to retrieve AABB

* Collider2D: Fix constructor for Box with Vector2

* Physics2D: Fix rotation (Chipmunk works with radian and Nazara degrees) and copy constructor of RigidBody2D

* Colider2D: Add New for convex and tests for the new classes
This commit is contained in:
Gawaboumga 2017-08-20 21:47:23 +02:00 committed by Jérôme Leclercq
parent 9806231b5c
commit 41a1b5d493
12 changed files with 860 additions and 37 deletions

View File

@ -29,6 +29,7 @@ namespace Ndk
CollisionComponent2D(const CollisionComponent2D& collision); CollisionComponent2D(const CollisionComponent2D& collision);
~CollisionComponent2D() = default; ~CollisionComponent2D() = default;
Nz::Rectf GetAABB() const;
const Nz::Collider2DRef& GetGeom() const; const Nz::Collider2DRef& GetGeom() const;
void SetGeom(Nz::Collider2DRef geom); void SetGeom(Nz::Collider2DRef geom);

View File

@ -34,6 +34,16 @@ namespace Ndk
{ {
} }
/*!
* \brief Gets the collision box representing the entity
* \return The physics collision box
*/
inline Nz::Rectf CollisionComponent2D::GetAABB() const
{
return m_staticBody->GetAABB();
}
/*! /*!
* \brief Gets the geometry representing the entity * \brief Gets the geometry representing the entity
* \return A constant reference to the physics geometry * \return A constant reference to the physics geometry

View File

@ -481,11 +481,11 @@ namespace Nz
T test = x * y + z * w; T test = x * y + z * w;
if (test > F(0.499)) if (test > F(0.499))
// singularity at north pole // singularity at north pole
return EulerAngles<T>(FromDegrees(F(90.0)), FromRadians(F(2.0) * std::atan2(x, w)), F(0.0)); return EulerAngles<T>(F(0.0), FromRadians(F(2.0) * std::atan2(x, w)), FromDegrees(F(90.0)));
if (test < F(-0.499)) if (test < F(-0.499))
// singularity at south pole // singularity at south pole
return EulerAngles<T>(FromDegrees(F(-90.0)), FromRadians(F(-2.0) * std::atan2(x, w)), F(0.0)); return EulerAngles<T>(F(0.0), FromRadians(F(-2.0) * std::atan2(x, w)), FromDegrees(F(-90.0)));
return EulerAngles<T>(FromRadians(std::atan2(F(2.0) * x * w - F(2.0) * y * z, F(1.0) - F(2.0) * x * x - F(2.0) * z * z)), return EulerAngles<T>(FromRadians(std::atan2(F(2.0) * x * w - F(2.0) * y * z, F(1.0) - F(2.0) * x * x - F(2.0) * z * z)),
FromRadians(std::atan2(F(2.0) * y * w - F(2.0) * x * z, F(1.0) - F(2.0) * y * y - F(2.0) * z * z)), FromRadians(std::atan2(F(2.0) * y * w - F(2.0) * x * z, F(1.0) - F(2.0) * y * y - F(2.0) * z * z)),

View File

@ -114,6 +114,15 @@ namespace Nz
return object.release(); return object.release();
} }
template<typename... Args>
ConvexCollider2DRef ConvexCollider2D::New(Args&&... args)
{
std::unique_ptr<ConvexCollider2D> object(new ConvexCollider2D(std::forward<Args>(args)...));
object->SetPersistent(false);
return object.release();
}
template<typename... Args> template<typename... Args>
NullCollider2DRef NullCollider2D::New(Args&&... args) NullCollider2DRef NullCollider2D::New(Args&&... args)
{ {

View File

@ -31,7 +31,7 @@ namespace Nz
/******************************** BoxCollider2D *********************************/ /******************************** BoxCollider2D *********************************/
BoxCollider2D::BoxCollider2D(const Vector2f& size, float radius) : BoxCollider2D::BoxCollider2D(const Vector2f& size, float radius) :
BoxCollider2D(Rectf(-size.x / 2.f, -size.y / 2.f, size.x / 2.f, size.y / 2.f), radius) BoxCollider2D(Rectf(-size.x / 2.f, -size.y / 2.f, size.x, size.y), radius)
{ {
} }

View File

@ -45,8 +45,28 @@ namespace Nz
Create(); Create();
cpBodySetMass(m_handle, cpBodyGetMass(object.GetHandle()));
cpBodySetMoment(m_handle, cpBodyGetMoment(object.GetHandle()));
SetGeom(object.GetGeom()); SetGeom(object.GetGeom());
SetMass(object.GetMass()); SetMass(object.GetMass());
cpBodySetForce(m_handle, cpBodyGetForce(object.GetHandle()));
cpBodySetTorque(m_handle, cpBodyGetTorque(object.GetHandle()));
cpBodySetAngle(m_handle, cpBodyGetAngle(object.GetHandle()));
cpBodySetAngularVelocity(m_handle, cpBodyGetAngularVelocity(object.GetHandle()));
cpBodySetCenterOfGravity(m_handle, cpBodyGetCenterOfGravity(object.GetHandle()));
cpBodySetPosition(m_handle, cpBodyGetPosition(object.GetHandle()));
cpBodySetVelocity(m_handle, cpBodyGetVelocity(object.GetHandle()));
for (int i = 0; i != m_shapes.size(); ++i)
m_shapes[i]->bb = cpShapeCacheBB(object.m_shapes[i]);
cpBodySetMass(m_handle, cpBodyGetMass(object.GetHandle()));
cpBodySetMoment(m_handle, cpBodyGetMoment(object.GetHandle()));
m_handle->m = object.GetHandle()->m;
} }
RigidBody2D::RigidBody2D(RigidBody2D&& object) : RigidBody2D::RigidBody2D(RigidBody2D&& object) :
@ -93,7 +113,7 @@ namespace Nz
cpBodyApplyForceAtLocalPoint(m_handle, cpv(force.x, force.y), cpv(point.x, point.y)); cpBodyApplyForceAtLocalPoint(m_handle, cpv(force.x, force.y), cpv(point.x, point.y));
break; break;
} }
} }
void RigidBody2D::AddImpulse(const Vector2f& impulse, CoordSys coordSys) void RigidBody2D::AddImpulse(const Vector2f& impulse, CoordSys coordSys)
{ {
@ -116,7 +136,7 @@ namespace Nz
void RigidBody2D::AddTorque(float torque) void RigidBody2D::AddTorque(float torque)
{ {
cpBodySetTorque(m_handle, cpBodyGetTorque(m_handle) + torque); cpBodySetTorque(m_handle, cpBodyGetTorque(m_handle) + ToRadians(torque));
} }
Rectf RigidBody2D::GetAABB() const Rectf RigidBody2D::GetAABB() const
@ -134,7 +154,7 @@ namespace Nz
float RigidBody2D::GetAngularVelocity() const float RigidBody2D::GetAngularVelocity() const
{ {
return static_cast<float>(cpBodyGetAngularVelocity(m_handle)); return FromRadians(static_cast<float>(cpBodyGetAngularVelocity(m_handle)));
} }
const Collider2DRef& RigidBody2D::GetGeom() const const Collider2DRef& RigidBody2D::GetGeom() const
@ -177,7 +197,7 @@ namespace Nz
float RigidBody2D::GetRotation() const float RigidBody2D::GetRotation() const
{ {
return static_cast<float>(cpBodyGetAngle(m_handle)); return FromRadians(static_cast<float>(cpBodyGetAngle(m_handle)));
} }
void* RigidBody2D::GetUserdata() const void* RigidBody2D::GetUserdata() const
@ -208,7 +228,7 @@ namespace Nz
void RigidBody2D::SetAngularVelocity(float angularVelocity) void RigidBody2D::SetAngularVelocity(float angularVelocity)
{ {
cpBodySetAngularVelocity(m_handle, angularVelocity); cpBodySetAngularVelocity(m_handle, ToRadians(angularVelocity));
} }
void RigidBody2D::SetGeom(Collider2DRef geom) void RigidBody2D::SetGeom(Collider2DRef geom)
@ -217,18 +237,11 @@ namespace Nz
// So let's save some attributes of the body, destroy it and rebuild it // So let's save some attributes of the body, destroy it and rebuild it
if (m_geom) if (m_geom)
{ {
cpVect pos = cpBodyGetPosition(m_handle);
cpFloat mass = cpBodyGetMass(m_handle); cpFloat mass = cpBodyGetMass(m_handle);
cpFloat moment = cpBodyGetMoment(m_handle); cpFloat moment = cpBodyGetMoment(m_handle);
cpFloat rot = cpBodyGetAngle(m_handle);
cpVect vel = cpBodyGetVelocity(m_handle);
Destroy(); Destroy();
Create(float(mass), float(moment)); Create(static_cast<float>(mass), static_cast<float>(moment));
cpBodySetAngle(m_handle, rot);
cpBodySetPosition(m_handle, pos);
cpBodySetVelocity(m_handle, vel);
} }
if (geom) if (geom)
@ -302,7 +315,7 @@ namespace Nz
void RigidBody2D::SetRotation(float rotation) void RigidBody2D::SetRotation(float rotation)
{ {
cpBodySetAngle(m_handle, rotation); cpBodySetAngle(m_handle, ToRadians(rotation));
} }
void RigidBody2D::SetUserdata(void* ud) void RigidBody2D::SetUserdata(void* ud)
@ -369,5 +382,6 @@ namespace Nz
cpSpaceRemoveBody(space, m_handle); cpSpaceRemoveBody(space, m_handle);
cpBodyFree(m_handle); cpBodyFree(m_handle);
} }
m_shapes.clear();
} }
} }

View File

@ -173,15 +173,52 @@ SCENARIO("Quaternion", "[MATH][QUATERNION]")
WHEN("We get the rotation between two vectors") WHEN("We get the rotation between two vectors")
{ {
/*TODO Nz::Quaternionf rotationBetweenXY = Nz::Quaternionf::RotationBetween(Nz::Vector3f::UnitX(), Nz::Vector3f::UnitY());
* Nz::Quaternionf rotationBetweenXY = Nz::Quaternionf::RotationBetween(Nz::Vector3f::UnitX(), Nz::Vector3f::UnitY());
THEN("The rotation in left-handed is 270 degree on z") THEN("The rotation in right-handed is 90 degree on z")
{ {
Nz::Quaternionf rotation270Z(Nz::FromDegrees(270.f), Nz::Vector3f::UnitZ());
Nz::Quaternionf rotation90Z(Nz::FromDegrees(90.f), Nz::Vector3f::UnitZ()); Nz::Quaternionf rotation90Z(Nz::FromDegrees(90.f), Nz::Vector3f::UnitZ());
REQUIRE(rotation90Z == rotationBetweenXY); REQUIRE(rotation90Z == rotationBetweenXY);
}*/ }
}
}
GIVEN("Different angles")
{
Nz::Quaternionf rotation90X(0.707f, 0.707f, 0.f, 0.f);
Nz::Quaternionf rotation90Y(0.707f, 0.f, 0.707f, 0.f);
Nz::Quaternionf rotation90Z(0.707f, 0.f, 0.f, 0.707f);
Nz::Quaternionf rotation180X(0.f, 1.f, 0.f, 0.f);
Nz::Quaternionf rotation180Y(0.f, 0.f, 1.f, 0.f);
Nz::Quaternionf rotation180Z(0.f, 0.f, 0.f, 1.f);
Nz::Quaternionf rotation270X(-0.707f, 0.707f, 0.f, 0.f);
Nz::Quaternionf rotation270Y(-0.707f, 0.f, 0.707f, 0.f);
Nz::Quaternionf rotation270Z(-0.707f, 0.f, 0.f, 0.707f);
Nz::Quaternionf special(0.707f, 0.006f, 0.006f, 0.707f);
WHEN("We convert them to euler angles")
{
THEN("Those are equal to")
{
CHECK(Nz::NumberEquals(rotation90X.ToEulerAngles().pitch, Nz::FromDegrees(90.f), 0.1f));
CHECK(Nz::NumberEquals(rotation90Y.ToEulerAngles().yaw, Nz::FromDegrees(90.f), 0.1f));
CHECK(Nz::NumberEquals(rotation90Z.ToEulerAngles().roll, Nz::FromDegrees(90.f), 0.1f));
CHECK(rotation180X == Nz::EulerAnglesf(180.f, 0.f, 0.f));
CHECK(rotation180Y == Nz::EulerAnglesf(0.f, 180.f, 0.f));
CHECK(rotation180Z == Nz::EulerAnglesf(0.f, 0.f, 180.f));
CHECK(Nz::NumberEquals(rotation270X.ToEulerAngles().pitch, Nz::FromDegrees(-90.f), 0.1f));
CHECK(Nz::NumberEquals(rotation270Y.ToEulerAngles().yaw, Nz::FromDegrees(-90.f), 0.1f));
CHECK(Nz::NumberEquals(rotation270Z.ToEulerAngles().roll, Nz::FromDegrees(-90.f), 0.1f));
CHECK(Nz::NumberEquals(special.ToEulerAngles().pitch, Nz::FromDegrees(0.f), 0.1f));
CHECK(Nz::NumberEquals(special.ToEulerAngles().yaw, Nz::FromDegrees(1.f), 0.1f));
CHECK(Nz::NumberEquals(special.ToEulerAngles().roll, Nz::FromDegrees(90.f), 0.1f));
}
} }
} }
} }

View File

@ -0,0 +1,133 @@
#include <Nazara/Physics2D/Collider2D.hpp>
#include <Catch/catch.hpp>
SCENARIO("Collider2D", "[PHYSICS2D][COLLIDER2D]")
{
GIVEN("No particular elements")
{
WHEN("We construct a box with Rect")
{
Nz::Rectf aabb(5.f, 3.f, 10.f, 6.f);
Nz::BoxCollider2D box(aabb);
THEN("We expect those to be true")
{
CHECK(box.GetRect() == aabb);
CHECK(box.GetSize() == aabb.GetLengths());
CHECK(box.GetType() == Nz::ColliderType2D_Box);
}
}
WHEN("We construct a box with Vector2D")
{
Nz::Vector2f vec(5.f, 3.f);
Nz::Rectf aabb(-2.5f, -1.5f, 5.f, 3.f);
Nz::BoxCollider2D box(vec);
THEN("We expect those to be true")
{
CHECK(box.GetRect() == aabb);
CHECK(box.GetSize() == vec);
CHECK(box.GetType() == Nz::ColliderType2D_Box);
}
}
WHEN("We construct a circle")
{
Nz::Vector2f position(5.f, 3.f);
float radius = 7.f;
Nz::CircleCollider2D circle(radius, position);
THEN("We expect those to be true")
{
CHECK(circle.GetRadius() == Approx(radius));
CHECK(circle.GetType() == Nz::ColliderType2D_Circle);
}
}
WHEN("We construct a compound")
{
Nz::Rectf aabb(0.f, 0.f, 1.f, 1.f);
Nz::BoxCollider2DRef box1 = Nz::BoxCollider2D::New(aabb);
aabb.Translate(Nz::Vector2f::Unit());
Nz::BoxCollider2DRef box2 = Nz::BoxCollider2D::New(aabb);
std::vector<Nz::Collider2DRef> colliders;
colliders.push_back(box1);
colliders.push_back(box2);
Nz::CompoundCollider2D compound(colliders);
THEN("We expect those to be true")
{
CHECK(compound.GetType() == Nz::ColliderType2D_Compound);
}
}
WHEN("We construct a convex")
{
std::vector<Nz::Vector2f> vertices;
vertices.push_back(Nz::Vector2f(0.f, 0.f));
vertices.push_back(Nz::Vector2f(0.f, 1.f));
vertices.push_back(Nz::Vector2f(1.f, 1.f));
vertices.push_back(Nz::Vector2f(1.f, 0.f));
Nz::ConvexCollider2D convex(Nz::SparsePtr<const Nz::Vector2f>(vertices.data()), vertices.size());
THEN("We expect those to be true")
{
CHECK(convex.GetType() == Nz::ColliderType2D_Convex);
}
}
WHEN("We construct a null")
{
Nz::NullCollider2D null;
THEN("We expect those to be true")
{
CHECK(null.GetType() == Nz::ColliderType2D_Null);
}
}
WHEN("We construct a segment")
{
Nz::Vector2f firstPoint(2.f, 1.f);
Nz::Vector2f secondPoint(-4.f, -3.f);
Nz::SegmentCollider2D segment(firstPoint, secondPoint);
THEN("We expect those to be true")
{
CHECK(segment.GetFirstPoint() == firstPoint);
CHECK(segment.GetLength() == firstPoint.Distance(secondPoint));
CHECK(segment.GetSecondPoint() == secondPoint);
CHECK(segment.GetType() == Nz::ColliderType2D_Segment);
}
}
WHEN("We verify general purpose methods")
{
Nz::Rectf aabb(5.f, 3.f, 10.f, 6.f);
Nz::BoxCollider2D box(aabb);
Nz::UInt32 categoryMask = 1;
Nz::UInt32 groupId = 2;
Nz::UInt32 typeId = 3;
Nz::UInt32 mask = 4;
bool trigger = true;
box.SetCategoryMask(categoryMask);
box.SetCollisionGroup(groupId);
box.SetCollisionId(typeId);
box.SetCollisionMask(mask);
box.SetTrigger(trigger);
THEN("We expect those to be true")
{
CHECK(box.GetCategoryMask() == categoryMask);
CHECK(box.GetCollisionGroup() == groupId);
CHECK(box.GetCollisionId() == typeId);
CHECK(box.GetCollisionMask() == mask);
CHECK(box.IsTrigger() == trigger);
}
}
}
}

View File

@ -0,0 +1,114 @@
#include <Nazara/Physics2D/PhysWorld2D.hpp>
#include <Catch/catch.hpp>
Nz::RigidBody2D CreateBody(Nz::PhysWorld2D& world, const Nz::Vector2f& position, bool isMoving = true, const Nz::Vector2f& lengths = Nz::Vector2f::Unit());
Nz::UInt32 collisionGroup = 1;
Nz::UInt32 categoryMask = 2;
Nz::UInt32 collisionMask = 3;
SCENARIO("PhysWorld2D", "[PHYSICS2D][PHYSWORLD2D]")
{
GIVEN("A physic world and a bunch of entities on a grid")
{
Nz::PhysWorld2D world;
std::vector<Nz::RigidBody2D> bodies;
const int numberOfBodiesPerLign = 3;
for (int i = 0; i != numberOfBodiesPerLign; ++i)
{
for (int j = 0; j != numberOfBodiesPerLign; ++j)
{
bodies.push_back(CreateBody(world, Nz::Vector2f(10.f * i, 10.f * j)));
}
}
world.Step(1.f);
WHEN("We ask for the nearest body")
{
Nz::PhysWorld2D::NearestQueryResult result;
REQUIRE(world.NearestBodyQuery(-Nz::Vector2f::UnitY() * 1.f, 2.f, collisionGroup, categoryMask, collisionMask, &result));
THEN("It should be the one on the origin")
{
CHECK(result.nearestBody == &bodies[0]);
CHECK(result.closestPoint == Nz::Vector2f::Zero());
CHECK(result.fraction == -Nz::Vector2f::UnitY());
CHECK(result.distance == Approx(1.f));
}
REQUIRE(world.NearestBodyQuery(Nz::Vector2f::UnitY() * 2.f, 2.f, collisionGroup, categoryMask, collisionMask, &result));
THEN("It should be the one on the origin")
{
CHECK(result.nearestBody == &bodies[0]);
CHECK(result.closestPoint == Nz::Vector2f::UnitY());
CHECK(result.fraction == Nz::Vector2f::UnitY());
CHECK(result.distance == Approx(1.f));
}
}
WHEN("We ask for the first ray collision")
{
Nz::Vector2f origin = -Nz::Vector2f::UnitY() * 2.f;
Nz::Vector2f end = (numberOfBodiesPerLign + 1) * 10.f * Nz::Vector2f::UnitY();
Nz::PhysWorld2D::RaycastHit result;
REQUIRE(world.RaycastQueryFirst(origin, end, 1.f, collisionGroup, categoryMask, collisionMask, &result));
THEN("It should be the one on the origin")
{
CHECK(result.nearestBody == &bodies[0]);
CHECK(result.fraction == Approx(1.f / 42.f));
CHECK(result.hitPos == Nz::Vector2f::Zero());
CHECK(result.hitNormal == -Nz::Vector2f::UnitY());
}
}
WHEN("We ask for the ray collisions")
{
Nz::Vector2f origin = -Nz::Vector2f::UnitY() * 2.f;
Nz::Vector2f end = (numberOfBodiesPerLign + 1) * 10.f * Nz::Vector2f::UnitY();
std::vector<Nz::PhysWorld2D::RaycastHit> results;
REQUIRE(world.RaycastQuery(origin, end, 1.f, collisionGroup, categoryMask, collisionMask, &results));
THEN("It should be the first lign")
{
REQUIRE(results.size() == numberOfBodiesPerLign);
for (int i = 0; i != numberOfBodiesPerLign; ++i)
{
const Nz::PhysWorld2D::RaycastHit& result = results[i];
CHECK(result.nearestBody == &bodies[i]);
CHECK(result.fraction == Approx(i / 4.f).epsilon(0.1f));
CHECK(result.hitPos == Nz::Vector2f(0.f, i * 10.f));
CHECK(result.hitNormal == -Nz::Vector2f::UnitY());
}
}
}
WHEN("We ask for a region")
{
std::vector<Nz::RigidBody2D*> results;
world.RegionQuery(Nz::Rectf(-5.f, -5.f, 5.f, 5.f), collisionGroup, categoryMask, collisionMask, &results);
THEN("It should be the one on the origin")
{
REQUIRE(results.size() == 1);
CHECK(results[0] == &bodies[0]);
}
}
}
}
Nz::RigidBody2D CreateBody(Nz::PhysWorld2D& world, const Nz::Vector2f& position, bool isMoving, const Nz::Vector2f& lengths)
{
Nz::Rectf aabb(0.f, 0.f, lengths.x, lengths.y);
Nz::Collider2DRef box = Nz::BoxCollider2D::New(aabb);
box->SetCategoryMask(categoryMask);
box->SetCollisionMask(collisionMask);
float mass = isMoving ? 1.f : 0.f;
Nz::RigidBody2D rigidBody(&world, mass, box);
rigidBody.SetPosition(position);
return rigidBody;
}

View File

@ -0,0 +1,318 @@
#include <Nazara/Physics2D/RigidBody2D.hpp>
#include <Nazara/Physics2D/PhysWorld2D.hpp>
#include <Catch/catch.hpp>
Nz::RigidBody2D CreateBody(Nz::PhysWorld2D& world);
void EQUALITY(const Nz::RigidBody2D& left, const Nz::RigidBody2D& right);
SCENARIO("RigidBody2D", "[PHYSICS2D][RIGIDBODY2D]")
{
GIVEN("A physic world and a rigid body")
{
Nz::PhysWorld2D world;
Nz::Vector2f positionAABB(3.f, 4.f);
Nz::Rectf aabb(positionAABB.x, positionAABB.y, 1.f, 2.f);
Nz::Collider2DRef box = Nz::BoxCollider2D::New(aabb);
float mass = 1.f;
Nz::RigidBody2D body(&world, mass, box);
float angularVelocity = 0.2f;
body.SetAngularVelocity(angularVelocity);
Nz::Vector2f massCenter(5.f, 7.f);
body.SetMassCenter(massCenter);
Nz::Vector2f position(9.f, 1.f);
body.SetPosition(position);
float rotation = 0.1f;
body.SetRotation(rotation);
Nz::Vector2f velocity(-4.f, -2.f);
body.SetVelocity(velocity);
bool userdata = false;
body.SetUserdata(&userdata);
world.Step(1.f);
WHEN("We copy construct the body")
{
body.AddForce(Nz::Vector2f(3.f, 5.f));
Nz::RigidBody2D copiedBody(body);
EQUALITY(copiedBody, body);
world.Step(1.f);
EQUALITY(copiedBody, body);
}
WHEN("We move construct the body")
{
Nz::RigidBody2D copiedBody(body);
Nz::RigidBody2D movedBody(std::move(body));
EQUALITY(movedBody, copiedBody);
}
WHEN("We copy assign the body")
{
Nz::RigidBody2D copiedBody(&world, 0.f);
copiedBody = body;
EQUALITY(copiedBody, body);
}
WHEN("We move assign the body")
{
Nz::RigidBody2D copiedBody(body);
Nz::RigidBody2D movedBody(&world, 0.f);
movedBody = std::move(body);
EQUALITY(movedBody, copiedBody);
}
WHEN("We set a new geometry")
{
float radius = 5.f;
Nz::Vector2f positionCircle(0.f, 0.f);
Nz::Collider2DRef circle = Nz::CircleCollider2D::New(radius, position);
body.SetGeom(circle);
world.Step(1.f);
THEN("The aabb should be updated")
{
Nz::Rectf circleAABB(position.x - radius, position.y - radius, 2.f * radius, 2.f* radius);
REQUIRE(body.GetAABB() == circleAABB);
}
}
}
GIVEN("A physic world")
{
Nz::PhysWorld2D world;
Nz::Rectf aabb(3.f, 4.f, 1.f, 2.f);
WHEN("We get a rigid body from a function")
{
std::vector<Nz::RigidBody2D> tmp;
tmp.push_back(CreateBody(world));
tmp.push_back(CreateBody(world));
world.Step(1.f);
THEN("They should be valid")
{
CHECK(tmp[0].GetAABB() == aabb);
CHECK(tmp[1].GetAABB() == aabb);
}
}
}
GIVEN("A physic world and a rigid body")
{
Nz::PhysWorld2D world;
Nz::Vector2f positionAABB(3.f, 4.f);
Nz::Rectf aabb(positionAABB.x, positionAABB.y, 1.f, 2.f);
Nz::Collider2DRef box = Nz::BoxCollider2D::New(aabb);
float mass = 1.f;
Nz::RigidBody2D body(&world, mass, box);
bool userData = false;
body.SetUserdata(&userData);
Nz::Vector2f position = Nz::Vector2f::Zero();
world.Step(1.f);
WHEN("We retrieve standard information")
{
THEN("We expect those to be true")
{
CHECK(body.GetAABB() == aabb);
CHECK(body.GetAngularVelocity() == Approx(0.f));
CHECK(body.GetCenterOfGravity() == Nz::Vector2f::Zero());
CHECK(body.GetGeom() == box);
CHECK(body.GetMass() == Approx(mass));
CHECK(body.GetPosition() == position);
CHECK(body.GetRotation() == Approx(0.f));
CHECK(body.GetUserdata() == &userData);
CHECK(body.GetVelocity() == Nz::Vector2f::Zero());
CHECK(body.IsMoveable() == true);
CHECK(body.IsSleeping() == false);
}
}
WHEN("We set a velocity")
{
Nz::Vector2f velocity(Nz::Vector2f::Unit());
body.SetVelocity(velocity);
position += velocity;
world.Step(1.f);
THEN("We expect those to be true")
{
aabb.Translate(velocity);
CHECK(body.GetAABB() == aabb);
CHECK(body.GetCenterOfGravity() == Nz::Vector2f::Zero());
CHECK(body.GetPosition() == position);
CHECK(body.GetVelocity() == velocity);
}
AND_THEN("We apply an impulse in the opposite direction")
{
body.AddImpulse(-velocity);
world.Step(1.f);
REQUIRE(body.GetVelocity() == Nz::Vector2f::Zero());
}
}
WHEN("We set an angular velocity")
{
float angularSpeed = Nz::FromDegrees(90.f);
body.SetAngularVelocity(angularSpeed);
world.Step(1.f);
THEN("We expect those to be true")
{
CHECK(body.GetAngularVelocity() == Approx(angularSpeed));
CHECK(body.GetRotation() == Approx(angularSpeed));
CHECK(body.GetAABB() == Nz::Rectf(-6.f, 3.f, 2.f, 1.f));
world.Step(1.f);
CHECK(body.GetRotation() == Approx(2.f * angularSpeed));
CHECK(body.GetAABB() == Nz::Rectf(-4.f, -6.f, 1.f, 2.f));
world.Step(1.f);
CHECK(body.GetRotation() == Approx(3.f * angularSpeed));
CHECK(body.GetAABB() == Nz::Rectf(4.f, -4.f, 2.f, 1.f));
world.Step(1.f);
CHECK(body.GetRotation() == Approx(4.f * angularSpeed));
}
}
WHEN("We apply a torque")
{
float angularSpeed = Nz::DegreeToRadian(90.f);
body.AddTorque(angularSpeed);
world.Step(1.f);
THEN("It is also counter-clockwise")
{
CHECK(body.GetAngularVelocity() >= 0.f);
CHECK(body.GetRotation() >= 0.f);
}
}
}
GIVEN("A physic world and a rigid body of circle")
{
Nz::PhysWorld2D world;
Nz::Vector2f position(3.f, 4.f);
float radius = 5.f;
Nz::Collider2DRef circle = Nz::CircleCollider2D::New(radius, position);
float mass = 1.f;
Nz::RigidBody2D body(&world, mass, circle);
world.Step(1.f);
WHEN("We ask for the aabb of the circle")
{
THEN("We expect this to be true")
{
Nz::Rectf circleAABB(position.x - radius, position.y - radius, 2.f * radius, 2.f* radius);
REQUIRE(body.GetAABB() == circleAABB);
}
}
}
GIVEN("A physic world and a rigid body of compound")
{
Nz::PhysWorld2D world;
Nz::Rectf aabb(0.f, 0.f, 1.f, 1.f);
Nz::BoxCollider2DRef box1 = Nz::BoxCollider2D::New(aabb);
aabb.Translate(Nz::Vector2f::Unit());
Nz::BoxCollider2DRef box2 = Nz::BoxCollider2D::New(aabb);
std::vector<Nz::Collider2DRef> colliders;
colliders.push_back(box1);
colliders.push_back(box2);
Nz::CompoundCollider2DRef compound = Nz::CompoundCollider2D::New(colliders);
float mass = 1.f;
Nz::RigidBody2D body(&world, mass, compound);
world.Step(1.f);
WHEN("We ask for the aabb of the compound")
{
THEN("We expect this to be true")
{
Nz::Rectf compoundAABB(0.f, 0.f, 2.f, 2.f);
REQUIRE(body.GetAABB() == compoundAABB);
}
}
}
GIVEN("A physic world and a rigid body of circle")
{
Nz::PhysWorld2D world;
std::vector<Nz::Vector2f> vertices;
vertices.push_back(Nz::Vector2f(0.f, 0.f));
vertices.push_back(Nz::Vector2f(0.f, 1.f));
vertices.push_back(Nz::Vector2f(1.f, 1.f));
vertices.push_back(Nz::Vector2f(1.f, 0.f));
Nz::SparsePtr<const Nz::Vector2f> sparsePtr(vertices.data());
Nz::ConvexCollider2DRef convex = Nz::ConvexCollider2D::New(sparsePtr, vertices.size());
float mass = 1.f;
Nz::RigidBody2D body(&world, mass, convex);
world.Step(1.f);
WHEN("We ask for the aabb of the convex")
{
THEN("We expect this to be true")
{
Nz::Rectf convexAABB(0.f, 0.f, 1.f, 1.f);
REQUIRE(body.GetAABB() == convexAABB);
}
}
}
GIVEN("A physic world and a rigid body of segment")
{
Nz::PhysWorld2D world;
Nz::Vector2f positionA(3.f, 4.f);
Nz::Vector2f positionB(1.f, -4.f);
Nz::Collider2DRef segment = Nz::SegmentCollider2D::New(positionA, positionB, 0.f);
float mass = 1.f;
Nz::RigidBody2D body(&world, mass, segment);
world.Step(1.f);
WHEN("We ask for the aabb of the segment")
{
THEN("We expect this to be true")
{
Nz::Rectf segmentAABB(positionA, positionB);
REQUIRE(body.GetAABB() == segmentAABB);
}
}
}
}
Nz::RigidBody2D CreateBody(Nz::PhysWorld2D& world)
{
Nz::Vector2f positionAABB(3.f, 4.f);
Nz::Rectf aabb(positionAABB.x, positionAABB.y, 1.f, 2.f);
Nz::Collider2DRef box = Nz::BoxCollider2D::New(aabb);
float mass = 1.f;
return Nz::RigidBody2D(&world, mass, box);
}
void EQUALITY(const Nz::RigidBody2D& left, const Nz::RigidBody2D& right)
{
CHECK(left.GetAABB() == right.GetAABB());
CHECK(left.GetAngularVelocity() == right.GetAngularVelocity());
CHECK(left.GetCenterOfGravity() == right.GetCenterOfGravity());
CHECK(left.GetGeom() == right.GetGeom());
CHECK(left.GetHandle() != right.GetHandle());
CHECK(left.GetMass() == right.GetMass());
CHECK(left.GetPosition() == right.GetPosition());
CHECK(left.GetRotation() == right.GetRotation());
CHECK(left.GetUserdata() == right.GetUserdata());
CHECK(left.GetVelocity() == right.GetVelocity());
}

View File

@ -5,19 +5,19 @@
#include <NDK/Components/PhysicsComponent2D.hpp> #include <NDK/Components/PhysicsComponent2D.hpp>
#include <Catch/catch.hpp> #include <Catch/catch.hpp>
Ndk::EntityHandle CreateBaseEntity(Ndk::World& world, const Nz::Vector2f& position, const Nz::Rectf AABB);
SCENARIO("PhysicsSystem2D", "[NDK][PHYSICSSYSTEM2D]") SCENARIO("PhysicsSystem2D", "[NDK][PHYSICSSYSTEM2D]")
{ {
GIVEN("A world and an entity") GIVEN("A world and an entity")
{ {
Ndk::World world; Ndk::World world;
const Ndk::EntityHandle& entity = world.CreateEntity();
Ndk::NodeComponent& nodeComponent = entity->AddComponent<Ndk::NodeComponent>();
Nz::Vector2f position(2.f, 3.f); Nz::Vector2f position(2.f, 3.f);
nodeComponent.SetPosition(position); Nz::Rectf movingAABB(0.f, 0.f, 16.f, 18.f);
Nz::Rectf aabb(0.f, 0.f, 16.f, 18.f); Ndk::EntityHandle movingEntity = CreateBaseEntity(world, position, movingAABB);
Nz::BoxCollider2DRef collisionBox = Nz::BoxCollider2D::New(aabb); Ndk::NodeComponent& nodeComponent = movingEntity->GetComponent<Ndk::NodeComponent>();
Ndk::CollisionComponent2D& collisionComponent = entity->AddComponent<Ndk::CollisionComponent2D>(collisionBox); Ndk::PhysicsComponent2D& physicsComponent2D = movingEntity->AddComponent<Ndk::PhysicsComponent2D>();
Ndk::PhysicsComponent2D& physicsComponent = entity->AddComponent<Ndk::PhysicsComponent2D>();
WHEN("We update the world") WHEN("We update the world")
{ {
@ -26,9 +26,123 @@ SCENARIO("PhysicsSystem2D", "[NDK][PHYSICSSYSTEM2D]")
THEN("Entity should have correct bounding box") THEN("Entity should have correct bounding box")
{ {
REQUIRE(nodeComponent.GetPosition() == position); REQUIRE(nodeComponent.GetPosition() == position);
aabb.Translate(position); movingAABB.Translate(position);
REQUIRE(physicsComponent.GetAABB() == aabb); REQUIRE(physicsComponent2D.GetAABB() == movingAABB);
}
}
WHEN("We make it collide with a wall")
{
int rawDistance = 3;
Nz::Vector2f distance(rawDistance, 0.f);
Nz::Vector2f wallPosition = position + Nz::Vector2f(movingAABB.width, 0.f) + distance;
Nz::Rectf wallAABB(0.f, 0.f, 100.f, 100.f);
Ndk::EntityHandle wallEntity = CreateBaseEntity(world, wallPosition, wallAABB);
world.Update(1.f);
THEN("It should moved freely")
{
REQUIRE(nodeComponent.GetPosition() == position);
movingAABB.Translate(position);
REQUIRE(physicsComponent2D.GetAABB() == movingAABB);
physicsComponent2D.SetVelocity(Nz::Vector2f::UnitX());
for (int i = 0; i < rawDistance; ++i)
{
world.Update(1.f);
position += Nz::Vector2f::UnitX();
REQUIRE(nodeComponent.GetPosition() == position);
movingAABB.Translate(Nz::Vector2f::UnitX());
REQUIRE(physicsComponent2D.GetAABB() == movingAABB);
}
}
AND_THEN("It should be stopped by it")
{
world.Update(1.f);
REQUIRE(nodeComponent.GetPosition().SquaredDistance(position) < 0.1f);
}
}
}
GIVEN("A world and a simple entity")
{
Ndk::World world;
Nz::Vector2f position(0.f, 0.f);
Nz::Rectf movingAABB(0.f, 0.f, 1.f, 2.f);
Ndk::EntityHandle movingEntity = CreateBaseEntity(world, position, movingAABB);
Ndk::NodeComponent& nodeComponent = movingEntity->GetComponent<Ndk::NodeComponent>();
Ndk::PhysicsComponent2D& physicsComponent2D = movingEntity->AddComponent<Ndk::PhysicsComponent2D>();
WHEN("We make rotate our entity")
{
float angularSpeed = Nz::FromDegrees(45.f);
physicsComponent2D.SetAngularVelocity(angularSpeed);
world.Update(2.f);
THEN("It should have been rotated")
{
CHECK(physicsComponent2D.GetAngularVelocity() == angularSpeed);
CHECK(physicsComponent2D.GetAABB() == Nz::Rectf(-2.f, 0.f, 2.f, 1.f));
CHECK(physicsComponent2D.GetRotation() == Approx(Nz::FromDegrees(90.f)));
CHECK(nodeComponent.GetRotation().ToEulerAngles().roll == Approx(Nz::FromDegrees(90.f)));
}
}
WHEN("We put a force on it")
{
float stepSize = world.GetSystem<Ndk::PhysicsSystem2D>().GetWorld().GetStepSize();
Nz::Vector2f velocity = Nz::Vector2f::UnitX();
physicsComponent2D.AddForce(velocity / stepSize);
world.Update(1.f);
THEN("Velocity should be the one targetted")
{
REQUIRE(physicsComponent2D.GetVelocity() == velocity);
world.Update(99.f);
REQUIRE(physicsComponent2D.GetPosition().Distance(Nz::Vector2f::UnitX() * 100.f) < 1.f);
REQUIRE(nodeComponent.GetPosition().Distance(Nz::Vector2f::UnitX() * 100.f) < 1.f);
}
}
}
GIVEN("A world and a simple entity not at the origin")
{
Ndk::World world;
Nz::Vector2f position(3.f, 4.f);
Nz::Rectf movingAABB(0.f, 0.f, 1.f, 2.f);
Ndk::EntityHandle movingEntity = CreateBaseEntity(world, position, movingAABB);
Ndk::NodeComponent& nodeComponent = movingEntity->GetComponent<Ndk::NodeComponent>();
Ndk::PhysicsComponent2D& physicsComponent2D = movingEntity->AddComponent<Ndk::PhysicsComponent2D>();
WHEN("We make rotate our entity")
{
float angularSpeed = Nz::FromDegrees(45.f);
physicsComponent2D.SetAngularVelocity(angularSpeed);
world.Update(2.f);
THEN("It should have been rotated")
{
CHECK(physicsComponent2D.GetAngularVelocity() == angularSpeed);
CHECK(physicsComponent2D.GetAABB() == Nz::Rectf(1.f, 4.f, 2.f, 1.f));
CHECK(physicsComponent2D.GetRotation() == Approx(Nz::FromDegrees(90.f)));
CHECK(nodeComponent.GetPosition() == position);
CHECK(nodeComponent.GetRotation().ToEulerAngles().roll == Approx(Nz::FromDegrees(90.f)));
} }
} }
} }
} }
Ndk::EntityHandle CreateBaseEntity(Ndk::World& world, const Nz::Vector2f& position, const Nz::Rectf AABB)
{
Ndk::EntityHandle entity = world.CreateEntity();
Ndk::NodeComponent& nodeComponent = entity->AddComponent<Ndk::NodeComponent>();
nodeComponent.SetPosition(position);
Nz::BoxCollider2DRef collisionBox = Nz::BoxCollider2D::New(AABB);
entity->AddComponent<Ndk::CollisionComponent2D>(collisionBox);
return entity;
}

View File

@ -1,13 +1,11 @@
#include <NDK/Systems/RenderSystem.hpp> #include <NDK/Systems/RenderSystem.hpp>
#include <NDK/World.hpp> #include <NDK/World.hpp>
#include <NDK/Components/CameraComponent.hpp> #include <NDK/Components.hpp>
#include <NDK/Components/GraphicsComponent.hpp>
#include <NDK/Components/LightComponent.hpp>
#include <NDK/Components/NodeComponent.hpp>
#include <NDK/Components/ParticleGroupComponent.hpp>
#include <Nazara/Graphics/Sprite.hpp> #include <Nazara/Graphics/Sprite.hpp>
#include <Catch/catch.hpp> #include <Catch/catch.hpp>
void CompareAABB(const Nz::Rectf& aabb, const Nz::BoundingVolumef& boundingVolume);
SCENARIO("RenderSystem", "[NDK][RenderSystem]") SCENARIO("RenderSystem", "[NDK][RenderSystem]")
{ {
GIVEN("A world with a camera, a drawable, a light and some particles") GIVEN("A world with a camera, a drawable, a light and some particles")
@ -41,4 +39,79 @@ SCENARIO("RenderSystem", "[NDK][RenderSystem]")
} }
} }
} }
GIVEN("A world with 2D coordinates (upper-left) and an entity with graphics and physics")
{
Ndk::World world;
world.GetSystem<Ndk::RenderSystem>().SetGlobalUp(Nz::Vector3f::Down());
const Ndk::EntityHandle& entity = world.CreateEntity();
Nz::Vector2f position(3.f, 4.f);
Ndk::NodeComponent& nodeComponent = entity->AddComponent<Ndk::NodeComponent>();
nodeComponent.SetPosition(position);
Nz::Vector2f dimensions(1.f, 2.f);
Ndk::GraphicsComponent& graphicsComponent = entity->AddComponent<Ndk::GraphicsComponent>();
Nz::SpriteRef sprite = Nz::Sprite::New();
sprite->SetSize(dimensions);
graphicsComponent.Attach(sprite);
Nz::Rectf aabb(Nz::Vector2f::Zero(), dimensions);
Nz::BoxCollider2DRef boxCollider2D = Nz::BoxCollider2D::New(aabb);
entity->AddComponent<Ndk::CollisionComponent2D>(boxCollider2D);
Ndk::PhysicsComponent2D& physicsComponent2D = entity->AddComponent<Ndk::PhysicsComponent2D>();
world.Update(1.f);
WHEN("We move it")
{
Nz::Vector2f velocity = Nz::Vector2f::UnitY();
physicsComponent2D.SetVelocity(velocity);
world.Update(1.f);
THEN("Graphics and physics should be synchronised")
{
CHECK(nodeComponent.GetPosition() == position + velocity);
CHECK(physicsComponent2D.GetAABB() == aabb.Translate(position + velocity));
CompareAABB(physicsComponent2D.GetAABB(), graphicsComponent.GetBoundingVolume());
}
}
WHEN("We set an angular velocity")
{
float angularSpeed = Nz::FromDegrees(90.f);
physicsComponent2D.SetAngularVelocity(angularSpeed);
world.Update(1.f);
THEN("We expect those to be true")
{
CHECK(physicsComponent2D.GetAngularVelocity() == Approx(angularSpeed));
CHECK(physicsComponent2D.GetRotation() == Approx(angularSpeed));
CHECK(physicsComponent2D.GetAABB() == Nz::Rectf(1.f, 4.f, 2.f, 1.f));
CompareAABB(physicsComponent2D.GetAABB(), graphicsComponent.GetBoundingVolume());
world.Update(1.f);
CHECK(physicsComponent2D.GetRotation() == Approx(2.f * angularSpeed));
CHECK(physicsComponent2D.GetAABB() == Nz::Rectf(2.f, 2.f, 1.f, 2.f));
CompareAABB(physicsComponent2D.GetAABB(), graphicsComponent.GetBoundingVolume());
world.Update(1.f);
CHECK(physicsComponent2D.GetRotation() == Approx(3.f * angularSpeed));
CHECK(physicsComponent2D.GetAABB() == Nz::Rectf(3.f, 3.f, 2.f, 1.f));
CompareAABB(physicsComponent2D.GetAABB(), graphicsComponent.GetBoundingVolume());
world.Update(1.f);
CHECK(physicsComponent2D.GetRotation() == Approx(4.f * angularSpeed));
}
}
}
}
void CompareAABB(const Nz::Rectf& aabb, const Nz::BoundingVolumef& boundingVolume)
{
Nz::Boxf box = boundingVolume.aabb;
CHECK(aabb.x == Approx(box.x));
CHECK(aabb.y == Approx(box.y));
CHECK(aabb.width == Approx(box.width));
CHECK(aabb.height == Approx(box.height));
} }