Merge branch 'master' into physics2d-position-offset

This commit is contained in:
Lynix 2019-03-26 20:33:40 +01:00
commit 23887cc519
12 changed files with 206 additions and 37 deletions

View File

@ -174,6 +174,8 @@ Nazara Engine:
- Signal now implement a copy constructor and copy assignation operator for convenience
- Fixed ENet UnreliableFragment packets sent as Unreliable (and such being incomplete upon reception)
- ENet DisconnectLater now reflects libenet behavior (and is waiting for unreliable commands to be sent before disconnecting for good)
- ⚠ Collider3D::ForEachPolygon now takes a void(Vector3f\*, std::size_t) callback (instead of void(float\*, std::size_t))
- Added Collider2D::ForEachPolygon method
Nazara Development Kit:
- Added ImageWidget (#139)
@ -217,7 +219,7 @@ Nazara Development Kit:
- Fix GraphicsComponent bounding volume not taking local matrix in account
- ⚠️ Rewrote all render queue system, which should be more efficient, take scissor box into account
- ⚠️ All widgets are now bound to a scissor box when rendering
- Add DebugComponent (a component able to show aabb/obb/collision mesh)
- Add DebugComponent (a component able to show aabb/obb/collision mesh 2D and 3D)
- ⚠️ TextAreaWidget now support text selection (WIP)
- ⚠️ TextAreaWidget::GetHoveredGlyph now returns a two-dimensional position instead of a single glyph position
- Fixed Entity::OnEntityDestruction signal not being properly moved and thus not being called.

View File

@ -16,7 +16,7 @@ namespace Ndk
{
enum class DebugDraw
{
//TODO: Collider2D
Collider2D,
Collider3D,
GraphicsAABB,
GraphicsOBB,

View File

@ -26,6 +26,7 @@ namespace Ndk
private:
Nz::InstancedRenderableRef GenerateBox(Nz::Boxf box);
Nz::InstancedRenderableRef GenerateCollision2DMesh(Entity* entity, Nz::Vector3f* origin);
Nz::InstancedRenderableRef GenerateCollision3DMesh(Entity* entity);
Nz::MaterialRef GetCollisionMaterial();

View File

@ -8,10 +8,12 @@
#include <Nazara/Utility/IndexIterator.hpp>
#include <Nazara/Utility/Mesh.hpp>
#include <Nazara/Utility/StaticMesh.hpp>
#include <NDK/Components/CollisionComponent2D.hpp>
#include <NDK/Components/CollisionComponent3D.hpp>
#include <NDK/Components/DebugComponent.hpp>
#include <NDK/Components/GraphicsComponent.hpp>
#include <NDK/Components/NodeComponent.hpp>
#include <NDK/Components/PhysicsComponent2D.hpp>
namespace Ndk
{
@ -227,17 +229,26 @@ namespace Ndk
{
switch (option)
{
case DebugDraw::Collider2D:
{
const Nz::Boxf& obb = entityGfx.GetAABB();
Nz::Vector3f origin;
Nz::InstancedRenderableRef renderable = GenerateCollision2DMesh(entity, &origin);
if (renderable)
entityGfx.Attach(renderable, Nz::Matrix4f::Translate(origin - entityNode.GetPosition()), DebugDrawOrder);
entityDebug.UpdateDebugRenderable(option, std::move(renderable));
break;
}
case DebugDraw::Collider3D:
{
const Nz::Boxf& obb = entityGfx.GetAABB();
Nz::InstancedRenderableRef renderable = GenerateCollision3DMesh(entity);
if (renderable)
{
renderable->SetPersistent(false);
entityGfx.Attach(renderable, Nz::Matrix4f::Translate(obb.GetCenter() - entityNode.GetPosition()), DebugDrawOrder);
}
entityDebug.UpdateDebugRenderable(option, std::move(renderable));
break;
@ -305,6 +316,73 @@ namespace Ndk
return model;
}
Nz::InstancedRenderableRef DebugSystem::GenerateCollision2DMesh(Entity* entity, Nz::Vector3f* origin)
{
if (entity->HasComponent<CollisionComponent2D>())
{
CollisionComponent2D& entityCollision = entity->GetComponent<CollisionComponent2D>();
const Nz::Collider2DRef& geom = entityCollision.GetGeom();
std::vector<Nz::Vector3f> vertices;
std::vector<std::size_t> indices;
geom->ForEachPolygon([&](const Nz::Vector2f* polygonVertices, std::size_t vertexCount)
{
std::size_t firstIndex = vertices.size();
// Don't reserve and let the vector handle its own capacity
for (std::size_t i = 0; i < vertexCount; ++i)
vertices.emplace_back(*polygonVertices++);
for (std::size_t i = 0; i < vertexCount - 1; ++i)
{
indices.push_back(firstIndex + i);
indices.push_back(firstIndex + i + 1);
}
indices.push_back(firstIndex + vertexCount - 1);
indices.push_back(firstIndex);
});
Nz::IndexBufferRef indexBuffer = Nz::IndexBuffer::New(vertices.size() > 0xFFFF, Nz::UInt32(indices.size()), Nz::DataStorage_Hardware, 0);
Nz::IndexMapper indexMapper(indexBuffer, Nz::BufferAccess_WriteOnly);
Nz::IndexIterator indexPtr = indexMapper.begin();
for (std::size_t index : indices)
*indexPtr++ = static_cast<Nz::UInt32>(index);
indexMapper.Unmap();
Nz::VertexBufferRef vertexBuffer = Nz::VertexBuffer::New(Nz::VertexDeclaration::Get(Nz::VertexLayout_XYZ), Nz::UInt32(vertices.size()), Nz::DataStorage_Hardware, 0);
vertexBuffer->Fill(vertices.data(), 0, Nz::UInt32(vertices.size()));
Nz::MeshRef mesh = Nz::Mesh::New();
mesh->CreateStatic();
Nz::StaticMeshRef subMesh = Nz::StaticMesh::New(vertexBuffer, indexBuffer);
subMesh->SetPrimitiveMode(Nz::PrimitiveMode_LineList);
subMesh->SetMaterialIndex(0);
subMesh->GenerateAABB();
mesh->SetMaterialCount(1);
mesh->AddSubMesh(subMesh);
Nz::ModelRef model = Nz::Model::New();
model->SetMesh(mesh);
model->SetMaterial(0, GetCollisionMaterial());
// Find center of mass
if (entity->HasComponent<PhysicsComponent2D>())
*origin = entity->GetComponent<PhysicsComponent2D>().GetMassCenter(Nz::CoordSys_Global);
else
*origin = entity->GetComponent<NodeComponent>().GetPosition(Nz::CoordSys_Global);
return model;
}
else
return nullptr;
}
Nz::InstancedRenderableRef DebugSystem::GenerateCollision3DMesh(Entity* entity)
{
@ -315,16 +393,12 @@ namespace Ndk
std::vector<Nz::Vector3f> vertices;
std::vector<std::size_t> indices;
geom->ForEachPolygon([&](const float* polygonVertices, std::size_t vertexCount)
geom->ForEachPolygon([&](const Nz::Vector3f* polygonVertices, std::size_t vertexCount)
{
std::size_t firstIndex = vertices.size();
for (std::size_t i = 0; i < vertexCount; ++i)
{
const float* vertexData = &polygonVertices[i * 3];
vertices.emplace_back(vertexData[0], vertexData[1], vertexData[2]);
}
vertices.resize(firstIndex + vertexCount);
std::copy(polygonVertices, polygonVertices + vertexCount, &vertices[firstIndex]);
for (std::size_t i = 0; i < vertexCount - 1; ++i)
{
@ -378,7 +452,7 @@ namespace Ndk
m_globalAabbMaterial->EnableDepthBuffer(true);
m_globalAabbMaterial->SetDiffuseColor(Nz::Color::Orange);
m_globalAabbMaterial->SetFaceFilling(Nz::FaceFilling_Line);
m_globalAabbMaterial->SetLineWidth(2.f);
//m_globalAabbMaterial->SetLineWidth(2.f);
}
return m_globalAabbMaterial;
@ -393,7 +467,7 @@ namespace Ndk
m_localAabbMaterial->EnableDepthBuffer(true);
m_localAabbMaterial->SetDiffuseColor(Nz::Color::Red);
m_localAabbMaterial->SetFaceFilling(Nz::FaceFilling_Line);
m_localAabbMaterial->SetLineWidth(2.f);
//m_localAabbMaterial->SetLineWidth(2.f);
}
return m_localAabbMaterial;
@ -408,7 +482,7 @@ namespace Ndk
m_collisionMaterial->EnableDepthBuffer(true);
m_collisionMaterial->SetDiffuseColor(Nz::Color::Blue);
m_collisionMaterial->SetFaceFilling(Nz::FaceFilling_Line);
m_collisionMaterial->SetLineWidth(2.f);
//m_collisionMaterial->SetLineWidth(2.f);
}
return m_collisionMaterial;
@ -423,7 +497,7 @@ namespace Ndk
m_obbMaterial->EnableDepthBuffer(true);
m_obbMaterial->SetDiffuseColor(Nz::Color::Green);
m_obbMaterial->SetFaceFilling(Nz::FaceFilling_Line);
m_obbMaterial->SetLineWidth(2.f);
//m_obbMaterial->SetLineWidth(2.f);
}
return m_obbMaterial;

View File

@ -41,9 +41,11 @@ namespace Nz
Collider2D(Collider2D&&) = delete;
virtual ~Collider2D();
virtual Nz::Vector2f ComputeCenterOfMass() const = 0;
virtual Vector2f ComputeCenterOfMass() const = 0;
virtual float ComputeMomentOfInertia(float mass) const = 0;
virtual void ForEachPolygon(const std::function<void(const Vector2f* vertices, std::size_t vertexCount)>& callback) const;
inline UInt32 GetCategoryMask() const;
inline UInt32 GetCollisionGroup() const;
inline unsigned int GetCollisionId() const;

View File

@ -54,7 +54,7 @@ namespace Nz
virtual void ComputeInertialMatrix(Vector3f* inertia, Vector3f* center) const;
virtual float ComputeVolume() const;
virtual void ForEachPolygon(const std::function<void(const float* vertices, std::size_t vertexCount)>& callback) const;
virtual void ForEachPolygon(const std::function<void(const Vector3f* vertices, std::size_t vertexCount)>& callback) const;
NewtonCollision* GetHandle(PhysWorld3D* world) const;
virtual ColliderType3D GetType() const = 0;

View File

@ -3,14 +3,81 @@
// For conditions of distribution and use, see copyright notice in Config.hpp
#include <Nazara/Physics2D/Collider2D.hpp>
#include <Nazara/Math/Quaternion.hpp>
#include <Nazara/Physics2D/RigidBody2D.hpp>
#include <Nazara/Physics2D/PhysWorld2D.hpp>
#include <chipmunk/chipmunk.h>
#include <Nazara/Physics3D/Debug.hpp>
#include <chipmunk/chipmunk_structs.h>
#include <array>
#include <Nazara/Physics2D/Debug.hpp>
namespace Nz
{
Collider2D::~Collider2D() = default;
void Collider2D::ForEachPolygon(const std::function<void(const Vector2f* vertices, std::size_t vertexCount)>& callback) const
{
// Currently, the only way to get only the polygons of a shape is to create a temporary cpSpace containing only this shape
// A better way to do this would be to reimplement this function in every subclass type in the very same way chipmunk does
PhysWorld2D physWorld;
RigidBody2D rigidBody(&physWorld, 0.f);
std::vector<cpShape*> shapeVector;
rigidBody.SetGeom(const_cast<Collider2D*>(this), false, false); //< Won't be used for writing, but still ugly
PhysWorld2D::DebugDrawOptions drawCallbacks;
drawCallbacks.circleCallback = [&](const Vector2f& origin, const RadianAnglef& /*rotation*/, float radius, Nz::Color /*outlineColor*/, Nz::Color /*fillColor*/, void* /*userData*/)
{
constexpr std::size_t circleVerticesCount = 20;
std::array<Vector2f, circleVerticesCount> vertices;
RadianAnglef angleBetweenVertices = 2.f * float(M_PI) / vertices.size();
for (std::size_t i = 0; i < vertices.size(); ++i)
{
RadianAnglef angle = float(i) * angleBetweenVertices;
std::pair<float, float> sincos = angle.GetSinCos();
vertices[i] = origin + Vector2f(radius * sincos.first, radius * sincos.second);
}
callback(vertices.data(), vertices.size());
};
drawCallbacks.polygonCallback = [&](const Vector2f* vertices, std::size_t vertexCount, float radius, Nz::Color /*outlineColor*/, Nz::Color /*fillColor*/, void* /*userData*/)
{
//TODO: Handle radius
callback(vertices, vertexCount);
};
drawCallbacks.segmentCallback = [&](const Vector2f& first, const Vector2f& second, Nz::Color /*color*/, void* /*userData*/)
{
std::array<Vector2f, 2> vertices = { first, second };
callback(vertices.data(), vertices.size());
};
drawCallbacks.thickSegmentCallback = [&](const Vector2f& first, const Vector2f& second, float thickness, Nz::Color /*outlineColor*/, Nz::Color /*fillColor*/, void* /*userData*/)
{
static std::pair<float, float> sincos = Nz::DegreeAnglef(90.f).GetSinCos();
Vector2f normal = Vector2f::Normalize(second - first);
Vector2f thicknessNormal(sincos.second * normal.x - sincos.first * normal.y,
sincos.first * normal.x + sincos.second * normal.y);
std::array<Vector2f, 4> vertices;
vertices[0] = first + thickness * thicknessNormal;
vertices[1] = first - thickness * thicknessNormal;
vertices[2] = second - thickness * thicknessNormal;
vertices[3] = second + thickness * thicknessNormal;
callback(vertices.data(), vertices.size());
};
physWorld.DebugDraw(drawCallbacks, true, false, false);
}
std::size_t Collider2D::GenerateShapes(RigidBody2D* body, std::vector<cpShape*>* shapes) const
{
std::size_t shapeCount = CreateShapes(body, shapes);
@ -75,7 +142,7 @@ namespace Nz
Nz::Vector2f CircleCollider2D::ComputeCenterOfMass() const
{
return m_offset + Nz::Vector2f(m_radius, m_radius);
return m_offset;
}
float CircleCollider2D::ComputeMomentOfInertia(float mass) const

View File

@ -114,12 +114,14 @@ namespace Nz
return volume;
}
void Collider3D::ForEachPolygon(const std::function<void(const float* vertices, std::size_t vertexCount)>& callback) const
void Collider3D::ForEachPolygon(const std::function<void(const Vector3f* vertices, std::size_t vertexCount)>& callback) const
{
auto newtCallback = [](void* const userData, int vertexCount, const dFloat* const faceArray, int /*faceId*/)
{
static_assert(sizeof(Vector3f) == 3 * sizeof(float), "Vector3 is expected to contain 3 floats without padding");
const auto& cb = *static_cast<std::add_pointer_t<decltype(callback)>>(userData);
cb(faceArray, vertexCount);
cb(reinterpret_cast<const Vector3f*>(faceArray), vertexCount);
};
// Check for existing collision handles, and create a temporary one if none is available

View File

@ -292,5 +292,5 @@ namespace Nz
}
else
NazaraError("Invalid window handle");
}
}
}

View File

@ -71,8 +71,8 @@ namespace Nz
win32Mode.dmBitsPerPel = mode.bitsPerPixel;
win32Mode.dmPelsHeight = mode.height;
win32Mode.dmPelsWidth = mode.width;
win32Mode.dmFields = DM_BITSPERPEL | DM_PELSWIDTH | DM_PELSHEIGHT;
win32Mode.dmSize = sizeof(DEVMODE);
win32Mode.dmFields = DM_BITSPERPEL | DM_PELSWIDTH | DM_PELSHEIGHT;
win32Mode.dmSize = sizeof(DEVMODE);
if (ChangeDisplaySettings(&win32Mode, CDS_FULLSCREEN) != DISP_CHANGE_SUCCESSFUL)
{

View File

@ -1,6 +1,7 @@
#include <Nazara/Physics2D/RigidBody2D.hpp>
#include <Nazara/Physics2D/PhysWorld2D.hpp>
#include <Catch/catch.hpp>
#include <iostream>
#include <limits>
Nz::RigidBody2D CreateBody(Nz::PhysWorld2D& world);
@ -93,6 +94,7 @@ SCENARIO("RigidBody2D", "[PHYSICS2D][RIGIDBODY2D]")
std::vector<Nz::RigidBody2D> tmp;
tmp.push_back(CreateBody(world));
tmp.push_back(CreateBody(world));
world.Step(1.f);
THEN("They should be valid")
@ -112,11 +114,14 @@ SCENARIO("RigidBody2D", "[PHYSICS2D][RIGIDBODY2D]")
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);
Nz::RigidBody2D body(&world, mass);
body.SetGeom(box, true, false);
bool userData = false;
body.SetUserdata(&userData);
Nz::Vector2f position = Nz::Vector2f::Zero();
body.SetPosition(position);
world.Step(1.f);
@ -126,7 +131,7 @@ SCENARIO("RigidBody2D", "[PHYSICS2D][RIGIDBODY2D]")
{
CHECK(body.GetAABB() == aabb);
CHECK(body.GetAngularVelocity() == 0.f);
CHECK(body.GetMassCenter() == Nz::Vector2f::Zero());
CHECK(body.GetMassCenter(Nz::CoordSys_Global) == position);
CHECK(body.GetGeom() == box);
CHECK(body.GetMass() == Approx(mass));
CHECK(body.GetPosition() == position);
@ -150,7 +155,7 @@ SCENARIO("RigidBody2D", "[PHYSICS2D][RIGIDBODY2D]")
{
aabb.Translate(velocity);
CHECK(body.GetAABB() == aabb);
CHECK(body.GetMassCenter() == Nz::Vector2f::Zero());
CHECK(body.GetMassCenter(Nz::CoordSys_Global) == position);
CHECK(body.GetPosition() == position);
CHECK(body.GetVelocity() == velocity);
}
@ -211,7 +216,9 @@ SCENARIO("RigidBody2D", "[PHYSICS2D][RIGIDBODY2D]")
float radius = 5.f;
Nz::Collider2DRef circle = Nz::CircleCollider2D::New(radius, position);
float mass = 1.f;
Nz::RigidBody2D body(&world, mass, circle);
Nz::RigidBody2D body(&world, mass);
body.SetGeom(circle, true, false);
world.Step(1.f);
WHEN("We ask for the aabb of the circle")
@ -240,7 +247,9 @@ SCENARIO("RigidBody2D", "[PHYSICS2D][RIGIDBODY2D]")
Nz::CompoundCollider2DRef compound = Nz::CompoundCollider2D::New(colliders);
float mass = 1.f;
Nz::RigidBody2D body(&world, mass, compound);
Nz::RigidBody2D body(&world, mass);
body.SetGeom(compound, true, false);
world.Step(1.f);
WHEN("We ask for the aabb of the compound")
@ -267,7 +276,9 @@ SCENARIO("RigidBody2D", "[PHYSICS2D][RIGIDBODY2D]")
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);
Nz::RigidBody2D body(&world, mass);
body.SetGeom(convex, true, false);
world.Step(1.f);
WHEN("We ask for the aabb of the convex")
@ -289,7 +300,9 @@ SCENARIO("RigidBody2D", "[PHYSICS2D][RIGIDBODY2D]")
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);
Nz::RigidBody2D body(&world, mass);
body.SetGeom(segment, true, false);
world.Step(1.f);
WHEN("We ask for the aabb of the segment")
@ -309,7 +322,11 @@ Nz::RigidBody2D CreateBody(Nz::PhysWorld2D& world)
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);
Nz::RigidBody2D body(&world, mass, box);
body.SetPosition(Nz::Vector2f::Zero());
return body;
}
void EQUALITY(const Nz::RigidBody2D& left, const Nz::RigidBody2D& right)

View File

@ -6,7 +6,7 @@
#include <Catch/catch.hpp>
#include <limits>
Ndk::EntityHandle CreateBaseEntity(Ndk::World& world, const Nz::Vector2f& position, const Nz::Rectf AABB);
Ndk::EntityHandle CreateBaseEntity(Ndk::World& world, const Nz::Vector2f& position, const Nz::Rectf& AABB);
SCENARIO("PhysicsSystem2D", "[NDK][PHYSICSSYSTEM2D]")
{
@ -80,6 +80,8 @@ SCENARIO("PhysicsSystem2D", "[NDK][PHYSICSSYSTEM2D]")
Ndk::EntityHandle movingEntity = CreateBaseEntity(world, position, movingAABB);
Ndk::NodeComponent& nodeComponent = movingEntity->GetComponent<Ndk::NodeComponent>();
Ndk::PhysicsComponent2D& physicsComponent2D = movingEntity->AddComponent<Ndk::PhysicsComponent2D>();
physicsComponent2D.SetMassCenter(Nz::Vector2f::Zero());
physicsComponent2D.SetPosition(position);
world.GetSystem<Ndk::PhysicsSystem2D>().SetFixedUpdateRate(30.f);
@ -124,6 +126,8 @@ SCENARIO("PhysicsSystem2D", "[NDK][PHYSICSSYSTEM2D]")
Ndk::EntityHandle movingEntity = CreateBaseEntity(world, position, movingAABB);
Ndk::NodeComponent& nodeComponent = movingEntity->GetComponent<Ndk::NodeComponent>();
Ndk::PhysicsComponent2D& physicsComponent2D = movingEntity->AddComponent<Ndk::PhysicsComponent2D>();
physicsComponent2D.SetMassCenter(Nz::Vector2f::Zero());
physicsComponent2D.SetPosition(position);
world.GetSystem<Ndk::PhysicsSystem2D>().SetFixedUpdateRate(30.f);
@ -145,7 +149,7 @@ SCENARIO("PhysicsSystem2D", "[NDK][PHYSICSSYSTEM2D]")
}
}
Ndk::EntityHandle CreateBaseEntity(Ndk::World& world, const Nz::Vector2f& position, const Nz::Rectf AABB)
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>();