Merge remote-tracking branch 'upstream/master'
This commit is contained in:
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -56,23 +56,32 @@
|
||||
#include <bounce/dynamics/contacts/convex_contact.h>
|
||||
#include <bounce/dynamics/contacts/mesh_contact.h>
|
||||
|
||||
#include <bounce/dynamics/rope/rope.h>
|
||||
|
||||
#include <bounce/garment/sewing_pattern.h>
|
||||
#include <bounce/garment/garment.h>
|
||||
#include <bounce/garment/garment_mesh.h>
|
||||
|
||||
#include <bounce/dynamics/cloth/cloth_mesh.h>
|
||||
#include <bounce/dynamics/cloth/cloth.h>
|
||||
#include <bounce/dynamics/cloth/particle.h>
|
||||
#include <bounce/dynamics/cloth/spring_force.h>
|
||||
|
||||
#include <bounce/dynamics/body.h>
|
||||
|
||||
#include <bounce/dynamics/world.h>
|
||||
#include <bounce/dynamics/world_listeners.h>
|
||||
|
||||
#include <bounce/controllers/cloth_dragger.h>
|
||||
#include <bounce/controllers/body_dragger.h>
|
||||
#include <bounce/rope/rope.h>
|
||||
|
||||
#include <bounce/cloth/cloth_mesh.h>
|
||||
#include <bounce/cloth/grid_cloth_mesh.h>
|
||||
#include <bounce/cloth/garment_cloth_mesh.h>
|
||||
#include <bounce/cloth/cloth.h>
|
||||
#include <bounce/cloth/particle.h>
|
||||
#include <bounce/cloth/cloth_triangle.h>
|
||||
|
||||
#include <bounce/cloth/forces/strech_force.h>
|
||||
#include <bounce/cloth/forces/shear_force.h>
|
||||
#include <bounce/cloth/forces/spring_force.h>
|
||||
#include <bounce/cloth/forces/mouse_force.h>
|
||||
|
||||
#include <bounce/cloth/garment/sewing_pattern.h>
|
||||
#include <bounce/cloth/garment/garment.h>
|
||||
#include <bounce/cloth/garment/garment_mesh.h>
|
||||
|
||||
#include <bounce/softbody/softbody_mesh.h>
|
||||
#include <bounce/softbody/block_softbody_mesh.h>
|
||||
#include <bounce/softbody/softbody.h>
|
||||
#include <bounce/softbody/softbody_node.h>
|
||||
|
||||
#endif
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -19,21 +19,21 @@
|
||||
#ifndef B3_CLOTH_H
|
||||
#define B3_CLOTH_H
|
||||
|
||||
#include <bounce/common/math/transform.h>
|
||||
#include <bounce/common/template/list.h>
|
||||
#include <bounce/common/memory/stack_allocator.h>
|
||||
#include <bounce/common/memory/block_pool.h>
|
||||
#include <bounce/common/math/transform.h>
|
||||
#include <bounce/cloth/cloth_contact_manager.h>
|
||||
|
||||
class b3World;
|
||||
class b3Shape;
|
||||
|
||||
class b3Particle;
|
||||
class b3Force;
|
||||
class b3BodyContact;
|
||||
class b3ParticleContact;
|
||||
class b3TriangleContact;
|
||||
|
||||
struct b3ParticleDef;
|
||||
class b3Particle;
|
||||
|
||||
struct b3ForceDef;
|
||||
class b3Force;
|
||||
|
||||
class b3ClothTriangle;
|
||||
|
||||
struct b3ClothMesh;
|
||||
|
||||
@ -57,33 +57,62 @@ struct b3ClothDef
|
||||
{
|
||||
mesh = nullptr;
|
||||
density = 0.0f;
|
||||
structural = 0.0f;
|
||||
streching = 0.0f;
|
||||
shearing = 0.0f;
|
||||
bending = 0.0f;
|
||||
sewing = 0.0f;
|
||||
damping = 0.0f;
|
||||
thickness = 0.0f;
|
||||
friction = 0.2f;
|
||||
}
|
||||
|
||||
// Cloth mesh
|
||||
const b3ClothMesh* mesh;
|
||||
|
||||
// Cloth density in kg/m^3
|
||||
// Cloth density in kg/m^2
|
||||
float32 density;
|
||||
|
||||
// Structural stiffness
|
||||
float32 structural;
|
||||
// Streching stiffness
|
||||
float32 streching;
|
||||
|
||||
// Shearing stiffness
|
||||
float32 shearing;
|
||||
|
||||
// Bending stiffness
|
||||
float32 bending;
|
||||
|
||||
// Sewing stiffness
|
||||
float32 sewing;
|
||||
|
||||
// Damping stiffness
|
||||
float32 damping;
|
||||
|
||||
// Cloth thickness
|
||||
float32 thickness;
|
||||
|
||||
// Cloth coefficient of friction
|
||||
float32 friction;
|
||||
};
|
||||
|
||||
// A cloth represents a deformable surface as a collection of particles.
|
||||
// Particles may be connected with each other.
|
||||
// Particles may be connected with each other by springs.
|
||||
class b3Cloth
|
||||
{
|
||||
public:
|
||||
// Get the world the cloth belongs to.
|
||||
b3Cloth(const b3ClothDef& def);
|
||||
~b3Cloth();
|
||||
|
||||
// Set the acceleration of gravity.
|
||||
void SetGravity(const b3Vec3& gravity);
|
||||
|
||||
// Get the acceleration of gravity.
|
||||
b3Vec3 GetGravity() const;
|
||||
|
||||
// Attach a world to this cloth.
|
||||
// The cloth will be able to respond to collisions with the rigid bodies in the attached world.
|
||||
void SetWorld(b3World* world);
|
||||
|
||||
// Get the world attached to this cloth.
|
||||
const b3World* GetWorld() const;
|
||||
b3World* GetWorld();
|
||||
|
||||
@ -99,9 +128,6 @@ public:
|
||||
// Destroy a given force.
|
||||
void DestroyForce(b3Force* force);
|
||||
|
||||
// Perform a ray cast with the cloth.
|
||||
void RayCast(b3RayCastListener* listener, const b3Vec3& p1, const b3Vec3& p2);
|
||||
|
||||
// Perform a ray cast with the cloth.
|
||||
bool RayCastSingle(b3ClothRayCastSingleOutput* output, const b3Vec3& p1, const b3Vec3& p2) const;
|
||||
|
||||
@ -111,8 +137,11 @@ public:
|
||||
// Return the cloth mesh proxy.
|
||||
const b3ClothMesh* GetMesh() const;
|
||||
|
||||
// Return the particle associated with the given vertex.
|
||||
b3Particle* GetVertexParticle(u32 i);
|
||||
// Return the cloth particle given the vertex index.
|
||||
b3Particle* GetParticle(u32 i);
|
||||
|
||||
// Return the cloth triangle given the triangle index.
|
||||
b3ClothTriangle* GetTriangle(u32 i);
|
||||
|
||||
// Return the list of particles in this cloth.
|
||||
const b3List2<b3Particle>& GetParticleList() const;
|
||||
@ -123,49 +152,43 @@ public:
|
||||
// Return the kinetic (or dynamic) energy in this system.
|
||||
float32 GetEnergy() const;
|
||||
|
||||
// Get the next cloth in the world cloth list.
|
||||
const b3Cloth* GetNext() const;
|
||||
|
||||
// Get the next cloth in the world cloth list.
|
||||
b3Cloth* GetNext();
|
||||
// Perform a time step.
|
||||
void Step(float32 dt, u32 velocityIterations, u32 positionIterations);
|
||||
|
||||
// Debug draw the cloth using the associated cloth mesh.
|
||||
void Draw() const;
|
||||
private:
|
||||
friend class b3World;
|
||||
|
||||
friend class b3List2<b3Cloth>;
|
||||
|
||||
b3Cloth(const b3ClothDef& def, b3World* world);
|
||||
~b3Cloth();
|
||||
|
||||
// Perform a time step.
|
||||
// Called only inside b3World.
|
||||
void Step(float32 dt, const b3Vec3& gravity);
|
||||
friend class b3Particle;
|
||||
friend class b3ClothTriangle;
|
||||
friend class b3ShearForce;
|
||||
friend class b3StrechForce;
|
||||
friend class b3SpringForce;
|
||||
friend class b3MouseForce;
|
||||
friend class b3ClothContactManager;
|
||||
|
||||
// Compute mass of each particle.
|
||||
void ComputeMass();
|
||||
|
||||
// Update body contacts.
|
||||
void UpdateBodyContacts();
|
||||
|
||||
// Update particle contacts.
|
||||
void UpdateParticleContacts();
|
||||
|
||||
// Update triangle contacts.
|
||||
void UpdateTriangleContacts();
|
||||
|
||||
// Update contacts
|
||||
void UpdateContacts();
|
||||
|
||||
// Solve
|
||||
void Solve(float32 dt, const b3Vec3& gravity);
|
||||
void Solve(float32 dt, const b3Vec3& gravity, u32 velocityIterations, u32 positionIterations);
|
||||
|
||||
// Stack allocator
|
||||
b3StackAllocator m_stackAllocator;
|
||||
|
||||
// The world attached to this cloth
|
||||
b3World* m_world;
|
||||
|
||||
// Gravity acceleration
|
||||
b3Vec3 m_gravity;
|
||||
|
||||
// Proxy mesh
|
||||
const b3ClothMesh* m_mesh;
|
||||
|
||||
// Vertex particles
|
||||
b3Particle** m_vertexParticles;
|
||||
// Particles
|
||||
b3Particle** m_particles;
|
||||
|
||||
// Triangles
|
||||
b3ClothTriangle* m_triangles;
|
||||
|
||||
// Cloth density
|
||||
float32 m_density;
|
||||
@ -173,38 +196,26 @@ private:
|
||||
// Pool of particles
|
||||
b3BlockPool m_particleBlocks;
|
||||
|
||||
// Pool of body contacts
|
||||
b3BlockPool m_bodyContactBlocks;
|
||||
|
||||
// Pool of particle contacts
|
||||
b3BlockPool m_particleContactBlocks;
|
||||
|
||||
// Pool of triangle contacts
|
||||
b3BlockPool m_triangleContactBlocks;
|
||||
|
||||
// List of particles
|
||||
b3List2<b3Particle> m_particleList;
|
||||
|
||||
|
||||
// List of forces
|
||||
b3List2<b3Force> m_forceList;
|
||||
|
||||
// List of particle contacts
|
||||
b3List2<b3BodyContact> m_bodyContactList;
|
||||
|
||||
// List of particle contacts
|
||||
b3List2<b3ParticleContact> m_particleContactList;
|
||||
|
||||
// List of triangle contacts
|
||||
b3List2<b3TriangleContact> m_triangleContactList;
|
||||
|
||||
// The parent world of this cloth.
|
||||
b3World* m_world;
|
||||
|
||||
// Links to the world cloth list.
|
||||
b3Cloth* m_prev;
|
||||
b3Cloth* m_next;
|
||||
// Contact manager
|
||||
b3ClothContactManager m_contactManager;
|
||||
};
|
||||
|
||||
inline void b3Cloth::SetGravity(const b3Vec3& gravity)
|
||||
{
|
||||
m_gravity = gravity;
|
||||
}
|
||||
|
||||
inline b3Vec3 b3Cloth::GetGravity() const
|
||||
{
|
||||
return m_gravity;
|
||||
}
|
||||
|
||||
inline const b3World* b3Cloth::GetWorld() const
|
||||
{
|
||||
return m_world;
|
||||
@ -230,14 +241,4 @@ inline const b3List2<b3Force>& b3Cloth::GetForceList() const
|
||||
return m_forceList;
|
||||
}
|
||||
|
||||
inline const b3Cloth* b3Cloth::GetNext() const
|
||||
{
|
||||
return m_next;
|
||||
}
|
||||
|
||||
inline b3Cloth* b3Cloth::GetNext()
|
||||
{
|
||||
return m_next;
|
||||
}
|
||||
|
||||
#endif
|
38
include/bounce/cloth/cloth_collision.h
Normal file
38
include/bounce/cloth/cloth_collision.h
Normal file
@ -0,0 +1,38 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
* arising from the use of this software.
|
||||
* Permission is granted to anyone to use this software for any purpose,
|
||||
* including commercial applications, and to alter it and redistribute it
|
||||
* freely, subject to the following restrictions:
|
||||
* 1. The origin of this software must not be misrepresented; you must not
|
||||
* claim that you wrote the original software. If you use this software
|
||||
* in a product, an acknowledgment in the product documentation would be
|
||||
* appreciated but is not required.
|
||||
* 2. Altered source versions must be plainly marked as such, and must not be
|
||||
* misrepresented as being the original software.
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef B3_CLOTH_COLLISION_H
|
||||
#define B3_CLOTH_COLLISION_H
|
||||
|
||||
#include <bounce/common/math/vec3.h>
|
||||
|
||||
// Cloth primitive type
|
||||
enum b3ClothAABBProxyType
|
||||
{
|
||||
e_particleProxy,
|
||||
e_triangleProxy
|
||||
};
|
||||
|
||||
// Cloth primitive broadphase proxy
|
||||
struct b3ClothAABBProxy
|
||||
{
|
||||
b3ClothAABBProxyType type;
|
||||
void* owner;
|
||||
};
|
||||
|
||||
#endif
|
63
include/bounce/cloth/cloth_contact_manager.h
Normal file
63
include/bounce/cloth/cloth_contact_manager.h
Normal file
@ -0,0 +1,63 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
* arising from the use of this software.
|
||||
* Permission is granted to anyone to use this software for any purpose,
|
||||
* including commercial applications, and to alter it and redistribute it
|
||||
* freely, subject to the following restrictions:
|
||||
* 1. The origin of this software must not be misrepresented; you must not
|
||||
* claim that you wrote the original software. If you use this software
|
||||
* in a product, an acknowledgment in the product documentation would be
|
||||
* appreciated but is not required.
|
||||
* 2. Altered source versions must be plainly marked as such, and must not be
|
||||
* misrepresented as being the original software.
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef B3_CLOTH_CONTACT_MANAGER_H
|
||||
#define B3_CLOTH_CONTACT_MANAGER_H
|
||||
|
||||
#include <bounce/cloth/contacts/cloth_particle_body_contact.h>
|
||||
#include <bounce/cloth/contacts/cloth_particle_triangle_contact.h>
|
||||
#include <bounce/collision/broad_phase.h>
|
||||
#include <bounce/common/memory/block_pool.h>
|
||||
#include <bounce/common/template/list.h>
|
||||
|
||||
class b3Cloth;
|
||||
|
||||
// Contact delegator for b3Cloth.
|
||||
class b3ClothContactManager
|
||||
{
|
||||
public:
|
||||
b3ClothContactManager();
|
||||
|
||||
void FindNewContacts();
|
||||
|
||||
void AddPair(void* data1, void* data2);
|
||||
void FindNewClothContacts();
|
||||
|
||||
void AddPSPair(b3Particle* p1, b3Shape* s2);
|
||||
void FindNewBodyContacts();
|
||||
|
||||
void UpdateContacts();
|
||||
void UpdateClothContacts();
|
||||
void UpdateBodyContacts();
|
||||
|
||||
b3ParticleTriangleContact* CreateParticleTriangleContact();
|
||||
void Destroy(b3ParticleTriangleContact* c);
|
||||
|
||||
b3ParticleBodyContact* CreateParticleBodyContact();
|
||||
void Destroy(b3ParticleBodyContact* c);
|
||||
|
||||
b3BlockPool m_particleTriangleContactBlocks;
|
||||
b3BlockPool m_particleBodyContactBlocks;
|
||||
|
||||
b3Cloth* m_cloth;
|
||||
b3BroadPhase m_broadPhase;
|
||||
b3List2<b3ParticleTriangleContact> m_particleTriangleContactList;
|
||||
b3List2<b3ParticleBodyContact> m_particleBodyContactList;
|
||||
};
|
||||
|
||||
#endif
|
77
include/bounce/cloth/cloth_force_solver.h
Normal file
77
include/bounce/cloth/cloth_force_solver.h
Normal file
@ -0,0 +1,77 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
* arising from the use of this software.
|
||||
* Permission is granted to anyone to use this software for any purpose,
|
||||
* including commercial applications, and to alter it and redistribute it
|
||||
* freely, subject to the following restrictions:
|
||||
* 1. The origin of this software must not be misrepresented; you must not
|
||||
* claim that you wrote the original software. If you use this software
|
||||
* in a product, an acknowledgment in the product documentation would be
|
||||
* appreciated but is not required.
|
||||
* 2. Altered source versions must be plainly marked as such, and must not be
|
||||
* misrepresented as being the original software.
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef B3_CLOTH_FORCE_SOLVER_H
|
||||
#define B3_CLOTH_FORCE_SOLVER_H
|
||||
|
||||
#include <bounce/common/math/mat22.h>
|
||||
#include <bounce/common/math/mat33.h>
|
||||
|
||||
class b3StackAllocator;
|
||||
|
||||
class b3Particle;
|
||||
class b3Force;
|
||||
|
||||
struct b3DenseVec3;
|
||||
struct b3DiagMat33;
|
||||
struct b3SparseMat33;
|
||||
struct b3SparseMat33View;
|
||||
|
||||
struct b3ClothForceSolverDef
|
||||
{
|
||||
b3StackAllocator* stack;
|
||||
u32 particleCount;
|
||||
b3Particle** particles;
|
||||
u32 forceCount;
|
||||
b3Force** forces;
|
||||
};
|
||||
|
||||
struct b3ClothForceSolverData
|
||||
{
|
||||
b3DenseVec3* x;
|
||||
b3DenseVec3* v;
|
||||
b3DenseVec3* f;
|
||||
b3DenseVec3* y;
|
||||
b3SparseMat33* dfdx;
|
||||
b3SparseMat33* dfdv;
|
||||
b3DiagMat33* S;
|
||||
b3DenseVec3* z;
|
||||
};
|
||||
|
||||
class b3ClothForceSolver
|
||||
{
|
||||
public:
|
||||
b3ClothForceSolver(const b3ClothForceSolverDef& def);
|
||||
~b3ClothForceSolver();
|
||||
|
||||
void Solve(float32 dt, const b3Vec3& gravity);
|
||||
private:
|
||||
void ApplyForces();
|
||||
|
||||
b3StackAllocator* m_allocator;
|
||||
|
||||
u32 m_particleCount;
|
||||
b3Particle** m_particles;
|
||||
|
||||
u32 m_forceCount;
|
||||
b3Force** m_forces;
|
||||
|
||||
b3ClothForceSolverData m_solverData;
|
||||
};
|
||||
|
||||
#endif
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -19,7 +19,6 @@
|
||||
#ifndef B3_CLOTH_MESH_H
|
||||
#define B3_CLOTH_MESH_H
|
||||
|
||||
#include <bounce/common/math/vec2.h>
|
||||
#include <bounce/common/math/vec3.h>
|
||||
|
||||
struct b3ClothMeshTriangle
|
||||
@ -53,16 +52,4 @@ struct b3ClothMesh
|
||||
b3ClothMeshSewingLine* sewingLines;
|
||||
};
|
||||
|
||||
struct b3GarmentMesh;
|
||||
|
||||
// Convenience structure.
|
||||
struct b3GarmentClothMesh : public b3ClothMesh
|
||||
{
|
||||
b3GarmentClothMesh();
|
||||
~b3GarmentClothMesh();
|
||||
|
||||
// Set this mesh from a 2D garment mesh.
|
||||
void Set(const b3GarmentMesh* garment);
|
||||
};
|
||||
|
||||
#endif
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -25,16 +25,9 @@
|
||||
class b3StackAllocator;
|
||||
|
||||
class b3Particle;
|
||||
class b3Body;
|
||||
class b3Force;
|
||||
|
||||
struct b3DenseVec3;
|
||||
struct b3DiagMat33;
|
||||
struct b3SparseSymMat33;
|
||||
|
||||
class b3BodyContact;
|
||||
class b3ParticleContact;
|
||||
class b3TriangleContact;
|
||||
class b3ParticleBodyContact;
|
||||
class b3ParticleTriangleContact;
|
||||
|
||||
struct b3ClothSolverDef
|
||||
{
|
||||
@ -42,33 +35,9 @@ struct b3ClothSolverDef
|
||||
u32 particleCapacity;
|
||||
u32 forceCapacity;
|
||||
u32 bodyContactCapacity;
|
||||
u32 particleContactCapacity;
|
||||
u32 triangleContactCapacity;
|
||||
};
|
||||
|
||||
struct b3ClothSolverData
|
||||
{
|
||||
b3DenseVec3* x;
|
||||
b3DenseVec3* v;
|
||||
b3DenseVec3* f;
|
||||
b3DenseVec3* y;
|
||||
b3SparseSymMat33* dfdx;
|
||||
b3SparseSymMat33* dfdv;
|
||||
b3DiagMat33* S;
|
||||
b3DenseVec3* z;
|
||||
float32 dt;
|
||||
float32 invdt;
|
||||
};
|
||||
|
||||
struct b3AccelerationConstraint
|
||||
{
|
||||
u32 i1;
|
||||
u32 ndof;
|
||||
b3Vec3 p, q, z;
|
||||
|
||||
void Apply(const b3ClothSolverData* data);
|
||||
};
|
||||
|
||||
class b3ClothSolver
|
||||
{
|
||||
public:
|
||||
@ -77,21 +46,11 @@ public:
|
||||
|
||||
void Add(b3Particle* p);
|
||||
void Add(b3Force* f);
|
||||
void Add(b3BodyContact* c);
|
||||
void Add(b3ParticleContact* c);
|
||||
void Add(b3TriangleContact* c);
|
||||
void Add(b3ParticleBodyContact* c);
|
||||
void Add(b3ParticleTriangleContact* c);
|
||||
|
||||
void Solve(float32 dt, const b3Vec3& gravity);
|
||||
void Solve(float32 dt, const b3Vec3& gravity, u32 velocityIterations, u32 positionIterations);
|
||||
private:
|
||||
// Apply forces.
|
||||
void ApplyForces();
|
||||
|
||||
// Apply constraints.
|
||||
void ApplyConstraints();
|
||||
|
||||
// Solve Ax = b.
|
||||
void Solve(b3DenseVec3& x, u32& iterations, const b3SparseSymMat33& A, const b3DenseVec3& b, const b3DiagMat33& S, const b3DenseVec3& z, const b3DenseVec3& y) const;
|
||||
|
||||
b3StackAllocator* m_allocator;
|
||||
|
||||
u32 m_particleCapacity;
|
||||
@ -101,24 +60,14 @@ private:
|
||||
u32 m_forceCapacity;
|
||||
u32 m_forceCount;
|
||||
b3Force** m_forces;
|
||||
|
||||
u32 m_constraintCapacity;
|
||||
u32 m_constraintCount;
|
||||
b3AccelerationConstraint* m_constraints;
|
||||
|
||||
|
||||
u32 m_bodyContactCapacity;
|
||||
u32 m_bodyContactCount;
|
||||
b3BodyContact** m_bodyContacts;
|
||||
b3ParticleBodyContact** m_bodyContacts;
|
||||
|
||||
u32 m_particleContactCapacity;
|
||||
u32 m_particleContactCount;
|
||||
b3ParticleContact** m_particleContacts;
|
||||
|
||||
u32 m_triangleContactCapacity;
|
||||
u32 m_triangleContactCount;
|
||||
b3TriangleContact** m_triangleContacts;
|
||||
|
||||
b3ClothSolverData m_solverData;
|
||||
b3ParticleTriangleContact** m_triangleContacts;
|
||||
};
|
||||
|
||||
#endif
|
112
include/bounce/cloth/cloth_triangle.h
Normal file
112
include/bounce/cloth/cloth_triangle.h
Normal file
@ -0,0 +1,112 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
* arising from the use of this software.
|
||||
* Permission is granted to anyone to use this software for any purpose,
|
||||
* including commercial applications, and to alter it and redistribute it
|
||||
* freely, subject to the following restrictions:
|
||||
* 1. The origin of this software must not be misrepresented; you must not
|
||||
* claim that you wrote the original software. If you use this software
|
||||
* in a product, an acknowledgment in the product documentation would be
|
||||
* appreciated but is not required.
|
||||
* 2. Altered source versions must be plainly marked as such, and must not be
|
||||
* misrepresented as being the original software.
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef B3_CLOTH_TRIANGLE_H
|
||||
#define B3_CLOTH_TRIANGLE_H
|
||||
|
||||
#include <bounce/cloth/cloth_collision.h>
|
||||
|
||||
// A cloth triangle
|
||||
class b3ClothTriangle
|
||||
{
|
||||
public:
|
||||
// Return the triangle index.
|
||||
u32 GetTriangle() const;
|
||||
|
||||
// Set the triangle radius.
|
||||
void SetRadius(float32 radius);
|
||||
|
||||
// Return the triangle radius.
|
||||
float32 GetRadius() const;
|
||||
|
||||
// Set the triangle coefficient of friction.
|
||||
void SetFriction(float32 friction);
|
||||
|
||||
// Return the triangle coefficient of friction.
|
||||
float32 GetFriction() const;
|
||||
private:
|
||||
friend class b3Cloth;
|
||||
friend class b3Particle;
|
||||
friend class b3ShearForce;
|
||||
friend class b3StrechForce;
|
||||
friend class b3MouseForce;
|
||||
friend class b3ClothContactManager;
|
||||
friend class b3ParticleTriangleContact;
|
||||
friend class b3ClothSolver;
|
||||
friend class b3ClothContactSolver;
|
||||
|
||||
b3ClothTriangle() { }
|
||||
~b3ClothTriangle() { }
|
||||
|
||||
// Synchronize AABB
|
||||
void Synchronize(const b3Vec3& displacement);
|
||||
|
||||
// Cloth
|
||||
b3Cloth* m_cloth;
|
||||
|
||||
// Triangle index
|
||||
u32 m_triangle;
|
||||
|
||||
// Radius
|
||||
float32 m_radius;
|
||||
|
||||
// Coefficient of friction
|
||||
float32 m_friction;
|
||||
|
||||
// AABB Proxy
|
||||
b3ClothAABBProxy m_aabbProxy;
|
||||
|
||||
// Broadphase ID
|
||||
u32 m_broadPhaseId;
|
||||
|
||||
// Alpha
|
||||
float32 m_alpha;
|
||||
|
||||
// Strech matrix
|
||||
float32 m_du1, m_dv1;
|
||||
float32 m_du2, m_dv2;
|
||||
float32 m_inv_det;
|
||||
};
|
||||
|
||||
inline u32 b3ClothTriangle::GetTriangle() const
|
||||
{
|
||||
return m_triangle;
|
||||
}
|
||||
|
||||
inline void b3ClothTriangle::SetRadius(float32 radius)
|
||||
{
|
||||
m_radius = radius;
|
||||
Synchronize(b3Vec3_zero);
|
||||
}
|
||||
|
||||
inline float32 b3ClothTriangle::GetRadius() const
|
||||
{
|
||||
return m_radius;
|
||||
}
|
||||
|
||||
inline void b3ClothTriangle::SetFriction(float32 friction)
|
||||
{
|
||||
m_friction = friction;
|
||||
}
|
||||
|
||||
inline float32 b3ClothTriangle::GetFriction() const
|
||||
{
|
||||
return m_friction;
|
||||
}
|
||||
|
||||
#endif
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -27,11 +27,8 @@ class b3StackAllocator;
|
||||
class b3Particle;
|
||||
class b3Body;
|
||||
|
||||
class b3BodyContact;
|
||||
class b3ParticleContact;
|
||||
class b3TriangleContact;
|
||||
|
||||
struct b3DenseVec3;
|
||||
class b3ParticleBodyContact;
|
||||
class b3ParticleTriangleContact;
|
||||
|
||||
struct b3ClothSolverBodyContactVelocityConstraint
|
||||
{
|
||||
@ -77,44 +74,11 @@ struct b3ClothSolverBodyContactPositionConstraint
|
||||
b3Vec3 rA;
|
||||
b3Vec3 rB;
|
||||
|
||||
b3Vec3 normalA;
|
||||
b3Vec3 localPointA;
|
||||
b3Vec3 localPointB;
|
||||
};
|
||||
|
||||
struct b3ClothSolverParticleContactVelocityConstraint
|
||||
{
|
||||
u32 indexA;
|
||||
float32 invMassA;
|
||||
|
||||
u32 indexB;
|
||||
float32 invMassB;
|
||||
|
||||
float32 friction;
|
||||
|
||||
b3Vec3 point;
|
||||
|
||||
b3Vec3 normal;
|
||||
float32 normalMass;
|
||||
float32 normalImpulse;
|
||||
float32 velocityBias;
|
||||
|
||||
b3Vec3 tangent1;
|
||||
b3Vec3 tangent2;
|
||||
b3Mat22 tangentMass;
|
||||
b3Vec2 tangentImpulse;
|
||||
};
|
||||
|
||||
struct b3ClothSolverParticleContactPositionConstraint
|
||||
{
|
||||
u32 indexA;
|
||||
float32 invMassA;
|
||||
float32 radiusA;
|
||||
|
||||
u32 indexB;
|
||||
float32 invMassB;
|
||||
float32 radiusB;
|
||||
};
|
||||
|
||||
struct b3ClothSolverTriangleContactVelocityConstraint
|
||||
{
|
||||
u32 indexA;
|
||||
@ -126,14 +90,21 @@ struct b3ClothSolverTriangleContactVelocityConstraint
|
||||
float32 invMassC;
|
||||
u32 indexD;
|
||||
float32 invMassD;
|
||||
|
||||
float32 wB, wC, wD;
|
||||
|
||||
b3Vec3 JA;
|
||||
b3Vec3 JB;
|
||||
b3Vec3 JC;
|
||||
b3Vec3 JD;
|
||||
|
||||
b3Vec3 normal;
|
||||
float32 normalMass;
|
||||
float32 normalImpulse;
|
||||
|
||||
float32 friction;
|
||||
|
||||
b3Vec3 tangent1;
|
||||
b3Vec3 tangent2;
|
||||
float32 tangentMass1;
|
||||
float32 tangentMass2;
|
||||
float32 tangentImpulse1;
|
||||
float32 tangentImpulse2;
|
||||
};
|
||||
|
||||
struct b3ClothSolverTriangleContactPositionConstraint
|
||||
@ -150,24 +121,21 @@ struct b3ClothSolverTriangleContactPositionConstraint
|
||||
float32 invMassD;
|
||||
float32 triangleRadius;
|
||||
|
||||
bool front;
|
||||
float32 wB, wC, wD;
|
||||
};
|
||||
|
||||
struct b3ClothContactSolverDef
|
||||
{
|
||||
b3StackAllocator* allocator;
|
||||
|
||||
b3DenseVec3* positions;
|
||||
b3DenseVec3* velocities;
|
||||
b3Vec3* positions;
|
||||
b3Vec3* velocities;
|
||||
|
||||
u32 bodyContactCount;
|
||||
b3BodyContact** bodyContacts;
|
||||
|
||||
u32 particleContactCount;
|
||||
b3ParticleContact** particleContacts;
|
||||
b3ParticleBodyContact** bodyContacts;
|
||||
|
||||
u32 triangleContactCount;
|
||||
b3TriangleContact** triangleContacts;
|
||||
b3ParticleTriangleContact** triangleContacts;
|
||||
};
|
||||
|
||||
inline float32 b3MixFriction(float32 u1, float32 u2)
|
||||
@ -182,45 +150,31 @@ public:
|
||||
~b3ClothContactSolver();
|
||||
|
||||
void InitializeBodyContactConstraints();
|
||||
|
||||
void InitializeParticleContactConstraints();
|
||||
|
||||
void InitializeTriangleContactConstraints();
|
||||
|
||||
void WarmStart();
|
||||
void WarmStartBodyContactConstraints();
|
||||
void WarmStartTriangleContactConstraints();
|
||||
|
||||
void SolveBodyContactVelocityConstraints();
|
||||
|
||||
void SolveParticleContactVelocityConstraints();
|
||||
|
||||
void SolveTriangleContactVelocityConstraints();
|
||||
|
||||
void StoreImpulses();
|
||||
|
||||
bool SolveBodyContactPositionConstraints();
|
||||
|
||||
bool SolveParticleContactPositionConstraints();
|
||||
|
||||
bool SolveTriangleContactPositionConstraints();
|
||||
|
||||
protected:
|
||||
b3StackAllocator* m_allocator;
|
||||
|
||||
b3DenseVec3* m_positions;
|
||||
b3DenseVec3* m_velocities;
|
||||
b3Vec3* m_positions;
|
||||
b3Vec3* m_velocities;
|
||||
|
||||
u32 m_bodyContactCount;
|
||||
b3BodyContact** m_bodyContacts;
|
||||
b3ParticleBodyContact** m_bodyContacts;
|
||||
b3ClothSolverBodyContactVelocityConstraint* m_bodyVelocityConstraints;
|
||||
b3ClothSolverBodyContactPositionConstraint* m_bodyPositionConstraints;
|
||||
|
||||
u32 m_particleContactCount;
|
||||
b3ParticleContact** m_particleContacts;
|
||||
b3ClothSolverParticleContactVelocityConstraint* m_particleVelocityConstraints;
|
||||
b3ClothSolverParticleContactPositionConstraint* m_particlePositionConstraints;
|
||||
|
||||
u32 m_triangleContactCount;
|
||||
b3TriangleContact** m_triangleContacts;
|
||||
b3ParticleTriangleContact** m_triangleContacts;
|
||||
b3ClothSolverTriangleContactVelocityConstraint* m_triangleVelocityConstraints;
|
||||
b3ClothSolverTriangleContactPositionConstraint* m_trianglePositionConstraints;
|
||||
};
|
76
include/bounce/cloth/contacts/cloth_particle_body_contact.h
Normal file
76
include/bounce/cloth/contacts/cloth_particle_body_contact.h
Normal file
@ -0,0 +1,76 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
* arising from the use of this software.
|
||||
* Permission is granted to anyone to use this software for any purpose,
|
||||
* including commercial applications, and to alter it and redistribute it
|
||||
* freely, subject to the following restrictions:
|
||||
* 1. The origin of this software must not be misrepresented; you must not
|
||||
* claim that you wrote the original software. If you use this software
|
||||
* in a product, an acknowledgment in the product documentation would be
|
||||
* appreciated but is not required.
|
||||
* 2. Altered source versions must be plainly marked as such, and must not be
|
||||
* misrepresented as being the original software.
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef B3_CLOTH_PARTICLE_BODY_CONTACT_H
|
||||
#define B3_CLOTH_PARTICLE_BODY_CONTACT_H
|
||||
|
||||
#include <bounce/common/template/list.h>
|
||||
#include <bounce/common/math/vec2.h>
|
||||
#include <bounce/common/math/vec3.h>
|
||||
#include <bounce/common/math/transform.h>
|
||||
|
||||
class b3Particle;
|
||||
class b3Shape;
|
||||
|
||||
// A contact between a particle and a body
|
||||
class b3ParticleBodyContact
|
||||
{
|
||||
public:
|
||||
private:
|
||||
friend class b3List2<b3ParticleBodyContact>;
|
||||
friend class b3Cloth;
|
||||
friend class b3Particle;
|
||||
friend class b3ClothContactManager;
|
||||
friend class b3ClothSolver;
|
||||
friend class b3ClothContactSolver;
|
||||
friend struct b3ParticleBodyContactWorldPoint;
|
||||
|
||||
b3ParticleBodyContact() { }
|
||||
~b3ParticleBodyContact() { }
|
||||
|
||||
void Update();
|
||||
|
||||
b3Particle* m_p1;
|
||||
b3Shape* m_s2;
|
||||
|
||||
bool m_active;
|
||||
|
||||
// Contact constraint
|
||||
b3Vec3 m_normal1;
|
||||
b3Vec3 m_localPoint1;
|
||||
b3Vec3 m_localPoint2;
|
||||
float32 m_normalImpulse;
|
||||
|
||||
// Friction constraint
|
||||
b3Vec3 m_tangent1, m_tangent2;
|
||||
b3Vec2 m_tangentImpulse;
|
||||
|
||||
b3ParticleBodyContact* m_prev;
|
||||
b3ParticleBodyContact* m_next;
|
||||
};
|
||||
|
||||
struct b3ParticleBodyContactWorldPoint
|
||||
{
|
||||
void Initialize(const b3ParticleBodyContact* c, float32 rA, const b3Transform& xfA, float32 rB, const b3Transform& xfB);
|
||||
|
||||
b3Vec3 point;
|
||||
b3Vec3 normal;
|
||||
float32 separation;
|
||||
};
|
||||
|
||||
#endif
|
@ -0,0 +1,65 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
* arising from the use of this software.
|
||||
* Permission is granted to anyone to use this software for any purpose,
|
||||
* including commercial applications, and to alter it and redistribute it
|
||||
* freely, subject to the following restrictions:
|
||||
* 1. The origin of this software must not be misrepresented; you must not
|
||||
* claim that you wrote the original software. If you use this software
|
||||
* in a product, an acknowledgment in the product documentation would be
|
||||
* appreciated but is not required.
|
||||
* 2. Altered source versions must be plainly marked as such, and must not be
|
||||
* misrepresented as being the original software.
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef B3_CLOTH_PARTICLE_TRIANGLE_CONTACT_H
|
||||
#define B3_CLOTH_PARTICLE_TRIANGLE_CONTACT_H
|
||||
|
||||
#include <bounce/common/template/list.h>
|
||||
|
||||
class b3Particle;
|
||||
class b3ClothTriangle;
|
||||
|
||||
// Contact between particle and a triangle
|
||||
class b3ParticleTriangleContact
|
||||
{
|
||||
public:
|
||||
private:
|
||||
friend class b3List2<b3ParticleTriangleContact>;
|
||||
friend class b3Cloth;
|
||||
friend class b3Particle;
|
||||
friend class b3ClothTriangle;
|
||||
friend class b3ClothContactManager;
|
||||
friend class b3ClothContactSolver;
|
||||
|
||||
b3ParticleTriangleContact() { }
|
||||
~b3ParticleTriangleContact() { }
|
||||
|
||||
void Update();
|
||||
|
||||
// Particle
|
||||
b3Particle* m_p1;
|
||||
|
||||
// Triangle
|
||||
b3ClothTriangle* m_t2;
|
||||
b3Particle* m_p2;
|
||||
b3Particle* m_p3;
|
||||
b3Particle* m_p4;
|
||||
|
||||
float32 m_w2, m_w3, m_w4;
|
||||
|
||||
float32 m_normalImpulse;
|
||||
float32 m_tangentImpulse1;
|
||||
float32 m_tangentImpulse2;
|
||||
|
||||
bool m_active;
|
||||
|
||||
b3ParticleTriangleContact* m_prev;
|
||||
b3ParticleTriangleContact* m_next;
|
||||
};
|
||||
|
||||
#endif
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -22,16 +22,17 @@
|
||||
#include <bounce/common/math/transform.h>
|
||||
#include <bounce/common/template/list.h>
|
||||
|
||||
struct b3ClothSolverData;
|
||||
struct b3ClothForceSolverData;
|
||||
|
||||
class b3Particle;
|
||||
|
||||
// Force types
|
||||
enum b3ForceType
|
||||
{
|
||||
e_frictionForce,
|
||||
e_strechForce,
|
||||
e_shearForce,
|
||||
e_springForce,
|
||||
e_bendForce,
|
||||
e_mouseForce,
|
||||
};
|
||||
|
||||
struct b3ForceDef
|
||||
@ -48,10 +49,13 @@ public:
|
||||
|
||||
//
|
||||
b3Force* GetNext();
|
||||
|
||||
//
|
||||
virtual bool HasParticle(const b3Particle* particle) const = 0;
|
||||
protected:
|
||||
friend class b3List2<b3Force>;
|
||||
friend class b3Cloth;
|
||||
friend class b3ClothSolver;
|
||||
friend class b3ClothForceSolver;
|
||||
friend class b3Particle;
|
||||
|
||||
static b3Force* Create(const b3ForceDef* def);
|
||||
@ -60,7 +64,7 @@ protected:
|
||||
b3Force() { }
|
||||
virtual ~b3Force() { }
|
||||
|
||||
virtual void Apply(const b3ClothSolverData* data) = 0;
|
||||
virtual void Apply(const b3ClothForceSolverData* data) = 0;
|
||||
|
||||
// Force type
|
||||
b3ForceType m_type;
|
140
include/bounce/cloth/forces/mouse_force.h
Normal file
140
include/bounce/cloth/forces/mouse_force.h
Normal file
@ -0,0 +1,140 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
* arising from the use of this software.
|
||||
* Permission is granted to anyone to use this software for any purpose,
|
||||
* including commercial applications, and to alter it and redistribute it
|
||||
* freely, subject to the following restrictions:
|
||||
* 1. The origin of this software must not be misrepresented; you must not
|
||||
* claim that you wrote the original software. If you use this software
|
||||
* in a product, an acknowledgment in the product documentation would be
|
||||
* appreciated but is not required.
|
||||
* 2. Altered source versions must be plainly marked as such, and must not be
|
||||
* misrepresented as being the original software.
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef B3_MOUSE_FORCE_H
|
||||
#define B3_MOUSE_FORCE_H
|
||||
|
||||
#include <bounce/cloth/forces/force.h>
|
||||
|
||||
class b3ClothTriangle;
|
||||
|
||||
struct b3MouseForceDef : public b3ForceDef
|
||||
{
|
||||
b3MouseForceDef()
|
||||
{
|
||||
type = e_mouseForce;
|
||||
}
|
||||
|
||||
// Particle
|
||||
b3Particle* particle;
|
||||
|
||||
// Triangle
|
||||
b3ClothTriangle* triangle;
|
||||
|
||||
// Barycentric coordinates on triangle
|
||||
float32 w2, w3, w4;
|
||||
|
||||
// Mouse stiffness
|
||||
float32 mouse;
|
||||
|
||||
// Damping stiffness
|
||||
float32 damping;
|
||||
};
|
||||
|
||||
// Mouse force acting on a particle and triangle.
|
||||
class b3MouseForce : public b3Force
|
||||
{
|
||||
public:
|
||||
bool HasParticle(const b3Particle* particle) const;
|
||||
|
||||
b3Particle* GetParticle() const;
|
||||
|
||||
b3ClothTriangle* GetTriangle() const;
|
||||
|
||||
float32 GetMouseStiffness() const;
|
||||
|
||||
float32 GetDampingStiffness() const;
|
||||
|
||||
b3Vec3 GetActionForce1() const;
|
||||
|
||||
b3Vec3 GetActionForce2() const;
|
||||
|
||||
b3Vec3 GetActionForce3() const;
|
||||
|
||||
b3Vec3 GetActionForce4() const;
|
||||
private:
|
||||
friend class b3Force;
|
||||
friend class b3Cloth;
|
||||
|
||||
b3MouseForce(const b3MouseForceDef* def);
|
||||
~b3MouseForce();
|
||||
|
||||
void Apply(const b3ClothForceSolverData* data);
|
||||
|
||||
// Solver shared
|
||||
|
||||
// Particle
|
||||
b3Particle* m_particle;
|
||||
|
||||
// Triangle
|
||||
b3ClothTriangle* m_triangle;
|
||||
|
||||
// Barycentric coordinates
|
||||
float32 m_w2, m_w3, m_w4;
|
||||
|
||||
// Mouse stiffness
|
||||
float32 m_km;
|
||||
|
||||
// Damping stiffness
|
||||
float32 m_kd;
|
||||
|
||||
// Action forces
|
||||
b3Vec3 m_f1, m_f2, m_f3, m_f4;
|
||||
};
|
||||
|
||||
inline b3Particle* b3MouseForce::GetParticle() const
|
||||
{
|
||||
return m_particle;
|
||||
}
|
||||
|
||||
inline b3ClothTriangle* b3MouseForce::GetTriangle() const
|
||||
{
|
||||
return m_triangle;
|
||||
}
|
||||
|
||||
inline float32 b3MouseForce::GetMouseStiffness() const
|
||||
{
|
||||
return m_km;
|
||||
}
|
||||
|
||||
inline float32 b3MouseForce::GetDampingStiffness() const
|
||||
{
|
||||
return m_kd;
|
||||
}
|
||||
|
||||
inline b3Vec3 b3MouseForce::GetActionForce1() const
|
||||
{
|
||||
return m_f1;
|
||||
}
|
||||
|
||||
inline b3Vec3 b3MouseForce::GetActionForce2() const
|
||||
{
|
||||
return m_f2;
|
||||
}
|
||||
|
||||
inline b3Vec3 b3MouseForce::GetActionForce3() const
|
||||
{
|
||||
return m_f3;
|
||||
}
|
||||
|
||||
inline b3Vec3 b3MouseForce::GetActionForce4() const
|
||||
{
|
||||
return m_f4;
|
||||
}
|
||||
|
||||
#endif
|
114
include/bounce/cloth/forces/shear_force.h
Normal file
114
include/bounce/cloth/forces/shear_force.h
Normal file
@ -0,0 +1,114 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
* arising from the use of this software.
|
||||
* Permission is granted to anyone to use this software for any purpose,
|
||||
* including commercial applications, and to alter it and redistribute it
|
||||
* freely, subject to the following restrictions:
|
||||
* 1. The origin of this software must not be misrepresented; you must not
|
||||
* claim that you wrote the original software. If you use this software
|
||||
* in a product, an acknowledgment in the product documentation would be
|
||||
* appreciated but is not required.
|
||||
* 2. Altered source versions must be plainly marked as such, and must not be
|
||||
* misrepresented as being the original software.
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef B3_SHEAR_FORCE_H
|
||||
#define B3_SHEAR_FORCE_H
|
||||
|
||||
#include <bounce/cloth/forces/force.h>
|
||||
|
||||
class b3ClothTriangle;
|
||||
|
||||
struct b3ShearForceDef : public b3ForceDef
|
||||
{
|
||||
b3ShearForceDef()
|
||||
{
|
||||
type = e_shearForce;
|
||||
}
|
||||
|
||||
// Triangle
|
||||
b3ClothTriangle* triangle;
|
||||
|
||||
// Shearing stiffness
|
||||
float32 shearing;
|
||||
|
||||
// Damping stiffness
|
||||
float32 damping;
|
||||
};
|
||||
|
||||
// Shear force acting on a cloth triangle.
|
||||
class b3ShearForce : public b3Force
|
||||
{
|
||||
public:
|
||||
bool HasParticle(const b3Particle* particle) const;
|
||||
|
||||
b3ClothTriangle* GetTriangle() const;
|
||||
|
||||
float32 GetShearingStiffness() const;
|
||||
|
||||
float32 GetDampingStiffness() const;
|
||||
|
||||
b3Vec3 GetActionForce1() const;
|
||||
|
||||
b3Vec3 GetActionForce2() const;
|
||||
|
||||
b3Vec3 GetActionForce3() const;
|
||||
private:
|
||||
friend class b3Force;
|
||||
friend class b3Cloth;
|
||||
|
||||
b3ShearForce(const b3ShearForceDef* def);
|
||||
~b3ShearForce();
|
||||
|
||||
void Apply(const b3ClothForceSolverData* data);
|
||||
|
||||
// Solver shared
|
||||
|
||||
// Triangle
|
||||
b3ClothTriangle* m_triangle;
|
||||
|
||||
// Shearing stiffness
|
||||
float32 m_ks;
|
||||
|
||||
// Damping stiffness
|
||||
float32 m_kd;
|
||||
|
||||
// Action forces
|
||||
b3Vec3 m_f1, m_f2, m_f3;
|
||||
};
|
||||
|
||||
inline b3ClothTriangle* b3ShearForce::GetTriangle() const
|
||||
{
|
||||
return m_triangle;
|
||||
}
|
||||
|
||||
inline float32 b3ShearForce::GetShearingStiffness() const
|
||||
{
|
||||
return m_ks;
|
||||
}
|
||||
|
||||
inline float32 b3ShearForce::GetDampingStiffness() const
|
||||
{
|
||||
return m_kd;
|
||||
}
|
||||
|
||||
inline b3Vec3 b3ShearForce::GetActionForce1() const
|
||||
{
|
||||
return m_f1;
|
||||
}
|
||||
|
||||
inline b3Vec3 b3ShearForce::GetActionForce2() const
|
||||
{
|
||||
return m_f2;
|
||||
}
|
||||
|
||||
inline b3Vec3 b3ShearForce::GetActionForce3() const
|
||||
{
|
||||
return m_f3;
|
||||
}
|
||||
|
||||
#endif
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -19,7 +19,7 @@
|
||||
#ifndef B3_SPRING_FORCE_H
|
||||
#define B3_SPRING_FORCE_H
|
||||
|
||||
#include <bounce/dynamics/cloth/force.h>
|
||||
#include <bounce/cloth/forces/force.h>
|
||||
|
||||
struct b3SpringForceDef : public b3ForceDef
|
||||
{
|
||||
@ -67,6 +67,8 @@ public:
|
||||
float32 GetDampingStiffness() const;
|
||||
|
||||
b3Vec3 GetActionForce() const;
|
||||
|
||||
bool HasParticle(const b3Particle* particle) const;
|
||||
private:
|
||||
friend class b3Force;
|
||||
friend class b3Cloth;
|
||||
@ -74,7 +76,7 @@ private:
|
||||
b3SpringForce(const b3SpringForceDef* def);
|
||||
~b3SpringForce();
|
||||
|
||||
void Apply(const b3ClothSolverData* data);
|
||||
void Apply(const b3ClothForceSolverData* data);
|
||||
|
||||
// Solver shared
|
||||
|
||||
@ -127,4 +129,9 @@ inline b3Vec3 b3SpringForce::GetActionForce() const
|
||||
return m_f;
|
||||
}
|
||||
|
||||
inline bool b3SpringForce::HasParticle(const b3Particle* particle) const
|
||||
{
|
||||
return m_p1 == particle || m_p2 == particle;
|
||||
}
|
||||
|
||||
#endif
|
126
include/bounce/cloth/forces/strech_force.h
Normal file
126
include/bounce/cloth/forces/strech_force.h
Normal file
@ -0,0 +1,126 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
* arising from the use of this software.
|
||||
* Permission is granted to anyone to use this software for any purpose,
|
||||
* including commercial applications, and to alter it and redistribute it
|
||||
* freely, subject to the following restrictions:
|
||||
* 1. The origin of this software must not be misrepresented; you must not
|
||||
* claim that you wrote the original software. If you use this software
|
||||
* in a product, an acknowledgment in the product documentation would be
|
||||
* appreciated but is not required.
|
||||
* 2. Altered source versions must be plainly marked as such, and must not be
|
||||
* misrepresented as being the original software.
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef B3_STRECH_FORCE_H
|
||||
#define B3_STRECH_FORCE_H
|
||||
|
||||
#include <bounce/cloth/forces/force.h>
|
||||
|
||||
class b3ClothTriangle;
|
||||
|
||||
struct b3StrechForceDef : public b3ForceDef
|
||||
{
|
||||
b3StrechForceDef()
|
||||
{
|
||||
type = e_strechForce;
|
||||
}
|
||||
|
||||
// Triangle
|
||||
b3ClothTriangle* triangle;
|
||||
|
||||
// Streching stiffness
|
||||
float32 streching;
|
||||
|
||||
// Damping stiffness
|
||||
float32 damping;
|
||||
|
||||
// Desired strechiness in u direction
|
||||
float32 bu;
|
||||
|
||||
// Desired strechiness in v direction
|
||||
float32 bv;
|
||||
};
|
||||
|
||||
// Strech force acting on a cloth triangle.
|
||||
class b3StrechForce : public b3Force
|
||||
{
|
||||
public:
|
||||
bool HasParticle(const b3Particle* particle) const;
|
||||
|
||||
b3ClothTriangle* GetTriangle() const;
|
||||
|
||||
float32 GetStrechingStiffness() const;
|
||||
|
||||
float32 GetDampingStiffness() const;
|
||||
|
||||
b3Vec3 GetActionForce1() const;
|
||||
|
||||
b3Vec3 GetActionForce2() const;
|
||||
|
||||
b3Vec3 GetActionForce3() const;
|
||||
private:
|
||||
friend class b3Force;
|
||||
friend class b3Cloth;
|
||||
|
||||
b3StrechForce(const b3StrechForceDef* def);
|
||||
~b3StrechForce();
|
||||
|
||||
void Apply(const b3ClothForceSolverData* data);
|
||||
|
||||
// Solver shared
|
||||
|
||||
// Triangle
|
||||
b3ClothTriangle* m_triangle;
|
||||
|
||||
// Streching stiffness
|
||||
float32 m_ks;
|
||||
|
||||
// Damping stiffness
|
||||
float32 m_kd;
|
||||
|
||||
// Desired strechiness in u direction
|
||||
float32 m_bu;
|
||||
|
||||
// Desired strechiness in v direction
|
||||
float32 m_bv;
|
||||
|
||||
// Action forces
|
||||
b3Vec3 m_f1, m_f2, m_f3;
|
||||
};
|
||||
|
||||
inline b3ClothTriangle* b3StrechForce::GetTriangle() const
|
||||
{
|
||||
return m_triangle;
|
||||
}
|
||||
|
||||
inline float32 b3StrechForce::GetStrechingStiffness() const
|
||||
{
|
||||
return m_ks;
|
||||
}
|
||||
|
||||
inline float32 b3StrechForce::GetDampingStiffness() const
|
||||
{
|
||||
return m_kd;
|
||||
}
|
||||
|
||||
inline b3Vec3 b3StrechForce::GetActionForce1() const
|
||||
{
|
||||
return m_f1;
|
||||
}
|
||||
|
||||
inline b3Vec3 b3StrechForce::GetActionForce2() const
|
||||
{
|
||||
return m_f2;
|
||||
}
|
||||
|
||||
inline b3Vec3 b3StrechForce::GetActionForce3() const
|
||||
{
|
||||
return m_f3;
|
||||
}
|
||||
|
||||
#endif
|
72
include/bounce/cloth/garment/garment.h
Normal file
72
include/bounce/cloth/garment/garment.h
Normal file
@ -0,0 +1,72 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
* arising from the use of this software.
|
||||
* Permission is granted to anyone to use this software for any purpose,
|
||||
* including commercial applications, and to alter it and redistribute it
|
||||
* freely, subject to the following restrictions:
|
||||
* 1. The origin of this software must not be misrepresented; you must not
|
||||
* claim that you wrote the original software. If you use this software
|
||||
* in a product, an acknowledgment in the product documentation would be
|
||||
* appreciated but is not required.
|
||||
* 2. Altered source versions must be plainly marked as such, and must not be
|
||||
* misrepresented as being the original software.
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef B3_GARMENT_H
|
||||
#define B3_GARMENT_H
|
||||
|
||||
#include <bounce/cloth/garment/sewing_pattern.h>
|
||||
|
||||
struct b3SewingLine
|
||||
{
|
||||
u32 p1, p2;
|
||||
u32 v1, v2;
|
||||
};
|
||||
|
||||
struct b3Garment
|
||||
{
|
||||
u32 patternCount;
|
||||
b3SewingPattern** patterns;
|
||||
u32 sewingCount;
|
||||
b3SewingLine* sewingLines;
|
||||
};
|
||||
|
||||
struct b3RectangleGarment : public b3Garment
|
||||
{
|
||||
b3RectanglePattern rectangle;
|
||||
b3SewingPattern* rectanglePatterns[1];
|
||||
|
||||
b3RectangleGarment(float32 ex = 1.0f, float32 ey = 1.0f) : rectangle(ex, ey)
|
||||
{
|
||||
rectanglePatterns[0] = &rectangle;
|
||||
|
||||
patternCount = 1;
|
||||
patterns = rectanglePatterns;
|
||||
|
||||
sewingCount = 0;
|
||||
sewingLines = nullptr;
|
||||
}
|
||||
};
|
||||
|
||||
struct b3CircleGarment : public b3Garment
|
||||
{
|
||||
b3CirclePattern<> circle;
|
||||
b3SewingPattern* circlePatterns[1];
|
||||
|
||||
b3CircleGarment(float32 r = 1.0f) : circle(r)
|
||||
{
|
||||
circlePatterns[0] = &circle;
|
||||
|
||||
patternCount = 1;
|
||||
patterns = circlePatterns;
|
||||
|
||||
sewingCount = 0;
|
||||
sewingLines = nullptr;
|
||||
}
|
||||
};
|
||||
|
||||
#endif
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
37
include/bounce/cloth/garment_cloth_mesh.h
Normal file
37
include/bounce/cloth/garment_cloth_mesh.h
Normal file
@ -0,0 +1,37 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
* arising from the use of this software.
|
||||
* Permission is granted to anyone to use this software for any purpose,
|
||||
* including commercial applications, and to alter it and redistribute it
|
||||
* freely, subject to the following restrictions:
|
||||
* 1. The origin of this software must not be misrepresented; you must not
|
||||
* claim that you wrote the original software. If you use this software
|
||||
* in a product, an acknowledgment in the product documentation would be
|
||||
* appreciated but is not required.
|
||||
* 2. Altered source versions must be plainly marked as such, and must not be
|
||||
* misrepresented as being the original software.
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef B3_GARMENT_CLOTH_MESH_H
|
||||
#define B3_GARMENT_CLOTH_MESH_H
|
||||
|
||||
#include <bounce/cloth/cloth_mesh.h>
|
||||
|
||||
struct b3GarmentMesh;
|
||||
|
||||
// This mesh structure represents a cloth mesh that can be set from 2D a garment mesh.
|
||||
// The mesh is set in the xy plane (z = 0).
|
||||
struct b3GarmentClothMesh : public b3ClothMesh
|
||||
{
|
||||
b3GarmentClothMesh();
|
||||
~b3GarmentClothMesh();
|
||||
|
||||
// Set this mesh from a 2D garment mesh.
|
||||
void Set(const b3GarmentMesh* garment);
|
||||
};
|
||||
|
||||
#endif
|
96
include/bounce/cloth/grid_cloth_mesh.h
Normal file
96
include/bounce/cloth/grid_cloth_mesh.h
Normal file
@ -0,0 +1,96 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
* arising from the use of this software.
|
||||
* Permission is granted to anyone to use this software for any purpose,
|
||||
* including commercial applications, and to alter it and redistribute it
|
||||
* freely, subject to the following restrictions:
|
||||
* 1. The origin of this software must not be misrepresented; you must not
|
||||
* claim that you wrote the original software. If you use this software
|
||||
* in a product, an acknowledgment in the product documentation would be
|
||||
* appreciated but is not required.
|
||||
* 2. Altered source versions must be plainly marked as such, and must not be
|
||||
* misrepresented as being the original software.
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef B3_GRID_CLOTH_MESH_H
|
||||
#define B3_GRID_CLOTH_MESH_H
|
||||
|
||||
#include <bounce/cloth/cloth_mesh.h>
|
||||
|
||||
// A (H + 1) x (W + 1) grid mesh stored in row-major order.
|
||||
// v(i, j) = i + (W + 1) + j
|
||||
template<u32 W = 1, u32 H = 1>
|
||||
struct b3GridClothMesh : public b3ClothMesh
|
||||
{
|
||||
b3Vec3 gridVertices[(H + 1) * (W + 1)];
|
||||
b3ClothMeshTriangle gridTriangles[2 * H * W];
|
||||
b3ClothMeshMesh gridMesh;
|
||||
|
||||
// Set this grid to a W (width) per H (height) dimensioned grid centered at the origin and aligned
|
||||
// with the world x-z axes.
|
||||
b3GridClothMesh()
|
||||
{
|
||||
vertexCount = 0;
|
||||
for (u32 i = 0; i <= H; ++i)
|
||||
{
|
||||
for (u32 j = 0; j <= W; ++j)
|
||||
{
|
||||
gridVertices[vertexCount++].Set(float32(j), 0.0f, float32(i));
|
||||
}
|
||||
}
|
||||
|
||||
B3_ASSERT(vertexCount == (W + 1) * (H + 1));
|
||||
|
||||
b3Vec3 translation;
|
||||
translation.x = -0.5f * float32(W);
|
||||
translation.y = 0.0f;
|
||||
translation.z = -0.5f * float32(H);
|
||||
|
||||
for (u32 i = 0; i < vertexCount; ++i)
|
||||
{
|
||||
gridVertices[i] += translation;
|
||||
}
|
||||
|
||||
triangleCount = 0;
|
||||
for (u32 i = 0; i < H; ++i)
|
||||
{
|
||||
for (u32 j = 0; j < W; ++j)
|
||||
{
|
||||
u32 v1 = i * (W + 1) + j;
|
||||
u32 v2 = (i + 1) * (W + 1) + j;
|
||||
u32 v3 = (i + 1) * (W + 1) + (j + 1);
|
||||
u32 v4 = i * (W + 1) + (j + 1);
|
||||
|
||||
b3ClothMeshTriangle* t1 = gridTriangles + triangleCount++;
|
||||
t1->v1 = v3;
|
||||
t1->v2 = v2;
|
||||
t1->v3 = v1;
|
||||
|
||||
b3ClothMeshTriangle* t2 = gridTriangles + triangleCount++;
|
||||
t2->v1 = v1;
|
||||
t2->v2 = v4;
|
||||
t2->v3 = v3;
|
||||
}
|
||||
}
|
||||
|
||||
B3_ASSERT(triangleCount == 2 * H * W);
|
||||
|
||||
gridMesh.startTriangle = 0;
|
||||
gridMesh.triangleCount = triangleCount;
|
||||
gridMesh.startVertex = 0;
|
||||
gridMesh.vertexCount = vertexCount;
|
||||
|
||||
vertices = gridVertices;
|
||||
triangles = gridTriangles;
|
||||
meshCount = 1;
|
||||
meshes = &gridMesh;
|
||||
sewingLineCount = 0;
|
||||
sewingLines = nullptr;
|
||||
}
|
||||
};
|
||||
|
||||
#endif
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -19,14 +19,10 @@
|
||||
#ifndef B3_PARTICLE_H
|
||||
#define B3_PARTICLE_H
|
||||
|
||||
#include <bounce/common/math/transform.h>
|
||||
#include <bounce/cloth/cloth_collision.h>
|
||||
#include <bounce/common/template/list.h>
|
||||
#include <bounce/dynamics/cloth/force.h>
|
||||
#include <bounce/common/math/vec2.h>
|
||||
|
||||
class b3Shape;
|
||||
class b3Cloth;
|
||||
class b3Particle;
|
||||
|
||||
// Static particle: Can be moved manually.
|
||||
// Kinematic particle: Non-zero velocity, can be moved by the solver.
|
||||
@ -38,12 +34,13 @@ enum b3ParticleType
|
||||
e_dynamicParticle
|
||||
};
|
||||
|
||||
//
|
||||
// Particle definition
|
||||
struct b3ParticleDef
|
||||
{
|
||||
b3ParticleDef()
|
||||
{
|
||||
type = e_staticParticle;
|
||||
mass = 0.0f;
|
||||
position.SetZero();
|
||||
velocity.SetZero();
|
||||
force.SetZero();
|
||||
@ -53,6 +50,7 @@ struct b3ParticleDef
|
||||
}
|
||||
|
||||
b3ParticleType type;
|
||||
float32 mass;
|
||||
b3Vec3 position;
|
||||
b3Vec3 velocity;
|
||||
b3Vec3 force;
|
||||
@ -61,89 +59,6 @@ struct b3ParticleDef
|
||||
void* userData;
|
||||
};
|
||||
|
||||
// A contact between a particle and a solid
|
||||
class b3BodyContact
|
||||
{
|
||||
public:
|
||||
b3BodyContact() { }
|
||||
~b3BodyContact() { }
|
||||
|
||||
b3Particle* p1;
|
||||
b3Shape* s2;
|
||||
|
||||
// Contact constraint
|
||||
b3Vec3 localPoint1;
|
||||
b3Vec3 localPoint2;
|
||||
float32 normalImpulse;
|
||||
|
||||
// Friction constraint
|
||||
b3Vec3 t1, t2;
|
||||
b3Vec2 tangentImpulse;
|
||||
|
||||
b3BodyContact* m_prev;
|
||||
b3BodyContact* m_next;
|
||||
};
|
||||
|
||||
struct b3BodyContactWorldPoint
|
||||
{
|
||||
void Initialize(const b3BodyContact* c, float32 rA, const b3Transform& xfA, float32 rB, const b3Transform& xfB);
|
||||
|
||||
b3Vec3 point;
|
||||
b3Vec3 normal;
|
||||
float32 separation;
|
||||
};
|
||||
|
||||
// A contact between two particles
|
||||
class b3ParticleContact
|
||||
{
|
||||
public:
|
||||
b3ParticleContact() { }
|
||||
~b3ParticleContact() { }
|
||||
|
||||
b3Particle* p1;
|
||||
b3Particle* p2;
|
||||
|
||||
// Contact constraint
|
||||
float32 normalImpulse;
|
||||
|
||||
// Friction constraint
|
||||
b3Vec3 t1, t2;
|
||||
b3Vec2 tangentImpulse;
|
||||
|
||||
b3ParticleContact* m_prev;
|
||||
b3ParticleContact* m_next;
|
||||
};
|
||||
|
||||
struct b3ParticleContactWorldPoint
|
||||
{
|
||||
void Initialize(const b3ParticleContact* c);
|
||||
|
||||
b3Vec3 point;
|
||||
b3Vec3 normal;
|
||||
float32 separation;
|
||||
};
|
||||
|
||||
// A contact between a particle and a triangle
|
||||
class b3TriangleContact
|
||||
{
|
||||
public:
|
||||
b3TriangleContact() { }
|
||||
~b3TriangleContact() { }
|
||||
|
||||
b3Particle* p1;
|
||||
b3Particle* p2;
|
||||
b3Particle* p3;
|
||||
b3Particle* p4;
|
||||
|
||||
bool front;
|
||||
|
||||
// Contact constraint
|
||||
float32 normalImpulse;
|
||||
|
||||
b3TriangleContact* m_prev;
|
||||
b3TriangleContact* m_next;
|
||||
};
|
||||
|
||||
// A cloth particle.
|
||||
class b3Particle
|
||||
{
|
||||
@ -197,16 +112,31 @@ public:
|
||||
private:
|
||||
friend class b3List2<b3Particle>;
|
||||
friend class b3Cloth;
|
||||
friend class b3ClothContactManager;
|
||||
friend class b3ClothSolver;
|
||||
friend class b3ClothForceSolver;
|
||||
friend class b3ClothTriangle;
|
||||
friend class b3ParticleBodyContact;
|
||||
friend class b3ParticleTriangleContact;
|
||||
friend class b3ClothContactSolver;
|
||||
friend class b3Force;
|
||||
friend class b3StrechForce;
|
||||
friend class b3ShearForce;
|
||||
friend class b3SpringForce;
|
||||
friend class b3BendForce;
|
||||
friend class b3FrictionForce;
|
||||
friend class b3MouseForce;
|
||||
|
||||
b3Particle(const b3ParticleDef& def, b3Cloth* cloth);
|
||||
~b3Particle();
|
||||
|
||||
// Synchronize particle AABB
|
||||
void Synchronize(const b3Vec3& displacement);
|
||||
|
||||
// Synchronize triangles AABB
|
||||
void SynchronizeTriangles();
|
||||
|
||||
// Destroy contacts.
|
||||
void DestroyContacts();
|
||||
|
||||
// Type
|
||||
b3ParticleType m_type;
|
||||
|
||||
@ -219,7 +149,7 @@ private:
|
||||
// Applied external force
|
||||
b3Vec3 m_force;
|
||||
|
||||
// Applied external translation
|
||||
// Applied translation
|
||||
b3Vec3 m_translation;
|
||||
|
||||
// Mass
|
||||
@ -248,13 +178,17 @@ private:
|
||||
// Solution
|
||||
b3Vec3 m_x;
|
||||
|
||||
//
|
||||
// Parent cloth
|
||||
b3Cloth* m_cloth;
|
||||
|
||||
//
|
||||
b3Particle* m_prev;
|
||||
// AABB Proxy
|
||||
b3ClothAABBProxy m_aabbProxy;
|
||||
|
||||
//
|
||||
// Broadphase ID
|
||||
u32 m_broadPhaseId;
|
||||
|
||||
// Links to the cloth particle list.
|
||||
b3Particle* m_prev;
|
||||
b3Particle* m_next;
|
||||
};
|
||||
|
||||
@ -270,8 +204,13 @@ inline u32 b3Particle::GetVertex() const
|
||||
|
||||
inline void b3Particle::SetPosition(const b3Vec3& position)
|
||||
{
|
||||
b3Vec3 displacement = position - m_position;
|
||||
|
||||
m_position = position;
|
||||
m_translation.SetZero();
|
||||
|
||||
Synchronize(displacement);
|
||||
SynchronizeTriangles();
|
||||
}
|
||||
|
||||
inline const b3Vec3& b3Particle::GetPosition() const
|
||||
@ -301,6 +240,8 @@ inline float32 b3Particle::GetMass() const
|
||||
inline void b3Particle::SetRadius(float32 radius)
|
||||
{
|
||||
m_radius = radius;
|
||||
|
||||
Synchronize(b3Vec3_zero);
|
||||
}
|
||||
|
||||
inline float32 b3Particle::GetRadius() const
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -22,6 +22,8 @@
|
||||
#include <bounce/collision/trees/dynamic_tree.h>
|
||||
#include <algorithm>
|
||||
|
||||
#define B3_NULL_PROXY (0xFFFFFFFF)
|
||||
|
||||
// A pair of broad-phase proxies.
|
||||
struct b3Pair
|
||||
{
|
||||
@ -49,9 +51,8 @@ public:
|
||||
// Return true if the proxy has moved.
|
||||
bool MoveProxy(u32 proxyId, const b3AABB3& aabb, const b3Vec3& displacement);
|
||||
|
||||
// Add a proxy to the list of moved proxies.
|
||||
// Only moved proxies will be used internally as an AABB query reference object.
|
||||
void BufferMove(u32 proxyId);
|
||||
// Force move the proxy
|
||||
void TouchProxy(u32 proxyId);
|
||||
|
||||
// Get the AABB of a given proxy.
|
||||
const b3AABB3& GetAABB(u32 proxyId) const;
|
||||
@ -59,6 +60,9 @@ public:
|
||||
// Get the user data attached to a proxy.
|
||||
void* GetUserData(u32 proxyId) const;
|
||||
|
||||
// Get the number of proxies.
|
||||
u32 GetProxyCount() const;
|
||||
|
||||
// Test if two proxy AABBs are overlapping.
|
||||
bool TestOverlap(u32 proxy1, u32 proxy2) const;
|
||||
|
||||
@ -81,6 +85,9 @@ public:
|
||||
void Draw() const;
|
||||
private :
|
||||
friend class b3DynamicTree;
|
||||
|
||||
void BufferMove(u32 proxyId);
|
||||
void UnbufferMove(u32 proxyId);
|
||||
|
||||
// The client callback used to add an overlapping pair
|
||||
// to the overlapping pair buffer.
|
||||
@ -89,6 +96,9 @@ private :
|
||||
// The dynamic tree.
|
||||
b3DynamicTree m_tree;
|
||||
|
||||
// Number of proxies
|
||||
u32 m_proxyCount;
|
||||
|
||||
// The current proxy being queried for overlap with another proxies.
|
||||
// It is used to avoid a proxy overlap with itself.
|
||||
u32 m_queryProxyId;
|
||||
@ -114,6 +124,11 @@ inline void* b3BroadPhase::GetUserData(u32 proxyId) const
|
||||
return m_tree.GetUserData(proxyId);
|
||||
}
|
||||
|
||||
inline u32 b3BroadPhase::GetProxyCount() const
|
||||
{
|
||||
return m_proxyCount;
|
||||
}
|
||||
|
||||
template<class T>
|
||||
inline void b3BroadPhase::QueryAABB(T* callback, const b3AABB3& aabb) const
|
||||
{
|
||||
@ -152,8 +167,10 @@ inline void b3BroadPhase::FindPairs(T* callback)
|
||||
{
|
||||
// Keep the current queried proxy ID to avoid self overlapping.
|
||||
m_queryProxyId = m_moveBuffer[i];
|
||||
if (m_queryProxyId == B3_NULL_NODE_D)
|
||||
|
||||
if (m_queryProxyId == B3_NULL_PROXY)
|
||||
{
|
||||
// Proxy was unbuffered
|
||||
continue;
|
||||
}
|
||||
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -37,4 +37,8 @@ struct b3RayCastOutput
|
||||
b3Vec3 normal; // surface normal of intersection
|
||||
};
|
||||
|
||||
// Perform a ray-cast on a triangle.
|
||||
bool b3RayCast(b3RayCastOutput* output, const b3RayCastInput* input,
|
||||
const b3Vec3& v1, const b3Vec3& v2, const b3Vec3& v3);
|
||||
|
||||
#endif
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -114,4 +114,18 @@ b3GJKOutput b3GJK(const b3Transform& xf1, const b3GJKProxy& proxy1,
|
||||
const b3Transform& xf2, const b3GJKProxy& proxy2,
|
||||
bool applyRadius, b3SimplexCache* cache);
|
||||
|
||||
// The output of the GJK-based shape cast algorithm.
|
||||
struct b3GJKShapeCastOutput
|
||||
{
|
||||
float32 t; // time of impact
|
||||
b3Vec3 point; // contact point at t
|
||||
b3Vec3 normal; // contact normal at t
|
||||
u32 iterations; // number of iterations
|
||||
};
|
||||
|
||||
// Find the time of impact between two proxies given the relative target translation vector.
|
||||
bool b3GJKShapeCast(b3GJKShapeCastOutput* output,
|
||||
const b3Transform& xf1, const b3GJKProxy& proxy1,
|
||||
const b3Transform& xf2, const b3GJKProxy& proxy2, const b3Vec3& translation2);
|
||||
|
||||
#endif
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -37,8 +37,8 @@ struct b3AABB3
|
||||
return support;
|
||||
}
|
||||
|
||||
// Compute this AABB from a list of points.
|
||||
void Compute(const b3Vec3* points, u32 count)
|
||||
// Set this AABB from a list of points.
|
||||
void Set(const b3Vec3* points, u32 count)
|
||||
{
|
||||
m_lower = m_upper = points[0];
|
||||
for (u32 i = 1; i < count; ++i)
|
||||
@ -48,8 +48,8 @@ struct b3AABB3
|
||||
}
|
||||
}
|
||||
|
||||
// Compute this AABB from a list of points and a transform.
|
||||
void Compute(const b3Vec3* points, u32 count, const b3Transform& xf)
|
||||
// Set this AABB from a list of points and a transform.
|
||||
void Set(const b3Vec3* points, u32 count, const b3Transform& xf)
|
||||
{
|
||||
m_lower = m_upper = b3Mul(xf, points[0]);
|
||||
for (u32 i = 1; i < count; ++i)
|
||||
@ -60,6 +60,27 @@ struct b3AABB3
|
||||
}
|
||||
}
|
||||
|
||||
// Set this AABB from a triangle.
|
||||
void Set(const b3Vec3& v1, const b3Vec3& v2, const b3Vec3& v3)
|
||||
{
|
||||
m_lower = b3Min(v1, b3Min(v2, v3));
|
||||
m_upper = b3Max(v1, b3Max(v2, v3));
|
||||
}
|
||||
|
||||
// Set this AABB from a center point and a radius vector.
|
||||
void Set(const b3Vec3& center, const b3Vec3& r)
|
||||
{
|
||||
m_lower = center - r;
|
||||
m_upper = center + r;
|
||||
}
|
||||
|
||||
// Set this AABB from a center point and a radius value.
|
||||
void Set(const b3Vec3& center, float32 radius)
|
||||
{
|
||||
b3Vec3 r(radius, radius, radius);
|
||||
Set(center, r);
|
||||
}
|
||||
|
||||
// Extend this AABB by a scalar.
|
||||
void Extend(float32 s)
|
||||
{
|
||||
@ -146,40 +167,70 @@ struct b3AABB3
|
||||
}
|
||||
|
||||
// Test if a ray intersects this AABB.
|
||||
// Output the minimum and maximum intersection fractions to derive the minimum and maximum intersection points.
|
||||
bool TestRay(const b3Vec3& p1, const b3Vec3& p2, float32& min_t, float32& max_t) const
|
||||
bool TestRay(float32& minFraction, const b3Vec3& p1, const b3Vec3& p2, float32 maxFraction) const
|
||||
{
|
||||
b3Vec3 d = p2 - p1;
|
||||
float32 t = d.Normalize();
|
||||
B3_ASSERT(t > B3_EPSILON);
|
||||
|
||||
b3Vec3 inv_d;
|
||||
inv_d.x = 1.0f / d.x;
|
||||
inv_d.y = 1.0f / d.y;
|
||||
inv_d.z = 1.0f / d.z;
|
||||
|
||||
b3Vec3 t1;
|
||||
t1.x = (m_lower.x - p1.x) * inv_d.x;
|
||||
t1.y = (m_lower.y - p1.y) * inv_d.y;
|
||||
t1.z = (m_lower.z - p1.z) * inv_d.z;
|
||||
|
||||
b3Vec3 t2;
|
||||
t2.x = (m_upper.x - p1.x) * inv_d.x;
|
||||
t2.y = (m_upper.y - p1.y) * inv_d.y;
|
||||
t2.z = (m_upper.z - p1.z) * inv_d.z;
|
||||
|
||||
|
||||
float32 lower = 0.0f;
|
||||
float32 upper = maxFraction;
|
||||
|
||||
for (u32 i = 0; i < 3; ++i)
|
||||
{
|
||||
min_t = b3Max(min_t, b3Min(t1[i], t2[i]));
|
||||
max_t = b3Min(max_t, b3Max(t1[i], t2[i]));
|
||||
float32 numerators[2], denominators[2];
|
||||
|
||||
numerators[0] = p1[i] - m_lower[i];
|
||||
numerators[1] = m_upper[i] - p1[i];
|
||||
|
||||
denominators[0] = -d[i];
|
||||
denominators[1] = d[i];
|
||||
|
||||
for (u32 j = 0; j < 2; ++j)
|
||||
{
|
||||
float32 numerator = numerators[j];
|
||||
float32 denominator = denominators[j];
|
||||
|
||||
if (denominator == 0.0f)
|
||||
{
|
||||
// s is parallel to this half-space.
|
||||
if (numerator < 0.0f)
|
||||
{
|
||||
// s is outside of this half-space.
|
||||
// dot(n, p1) and dot(n, p2) < 0.
|
||||
return false;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if (denominator < 0.0f)
|
||||
{
|
||||
// s enters this half-space.
|
||||
if (numerator < lower * denominator)
|
||||
{
|
||||
// Increase lower.
|
||||
lower = numerator / denominator;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
// s exits the half-space.
|
||||
if (numerator < upper * denominator)
|
||||
{
|
||||
// Decrease upper.
|
||||
upper = numerator / denominator;
|
||||
}
|
||||
}
|
||||
// Exit if intersection becomes empty.
|
||||
if (upper < lower)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (min_t >= 0.0f && min_t >= max_t && max_t <= t)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
B3_ASSERT(lower >= 0.0f && lower <= maxFraction);
|
||||
minFraction = lower;
|
||||
return true;
|
||||
}
|
||||
};
|
||||
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -22,6 +22,7 @@
|
||||
#include <bounce/collision/shapes/mesh.h>
|
||||
|
||||
// A (H + 1) x (W + 1) grid mesh stored in row-major order.
|
||||
// v(i, j) = i * (W + 1) + j
|
||||
template<u32 H = 1, u32 W = 1>
|
||||
struct b3GridMesh : public b3Mesh
|
||||
{
|
||||
@ -32,61 +33,53 @@ struct b3GridMesh : public b3Mesh
|
||||
// with the world x-z axes.
|
||||
b3GridMesh()
|
||||
{
|
||||
u32 h = H + 1;
|
||||
u32 w = W + 1;
|
||||
|
||||
b3Vec3 t;
|
||||
t.x = -0.5f * float32(w) + 0.5f;
|
||||
t.y = 0.0f;
|
||||
t.z = -0.5f * float32(h) + 0.5f;
|
||||
|
||||
for (u32 i = 0; i < h; ++i)
|
||||
vertexCount = 0;
|
||||
for (u32 i = 0; i <= H; ++i)
|
||||
{
|
||||
for (u32 j = 0; j < w; ++j)
|
||||
for (u32 j = 0; j <= W; ++j)
|
||||
{
|
||||
u32 v1 = i * w + j;
|
||||
|
||||
b3Vec3 v;
|
||||
v.x = float32(j);
|
||||
v.y = 0.0f;
|
||||
v.z = float32(i);
|
||||
|
||||
v += t;
|
||||
|
||||
gridVertices[v1] = v;
|
||||
gridVertices[vertexCount++].Set(float32(j), 0.0f, float32(i));
|
||||
}
|
||||
}
|
||||
|
||||
u32 triangleIndex = 0;
|
||||
for (u32 i = 0; i < h - 1; ++i)
|
||||
B3_ASSERT(vertexCount == (H + 1) * (W + 1));
|
||||
|
||||
b3Vec3 translation;
|
||||
translation.x = -0.5f * float32(W);
|
||||
translation.y = 0.0f;
|
||||
translation.z = -0.5f * float32(H);
|
||||
|
||||
for (u32 i = 0; i < vertexCount; ++i)
|
||||
{
|
||||
for (u32 j = 0; j < w - 1; ++j)
|
||||
gridVertices[i] += translation;
|
||||
}
|
||||
|
||||
triangleCount = 0;
|
||||
for (u32 i = 0; i < H; ++i)
|
||||
{
|
||||
for (u32 j = 0; j < W; ++j)
|
||||
{
|
||||
u32 v1 = i * w + j;
|
||||
u32 v2 = (i + 1) * w + j;
|
||||
u32 v3 = (i + 1) * w + (j + 1);
|
||||
u32 v4 = i * w + (j + 1);
|
||||
|
||||
b3Triangle* t1 = gridTriangles + triangleIndex;
|
||||
++triangleIndex;
|
||||
u32 v1 = i * (W + 1) + j;
|
||||
u32 v2 = (i + 1) * (W + 1) + j;
|
||||
u32 v3 = (i + 1) * (W + 1) + (j + 1);
|
||||
u32 v4 = i * (W + 1) + (j + 1);
|
||||
|
||||
b3Triangle* t1 = gridTriangles + triangleCount++;
|
||||
t1->v1 = v3;
|
||||
t1->v2 = v2;
|
||||
t1->v3 = v1;
|
||||
|
||||
b3Triangle* t2 = gridTriangles + triangleIndex;
|
||||
++triangleIndex;
|
||||
|
||||
b3Triangle* t2 = gridTriangles + triangleCount++;
|
||||
t2->v1 = v1;
|
||||
t2->v2 = v4;
|
||||
t2->v3 = v3;
|
||||
}
|
||||
}
|
||||
|
||||
B3_ASSERT(triangleCount == 2 * H * W);
|
||||
|
||||
vertices = gridVertices;
|
||||
vertexCount = (H + 1) * (W + 1);
|
||||
triangles = gridTriangles;
|
||||
triangleCount = 2 * H * W;
|
||||
}
|
||||
};
|
||||
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -78,14 +78,10 @@ inline u32 b3Mesh::GetSize() const
|
||||
inline b3AABB3 b3Mesh::GetTriangleAABB(u32 index) const
|
||||
{
|
||||
const b3Triangle* triangle = triangles + index;
|
||||
|
||||
u32 i1 = triangle->v1;
|
||||
u32 i2 = triangle->v2;
|
||||
u32 i3 = triangle->v3;
|
||||
|
||||
b3AABB3 aabb;
|
||||
aabb.m_lower = b3Min(b3Min(vertices[i1], vertices[i2]), vertices[i3]);
|
||||
aabb.m_upper = b3Max(b3Max(vertices[i1], vertices[i2]), vertices[i3]);
|
||||
aabb.Set(vertices[triangle->v1], vertices[triangle->v2], vertices[triangle->v3]);
|
||||
|
||||
return aabb;
|
||||
}
|
||||
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -32,13 +32,13 @@ struct b3QHull : public b3Hull
|
||||
|
||||
b3QHull()
|
||||
{
|
||||
vertices = hullVertices.Begin();
|
||||
vertices = nullptr;
|
||||
vertexCount = 0;
|
||||
edges = hullEdges.Begin();
|
||||
edges = nullptr;
|
||||
edgeCount = 0;
|
||||
faces = hullFaces.Begin();
|
||||
faces = nullptr;
|
||||
faceCount = 0;
|
||||
planes = hullPlanes.Begin();
|
||||
planes = nullptr;
|
||||
centroid.SetZero();
|
||||
}
|
||||
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -211,8 +211,8 @@ inline void b3DynamicTree::RayCast(T* callback, const b3RayCastInput& input) con
|
||||
|
||||
const b3Node* node = m_nodes + nodeIndex;
|
||||
|
||||
float32 minFraction = 0.0f;
|
||||
if (node->aabb.TestRay(p1, p2, maxFraction, minFraction) == true)
|
||||
float32 minFraction;
|
||||
if (node->aabb.TestRay(minFraction, p1, p2, maxFraction) == true)
|
||||
{
|
||||
if (node->IsLeaf() == true)
|
||||
{
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -174,8 +174,8 @@ inline void b3StaticTree::RayCast(T* callback, const b3RayCastInput& input) cons
|
||||
|
||||
const b3Node* node = m_nodes + nodeIndex;
|
||||
|
||||
float32 minFraction = 0.0f;
|
||||
if (node->aabb.TestRay(p1, p2, maxFraction, minFraction) == true)
|
||||
float32 minFraction;
|
||||
if (node->aabb.TestRay(minFraction, p1, p2, maxFraction) == true)
|
||||
{
|
||||
if (node->IsLeaf() == true)
|
||||
{
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -95,17 +95,23 @@ public :
|
||||
// Draw a solid circle with center, normal, and radius.
|
||||
virtual void DrawSolidCircle(const b3Vec3& normal, const b3Vec3& center, float32 radius, const b3Color& color) = 0;
|
||||
|
||||
// Draw a sphere with center and radius.
|
||||
// Draw a plane with center, normal and radius.
|
||||
virtual void DrawPlane(const b3Vec3& normal, const b3Vec3& center, float32 radius, const b3Color& color) = 0;
|
||||
|
||||
// Draw a solid plane with center, normal and radius.
|
||||
virtual void DrawSolidPlane(const b3Vec3& normal, const b3Vec3& center, float32 radius, const b3Color& color) = 0;
|
||||
|
||||
// Draw a sphere with center, and radius.
|
||||
virtual void DrawSphere(const b3Vec3& center, float32 radius, const b3Color& color) = 0;
|
||||
|
||||
// Draw a solid sphere with center and radius.
|
||||
virtual void DrawSolidSphere(const b3Vec3& center, float32 radius, const b3Color& color) = 0;
|
||||
// Draw a solid sphere with center, radius, and rotation.
|
||||
virtual void DrawSolidSphere(const b3Vec3& center, float32 radius, const b3Mat33& rotation, const b3Color& color) = 0;
|
||||
|
||||
// Draw a capsule with segment and radius.
|
||||
// Draw a capsule with segment, and radius.
|
||||
virtual void DrawCapsule(const b3Vec3& p1, const b3Vec3& p2, float32 radius, const b3Color& color) = 0;
|
||||
|
||||
// Draw a solid capsule with segment and radius.
|
||||
virtual void DrawSolidCapsule(const b3Vec3& p1, const b3Vec3& p2, float32 radius, const b3Color& color) = 0;
|
||||
// Draw a solid capsule with segment, radius, and rotation.
|
||||
virtual void DrawSolidCapsule(const b3Vec3& p1, const b3Vec3& p2, float32 radius, const b3Mat33& rotation, const b3Color& color) = 0;
|
||||
|
||||
// Draw a AABB.
|
||||
virtual void DrawAABB(const b3AABB3& aabb, const b3Color& color) = 0;
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -144,6 +144,32 @@ inline void b3BarycentricCoordinates(float32 out[4],
|
||||
out[3] = out[0] + out[1] + out[2];
|
||||
}
|
||||
|
||||
// Convert a point Q from Cartesian coordinates to Barycentric coordinates (u, v, w, x)
|
||||
// with respect to a tetrahedron ABCD.
|
||||
// The last output value is the (positive) divisor.
|
||||
inline void b3BarycentricCoordinates(float32 out[5],
|
||||
const b3Vec3& A, const b3Vec3& B, const b3Vec3& C, const b3Vec3& D,
|
||||
const b3Vec3& Q)
|
||||
{
|
||||
b3Vec3 AB = B - A;
|
||||
b3Vec3 AC = C - A;
|
||||
b3Vec3 AD = D - A;
|
||||
|
||||
b3Vec3 QA = A - Q;
|
||||
b3Vec3 QB = B - Q;
|
||||
b3Vec3 QC = C - Q;
|
||||
b3Vec3 QD = D - Q;
|
||||
|
||||
float32 divisor = b3Det(AB, AC, AD);
|
||||
float32 sign = b3Sign(divisor);
|
||||
|
||||
out[0] = sign * b3Det(QB, QC, QD);
|
||||
out[1] = sign * b3Det(QA, QD, QC);
|
||||
out[2] = sign * b3Det(QA, QB, QD);
|
||||
out[3] = sign * b3Det(QA, QC, QB);
|
||||
out[4] = sign * divisor;
|
||||
}
|
||||
|
||||
// Project a point onto a segment AB.
|
||||
inline b3Vec3 b3ClosestPointOnSegment(const b3Vec3& P, const b3Vec3& A, const b3Vec3& B)
|
||||
{
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -48,6 +48,12 @@ struct b3Mat33
|
||||
return (&x.x)[i + 3 * j];
|
||||
}
|
||||
|
||||
// Write an indexed element from this matrix.
|
||||
float32& operator()(u32 i, u32 j)
|
||||
{
|
||||
return (&x.x)[i + 3 * j];
|
||||
}
|
||||
|
||||
// Add a matrix to this matrix.
|
||||
void operator+=(const b3Mat33& B)
|
||||
{
|
||||
@ -227,22 +233,20 @@ inline b3Mat33 b3Outer(const b3Vec3& a, const b3Vec3& b)
|
||||
|
||||
// Compute an orthogonal basis given one of its vectors.
|
||||
// The vector must be normalized.
|
||||
inline b3Mat33 b3Basis(const b3Vec3& a)
|
||||
inline void b3ComputeBasis(const b3Vec3& a, b3Vec3& b, b3Vec3& c)
|
||||
{
|
||||
// Box2D
|
||||
b3Mat33 A;
|
||||
// https://box2d.org/2014/02/computing-a-basis/
|
||||
if (b3Abs(a.x) >= float32(0.57735027))
|
||||
{
|
||||
A.y.Set(a.y, -a.x, 0.0f);
|
||||
b.Set(a.y, -a.x, 0.0f);
|
||||
}
|
||||
else
|
||||
{
|
||||
A.y.Set(0.0f, a.z, -a.y);
|
||||
b.Set(0.0f, a.z, -a.y);
|
||||
}
|
||||
A.x = a;
|
||||
A.y = b3Normalize(A.y);
|
||||
A.z = b3Cross(a, A.y);
|
||||
return A;
|
||||
|
||||
b.Normalize();
|
||||
c = b3Cross(a, b);
|
||||
}
|
||||
|
||||
// Rotation about the x-axis.
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -93,6 +93,9 @@ public:
|
||||
{
|
||||
B3_ASSERT(m_count > 0);
|
||||
--m_count;
|
||||
|
||||
T* e = m_elements + m_count;
|
||||
e->~T();
|
||||
}
|
||||
|
||||
const T& Back() const
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,129 +0,0 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
* arising from the use of this software.
|
||||
* Permission is granted to anyone to use this software for any purpose,
|
||||
* including commercial applications, and to alter it and redistribute it
|
||||
* freely, subject to the following restrictions:
|
||||
* 1. The origin of this software must not be misrepresented; you must not
|
||||
* claim that you wrote the original software. If you use this software
|
||||
* in a product, an acknowledgment in the product documentation would be
|
||||
* appreciated but is not required.
|
||||
* 2. Altered source versions must be plainly marked as such, and must not be
|
||||
* misrepresented as being the original software.
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef B3_BODY_DRAGGER_H
|
||||
#define B3_BODY_DRAGGER_H
|
||||
|
||||
#include <bounce/common/geometry.h>
|
||||
#include <bounce/dynamics/body.h>
|
||||
|
||||
// A body dragger.
|
||||
class b3BodyDragger
|
||||
{
|
||||
public:
|
||||
b3BodyDragger(b3Ray3* ray, b3World* world)
|
||||
{
|
||||
m_ray = ray;
|
||||
m_world = world;
|
||||
m_shape = nullptr;
|
||||
m_mouseJoint = nullptr;
|
||||
}
|
||||
|
||||
~b3BodyDragger()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
bool IsDragging() const
|
||||
{
|
||||
return m_shape != nullptr;
|
||||
}
|
||||
|
||||
bool StartDragging()
|
||||
{
|
||||
B3_ASSERT(IsDragging() == false);
|
||||
|
||||
b3RayCastSingleShapeOutput out;
|
||||
if (m_world->RayCastSingleShape(&out, m_ray->A(), m_ray->B()) == false)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
m_x = out.fraction;
|
||||
m_shape = out.shape;
|
||||
|
||||
b3BodyDef bd;
|
||||
b3Body* groundBody = m_world->CreateBody(bd);
|
||||
|
||||
b3Body* body = m_shape->GetBody();
|
||||
body->SetAwake(true);
|
||||
|
||||
b3MouseJointDef jd;
|
||||
jd.bodyA = groundBody;
|
||||
jd.bodyB = body;
|
||||
jd.target = out.point;
|
||||
jd.maxForce = 2000.0f * body->GetMass();
|
||||
|
||||
m_mouseJoint = (b3MouseJoint*)m_world->CreateJoint(jd);
|
||||
|
||||
m_p = body->GetLocalPoint(out.point);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void Drag()
|
||||
{
|
||||
B3_ASSERT(IsDragging() == true);
|
||||
m_mouseJoint->SetTarget(GetPointB());
|
||||
}
|
||||
|
||||
void StopDragging()
|
||||
{
|
||||
B3_ASSERT(IsDragging() == true);
|
||||
b3Body* groundBody = m_mouseJoint->GetBodyA();
|
||||
m_world->DestroyJoint(m_mouseJoint);
|
||||
m_mouseJoint = nullptr;
|
||||
m_world->DestroyBody(groundBody);
|
||||
m_shape = nullptr;
|
||||
}
|
||||
|
||||
b3Ray3* GetRay() const
|
||||
{
|
||||
return m_ray;
|
||||
}
|
||||
|
||||
b3Body* GetBody() const
|
||||
{
|
||||
B3_ASSERT(IsDragging() == true);
|
||||
return m_shape->GetBody();
|
||||
}
|
||||
|
||||
b3Vec3 GetPointA() const
|
||||
{
|
||||
B3_ASSERT(IsDragging() == true);
|
||||
return m_shape->GetBody()->GetWorldPoint(m_p);
|
||||
}
|
||||
|
||||
b3Vec3 GetPointB() const
|
||||
{
|
||||
B3_ASSERT(IsDragging() == true);
|
||||
return (1.0f - m_x) * m_ray->A() + m_x * m_ray->B();
|
||||
}
|
||||
|
||||
private:
|
||||
b3Ray3 * m_ray;
|
||||
float32 m_x;
|
||||
|
||||
b3World* m_world;
|
||||
|
||||
b3Shape* m_shape;
|
||||
b3Vec3 m_p;
|
||||
b3MouseJoint* m_mouseJoint;
|
||||
};
|
||||
|
||||
#endif
|
@ -1,224 +0,0 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
* arising from the use of this software.
|
||||
* Permission is granted to anyone to use this software for any purpose,
|
||||
* including commercial applications, and to alter it and redistribute it
|
||||
* freely, subject to the following restrictions:
|
||||
* 1. The origin of this software must not be misrepresented; you must not
|
||||
* claim that you wrote the original software. If you use this software
|
||||
* in a product, an acknowledgment in the product documentation would be
|
||||
* appreciated but is not required.
|
||||
* 2. Altered source versions must be plainly marked as such, and must not be
|
||||
* misrepresented as being the original software.
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef B3_CLOTH_DRAGGER_H
|
||||
#define B3_CLOTH_DRAGGER_H
|
||||
|
||||
#include <bounce/collision/collision.h>
|
||||
#include <bounce/dynamics/cloth/cloth.h>
|
||||
#include <bounce/dynamics/cloth/cloth_mesh.h>
|
||||
#include <bounce/dynamics/cloth/particle.h>
|
||||
#include <bounce/dynamics/cloth/spring_force.h>
|
||||
#include <bounce/dynamics/world.h>
|
||||
|
||||
// A cloth triangle dragger.
|
||||
class b3ClothDragger
|
||||
{
|
||||
public:
|
||||
b3ClothDragger(b3Ray3* ray, b3World* world)
|
||||
{
|
||||
m_spring = false;
|
||||
m_ray = ray;
|
||||
m_world = world;
|
||||
m_cloth = nullptr;
|
||||
}
|
||||
|
||||
~b3ClothDragger()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
bool IsDragging() const
|
||||
{
|
||||
return m_cloth != nullptr;
|
||||
}
|
||||
|
||||
bool StartDragging()
|
||||
{
|
||||
B3_ASSERT(IsDragging() == false);
|
||||
|
||||
b3RayCastSingleClothOutput rayOut;
|
||||
if (m_world->RayCastSingleCloth(&rayOut, m_ray->A(), m_ray->B()) == false)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
m_cloth = rayOut.cloth;
|
||||
m_mesh = m_cloth->GetMesh();
|
||||
m_triangle = m_mesh->triangles + rayOut.triangle;
|
||||
m_x = rayOut.fraction;
|
||||
|
||||
b3Particle* p1 = m_cloth->GetVertexParticle(m_triangle->v1);
|
||||
b3Particle* p2 = m_cloth->GetVertexParticle(m_triangle->v2);
|
||||
b3Particle* p3 = m_cloth->GetVertexParticle(m_triangle->v3);
|
||||
|
||||
b3Vec3 v1 = p1->GetPosition();
|
||||
b3Vec3 v2 = p2->GetPosition();
|
||||
b3Vec3 v3 = p3->GetPosition();
|
||||
|
||||
b3Vec3 B = GetPointB();
|
||||
|
||||
float32 wABC[4];
|
||||
b3BarycentricCoordinates(wABC, v1, v2, v3, B);
|
||||
|
||||
if (wABC[3] > B3_EPSILON)
|
||||
{
|
||||
m_u = wABC[0] / wABC[3];
|
||||
m_v = wABC[1] / wABC[3];
|
||||
}
|
||||
else
|
||||
{
|
||||
m_u = m_v = 0.0f;
|
||||
}
|
||||
|
||||
if (m_spring)
|
||||
{
|
||||
b3ParticleDef pd;
|
||||
pd.type = e_staticParticle;
|
||||
pd.position = B;
|
||||
|
||||
m_particle = m_cloth->CreateParticle(pd);
|
||||
|
||||
{
|
||||
b3SpringForceDef sfd;
|
||||
sfd.p1 = m_particle;
|
||||
sfd.p2 = p1;
|
||||
sfd.restLength = 0.0f;
|
||||
sfd.structural = 10000.0f;
|
||||
m_s1 = (b3SpringForce*)m_cloth->CreateForce(sfd);
|
||||
}
|
||||
|
||||
{
|
||||
b3SpringForceDef sfd;
|
||||
sfd.p1 = m_particle;
|
||||
sfd.p2 = p2;
|
||||
sfd.restLength = 0.0f;
|
||||
sfd.structural = 10000.0f;
|
||||
m_s2 = (b3SpringForce*)m_cloth->CreateForce(sfd);
|
||||
}
|
||||
|
||||
{
|
||||
b3SpringForceDef sfd;
|
||||
sfd.p1 = m_particle;
|
||||
sfd.p2 = p3;
|
||||
sfd.restLength = 0.0f;
|
||||
sfd.structural = 10000.0f;
|
||||
m_s3 = (b3SpringForce*)m_cloth->CreateForce(sfd);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
m_t1 = p1->GetType();
|
||||
p1->SetType(e_staticParticle);
|
||||
|
||||
m_t2 = p2->GetType();
|
||||
p2->SetType(e_staticParticle);
|
||||
|
||||
m_t3 = p3->GetType();
|
||||
p3->SetType(e_staticParticle);
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void Drag()
|
||||
{
|
||||
B3_ASSERT(IsDragging() == true);
|
||||
|
||||
b3Vec3 A = GetPointA();
|
||||
b3Vec3 B = GetPointB();
|
||||
|
||||
b3Vec3 dx = B - A;
|
||||
|
||||
if (m_spring)
|
||||
{
|
||||
m_particle->SetPosition(B);
|
||||
}
|
||||
else
|
||||
{
|
||||
b3Particle* p1 = m_cloth->GetVertexParticle(m_triangle->v1);
|
||||
p1->ApplyTranslation(dx);
|
||||
|
||||
b3Particle* p2 = m_cloth->GetVertexParticle(m_triangle->v2);
|
||||
p2->ApplyTranslation(dx);
|
||||
|
||||
b3Particle* p3 = m_cloth->GetVertexParticle(m_triangle->v3);
|
||||
p3->ApplyTranslation(dx);
|
||||
}
|
||||
}
|
||||
|
||||
void StopDragging()
|
||||
{
|
||||
B3_ASSERT(IsDragging() == true);
|
||||
|
||||
if (m_spring)
|
||||
{
|
||||
m_cloth->DestroyForce(m_s1);
|
||||
m_cloth->DestroyForce(m_s2);
|
||||
m_cloth->DestroyForce(m_s3);
|
||||
m_cloth->DestroyParticle(m_particle);
|
||||
}
|
||||
else
|
||||
{
|
||||
m_cloth->GetVertexParticle(m_triangle->v1)->SetType(m_t1);
|
||||
m_cloth->GetVertexParticle(m_triangle->v2)->SetType(m_t2);
|
||||
m_cloth->GetVertexParticle(m_triangle->v3)->SetType(m_t3);
|
||||
}
|
||||
|
||||
m_cloth = nullptr;
|
||||
}
|
||||
|
||||
b3Vec3 GetPointA() const
|
||||
{
|
||||
B3_ASSERT(IsDragging() == true);
|
||||
|
||||
b3Vec3 A = m_cloth->GetVertexParticle(m_triangle->v1)->GetPosition();
|
||||
b3Vec3 B = m_cloth->GetVertexParticle(m_triangle->v2)->GetPosition();
|
||||
b3Vec3 C = m_cloth->GetVertexParticle(m_triangle->v3)->GetPosition();
|
||||
|
||||
return m_u * A + m_v * B + (1.0f - m_u - m_v) * C;
|
||||
}
|
||||
|
||||
b3Vec3 GetPointB() const
|
||||
{
|
||||
B3_ASSERT(IsDragging() == true);
|
||||
|
||||
return (1.0f - m_x) * m_ray->A() + m_x * m_ray->B();
|
||||
}
|
||||
private:
|
||||
b3Ray3* m_ray;
|
||||
float32 m_x;
|
||||
|
||||
b3World* m_world;
|
||||
|
||||
b3Cloth* m_cloth;
|
||||
const b3ClothMesh* m_mesh;
|
||||
b3ClothMeshTriangle* m_triangle;
|
||||
float32 m_u, m_v;
|
||||
|
||||
bool m_spring;
|
||||
|
||||
b3Particle* m_particle;
|
||||
b3SpringForce* m_s1;
|
||||
b3SpringForce* m_s2;
|
||||
b3SpringForce* m_s3;
|
||||
|
||||
b3ParticleType m_t1, m_t2, m_t3;
|
||||
};
|
||||
|
||||
#endif
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -293,9 +293,7 @@ private:
|
||||
friend class b3MeshContact;
|
||||
friend class b3ContactManager;
|
||||
friend class b3ContactSolver;
|
||||
friend class b3ClothSolver;
|
||||
friend class b3ClothContactSolver;
|
||||
|
||||
|
||||
friend class b3Joint;
|
||||
friend class b3JointManager;
|
||||
friend class b3JointSolver;
|
||||
@ -308,6 +306,13 @@ private:
|
||||
|
||||
friend class b3List2<b3Body>;
|
||||
|
||||
friend class b3ClothSolver;
|
||||
friend class b3ClothContactSolver;
|
||||
|
||||
friend class b3SoftBody;
|
||||
friend class b3SoftBodySolver;
|
||||
friend class b3SoftBodyContactSolver;
|
||||
|
||||
enum b3BodyFlags
|
||||
{
|
||||
e_awakeFlag = 0x0001,
|
||||
|
@ -1,158 +0,0 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
* arising from the use of this software.
|
||||
* Permission is granted to anyone to use this software for any purpose,
|
||||
* including commercial applications, and to alter it and redistribute it
|
||||
* freely, subject to the following restrictions:
|
||||
* 1. The origin of this software must not be misrepresented; you must not
|
||||
* claim that you wrote the original software. If you use this software
|
||||
* in a product, an acknowledgment in the product documentation would be
|
||||
* appreciated but is not required.
|
||||
* 2. Altered source versions must be plainly marked as such, and must not be
|
||||
* misrepresented as being the original software.
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef B3_BEND_FORCE_H
|
||||
#define B3_BEND_FORCE_H
|
||||
|
||||
#include <bounce/dynamics/cloth/force.h>
|
||||
|
||||
struct b3BendForceDef : public b3ForceDef
|
||||
{
|
||||
b3BendForceDef()
|
||||
{
|
||||
type = e_bendForce;
|
||||
p1 = nullptr;
|
||||
p2 = nullptr;
|
||||
p3 = nullptr;
|
||||
p4 = nullptr;
|
||||
restDistance = 0.0f;
|
||||
restAngle = 0.0f;
|
||||
structural = 0.0f;
|
||||
damping = 0.0f;
|
||||
}
|
||||
|
||||
//
|
||||
void Initialize(b3Particle* particle1, b3Particle* particle2, b3Particle* particle3, b3Particle* particle4,
|
||||
float32 structuralStiffness, float32 dampingStiffness);
|
||||
|
||||
// Particle 1
|
||||
b3Particle* p1;
|
||||
|
||||
// Particle 2
|
||||
b3Particle* p2;
|
||||
|
||||
// Particle 3
|
||||
b3Particle* p3;
|
||||
|
||||
// Particle 4
|
||||
b3Particle* p4;
|
||||
|
||||
// Rest distance
|
||||
float32 restDistance;
|
||||
|
||||
// Rest angle
|
||||
float32 restAngle;
|
||||
|
||||
// Structural stiffness
|
||||
float32 structural;
|
||||
|
||||
// Damping stiffness
|
||||
float32 damping;
|
||||
};
|
||||
|
||||
//
|
||||
class b3BendForce : public b3Force
|
||||
{
|
||||
public:
|
||||
b3Particle* GetParticle1();
|
||||
|
||||
b3Particle* GetParticle2();
|
||||
|
||||
b3Particle* GetParticle3();
|
||||
|
||||
b3Particle* GetParticle4();
|
||||
|
||||
float32 GetRestDistance() const;
|
||||
|
||||
float32 GetRestAngle() const;
|
||||
|
||||
float32 GetStructuralStiffness() const;
|
||||
|
||||
float32 GetDampingStiffness() const;
|
||||
private:
|
||||
friend class b3Force;
|
||||
friend class b3Cloth;
|
||||
|
||||
b3BendForce(const b3BendForceDef* def);
|
||||
~b3BendForce();
|
||||
|
||||
void Apply(const b3ClothSolverData* data);
|
||||
|
||||
// Solver shared
|
||||
|
||||
// Particle 1
|
||||
b3Particle* m_p1;
|
||||
|
||||
// Particle 2
|
||||
b3Particle* m_p2;
|
||||
|
||||
// Particle 3
|
||||
b3Particle* m_p3;
|
||||
|
||||
// Particle 4
|
||||
b3Particle* m_p4;
|
||||
|
||||
// Rest distance
|
||||
float32 m_L0;
|
||||
|
||||
// Rest angle
|
||||
float32 m_angle0;
|
||||
|
||||
// Structural stiffness
|
||||
float32 m_ks;
|
||||
|
||||
// Structural stiffness
|
||||
float32 m_kd;
|
||||
};
|
||||
|
||||
inline b3Particle* b3BendForce::GetParticle1()
|
||||
{
|
||||
return m_p1;
|
||||
}
|
||||
|
||||
inline b3Particle* b3BendForce::GetParticle2()
|
||||
{
|
||||
return m_p2;
|
||||
}
|
||||
|
||||
inline b3Particle* b3BendForce::GetParticle3()
|
||||
{
|
||||
return m_p3;
|
||||
}
|
||||
|
||||
inline b3Particle* b3BendForce::GetParticle4()
|
||||
{
|
||||
return m_p4;
|
||||
}
|
||||
|
||||
inline float32 b3BendForce::GetRestAngle() const
|
||||
{
|
||||
return m_angle0;
|
||||
}
|
||||
|
||||
inline float32 b3BendForce::GetStructuralStiffness() const
|
||||
{
|
||||
return m_ks;
|
||||
}
|
||||
|
||||
inline float32 b3BendForce::GetDampingStiffness() const
|
||||
{
|
||||
return m_kd;
|
||||
}
|
||||
|
||||
#endif
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -41,6 +41,8 @@ public:
|
||||
|
||||
bool TestSphere(b3TestSphereOutput* output, const b3Sphere& sphere, const b3Transform& xf) const;
|
||||
|
||||
bool TestSphere(b3TestSphereOutput* output, const b3Sphere& sphere, const b3Transform& xf, u32 childIndex) const;
|
||||
|
||||
bool RayCast(b3RayCastOutput* output, const b3RayCastInput& input, const b3Transform& xf) const;
|
||||
|
||||
bool RayCast(b3RayCastOutput* output, const b3RayCastInput& input, const b3Transform& xf, u32 childIndex) const;
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -140,6 +140,9 @@ public:
|
||||
// Set the user data associated with this shape.
|
||||
void SetUserData(void* data);
|
||||
|
||||
// Get broadphase AABB
|
||||
const b3AABB3& GetAABB() const;
|
||||
|
||||
// Dump this shape to the log file.
|
||||
void Dump(u32 bodyIndex) const;
|
||||
|
||||
@ -153,6 +156,7 @@ protected:
|
||||
friend class b3Body;
|
||||
friend class b3Contact;
|
||||
friend class b3ContactManager;
|
||||
friend class b3MeshShape;
|
||||
friend class b3MeshContact;
|
||||
friend class b3ContactSolver;
|
||||
friend class b3List1<b3Shape>;
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -22,21 +22,20 @@
|
||||
#include <bounce/common/memory/stack_allocator.h>
|
||||
#include <bounce/common/memory/block_pool.h>
|
||||
#include <bounce/common/template/list.h>
|
||||
#include <bounce/common/draw.h>
|
||||
#include <bounce/dynamics/time_step.h>
|
||||
#include <bounce/dynamics/joint_manager.h>
|
||||
#include <bounce/dynamics/contact_manager.h>
|
||||
|
||||
struct b3ClothDef;
|
||||
struct b3BodyDef;
|
||||
|
||||
class b3Cloth;
|
||||
class b3Body;
|
||||
class b3QueryListener;
|
||||
class b3RayCastListener;
|
||||
class b3ContactListener;
|
||||
class b3ContactFilter;
|
||||
|
||||
struct b3RayCastSingleShapeOutput
|
||||
struct b3RayCastSingleOutput
|
||||
{
|
||||
b3Shape* shape; // shape
|
||||
b3Vec3 point; // intersection point on surface
|
||||
@ -44,15 +43,6 @@ struct b3RayCastSingleShapeOutput
|
||||
float32 fraction; // time of intersection on segment
|
||||
};
|
||||
|
||||
struct b3RayCastSingleClothOutput
|
||||
{
|
||||
b3Cloth* cloth; // cloth
|
||||
u32 triangle; // triangle
|
||||
b3Vec3 point; // intersection point on surface
|
||||
b3Vec3 normal; // surface normal of intersection
|
||||
float32 fraction; // time of intersection on segment
|
||||
};
|
||||
|
||||
// Use a physics world to create/destroy rigid bodies, execute ray cast and volume queries.
|
||||
class b3World
|
||||
{
|
||||
@ -79,12 +69,6 @@ public:
|
||||
// The acceleration has units of m/s^2.
|
||||
void SetGravity(const b3Vec3& gravity);
|
||||
|
||||
// Create a new deformable cloth.
|
||||
b3Cloth* CreateCloth(const b3ClothDef& def);
|
||||
|
||||
// Destroy an existing deformable cloth.
|
||||
void DestroyCloth(b3Cloth* cloth);
|
||||
|
||||
// Create a new rigid body.
|
||||
b3Body* CreateBody(const b3BodyDef& def);
|
||||
|
||||
@ -108,29 +92,14 @@ public:
|
||||
// The ray cast output is the intercepted shape, the intersection
|
||||
// point in world space, the face normal on the shape associated with the point,
|
||||
// and the intersection fraction.
|
||||
void RayCastShape(b3RayCastListener* listener, const b3Vec3& p1, const b3Vec3& p2) const;
|
||||
void RayCast(b3RayCastListener* listener, const b3Vec3& p1, const b3Vec3& p2) const;
|
||||
|
||||
// Perform a ray cast with the world.
|
||||
// If the ray doesn't intersect with a shape in the world then return false.
|
||||
// The ray cast output is the intercepted shape, the intersection
|
||||
// point in world space, the face normal on the shape associated with the point,
|
||||
// and the intersection fraction.
|
||||
bool RayCastSingleShape(b3RayCastSingleShapeOutput* output, const b3Vec3& p1, const b3Vec3& p2) const;
|
||||
|
||||
// Perform a ray cast with the world.
|
||||
// The given ray cast listener will be notified when a ray intersects a shape
|
||||
// in the world.
|
||||
// The ray cast output is the intercepted cloth, the intersection
|
||||
// point in world space, the face normal on the cloth associated with the point,
|
||||
// and the intersection fraction.
|
||||
void RayCastCloth(b3RayCastListener* listener, const b3Vec3& p1, const b3Vec3& p2) const;
|
||||
|
||||
// Perform a ray cast with the world.
|
||||
// If the ray doesn't intersect with a cloth in the world then return false.
|
||||
// The ray cast output is the intercepted cloth, the intersection
|
||||
// point in world space, the face normal on the cloth associated with the point,
|
||||
// and the intersection fraction.
|
||||
bool RayCastSingleCloth(b3RayCastSingleClothOutput* output, const b3Vec3& p1, const b3Vec3& p2) const;
|
||||
bool RayCastSingle(b3RayCastSingleOutput* output, const b3Vec3& p1, const b3Vec3& p2) const;
|
||||
|
||||
// Perform a AABB query with the world.
|
||||
// The query listener will be notified when two shape AABBs are overlapping.
|
||||
@ -153,16 +122,21 @@ public:
|
||||
// Draw the entities in this world.
|
||||
void Draw() const;
|
||||
|
||||
// Draw solid the entities in this world.
|
||||
void DrawSolid() const;
|
||||
|
||||
// Draw a shape.
|
||||
void DrawShape(const b3Transform& xf, const b3Shape* shape) const;
|
||||
private :
|
||||
void DrawShape(const b3Transform& xf, const b3Shape* shape, const b3Color& color) const;
|
||||
|
||||
// Draw solid a shape.
|
||||
void DrawSolidShape(const b3Transform& xf, const b3Shape* shape, const b3Color& color) const;
|
||||
private:
|
||||
enum b3Flags
|
||||
{
|
||||
e_shapeAddedFlag = 0x0001,
|
||||
e_clearForcesFlag = 0x0002,
|
||||
};
|
||||
|
||||
friend class b3Cloth;
|
||||
|
||||
friend class b3Body;
|
||||
friend class b3Shape;
|
||||
friend class b3Contact;
|
||||
@ -172,20 +146,16 @@ private :
|
||||
|
||||
void Solve(float32 dt, u32 velocityIterations, u32 positionIterations);
|
||||
|
||||
void StepCloth(float32 dt);
|
||||
|
||||
bool m_sleeping;
|
||||
bool m_warmStarting;
|
||||
u32 m_flags;
|
||||
b3Vec3 m_gravity;
|
||||
|
||||
b3StackAllocator m_stackAllocator;
|
||||
b3BlockPool m_clothBlocks;
|
||||
|
||||
// Pool of bodies
|
||||
b3BlockPool m_bodyBlocks;
|
||||
|
||||
// List of clothes
|
||||
b3List2<b3Cloth> m_clothList;
|
||||
|
||||
// List of bodies
|
||||
b3List2<b3Body> m_bodyList;
|
||||
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
@ -22,7 +22,6 @@
|
||||
#include <bounce/common/math/math.h>
|
||||
|
||||
class b3Shape;
|
||||
class b3Cloth;
|
||||
class b3Contact;
|
||||
|
||||
class b3QueryListener
|
||||
@ -47,12 +46,6 @@ public:
|
||||
// the intersection point on the shape, the surface normal associated with the point, and the
|
||||
// intersection fraction for the ray.
|
||||
virtual float32 ReportShape(b3Shape* shape, const b3Vec3& point, const b3Vec3& normal, float32 fraction) = 0;
|
||||
|
||||
// Report that a cloth was hit by the ray to this contact listener.
|
||||
// The reported information are the shape hit by the ray,
|
||||
// the intersection point on the cloth, the surface normal associated with the point, the
|
||||
// intersection fraction for the ray, and the triangle.
|
||||
virtual float32 ReportCloth(b3Cloth* cloth, const b3Vec3& point, const b3Vec3& normal, float32 fraction, u32 triangle) = 0;
|
||||
};
|
||||
|
||||
class b3ContactListener
|
||||
|
@ -1,166 +0,0 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
* arising from the use of this software.
|
||||
* Permission is granted to anyone to use this software for any purpose,
|
||||
* including commercial applications, and to alter it and redistribute it
|
||||
* freely, subject to the following restrictions:
|
||||
* 1. The origin of this software must not be misrepresented; you must not
|
||||
* claim that you wrote the original software. If you use this software
|
||||
* in a product, an acknowledgment in the product documentation would be
|
||||
* appreciated but is not required.
|
||||
* 2. Altered source versions must be plainly marked as such, and must not be
|
||||
* misrepresented as being the original software.
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef B3_GARMENT_H
|
||||
#define B3_GARMENT_H
|
||||
|
||||
#include <bounce/garment/sewing_pattern.h>
|
||||
|
||||
struct b3SewingLine
|
||||
{
|
||||
u32 p1, p2;
|
||||
u32 v1, v2;
|
||||
};
|
||||
|
||||
struct b3Garment
|
||||
{
|
||||
u32 patternCount;
|
||||
b3SewingPattern** patterns;
|
||||
u32 sewingCount;
|
||||
b3SewingLine* sewingLines;
|
||||
};
|
||||
|
||||
struct b3RectangleGarment : public b3Garment
|
||||
{
|
||||
b3RectanglePattern rectangle;
|
||||
b3SewingPattern* rectanglePatterns[1];
|
||||
|
||||
b3RectangleGarment(float32 ex = 1.0f, float32 ey = 1.0f) : rectangle(ex, ey)
|
||||
{
|
||||
rectanglePatterns[0] = &rectangle;
|
||||
|
||||
patternCount = 1;
|
||||
patterns = rectanglePatterns;
|
||||
|
||||
sewingCount = 0;
|
||||
sewingLines = nullptr;
|
||||
}
|
||||
};
|
||||
|
||||
struct b3CircleGarment : public b3Garment
|
||||
{
|
||||
b3CirclePattern<> circle;
|
||||
b3SewingPattern* circlePatterns[1];
|
||||
|
||||
b3CircleGarment(float32 r = 1.0f) : circle(r)
|
||||
{
|
||||
circlePatterns[0] = &circle;
|
||||
|
||||
patternCount = 1;
|
||||
patterns = circlePatterns;
|
||||
|
||||
sewingCount = 0;
|
||||
sewingLines = nullptr;
|
||||
}
|
||||
};
|
||||
|
||||
struct b3ShirtGarment : public b3Garment
|
||||
{
|
||||
b3RectanglePattern frontBody;
|
||||
b3RectanglePattern frontRightSleeve;
|
||||
b3RectanglePattern frontLeftSleeve;
|
||||
|
||||
b3RectanglePattern backBody;
|
||||
b3RectanglePattern backRightSleeve;
|
||||
b3RectanglePattern backLeftSleeve;
|
||||
|
||||
b3SewingLine shirtSewingLines[12];
|
||||
|
||||
b3SewingPattern* shirtPatterns[6];
|
||||
|
||||
b3ShirtGarment() :
|
||||
frontBody(1.0f, 1.0f),
|
||||
frontRightSleeve(0.2f, 0.2f),
|
||||
frontLeftSleeve(0.2f, 0.2f),
|
||||
backBody(1.0f, 1.0f),
|
||||
backRightSleeve(0.2f, 0.2f),
|
||||
backLeftSleeve(0.2f, 0.2f)
|
||||
{
|
||||
b3Vec2 etr;
|
||||
etr.x = 1.2f;
|
||||
etr.y = 0.8f;
|
||||
|
||||
b3Vec2 etl;
|
||||
etl.x = -1.2f;
|
||||
etl.y = 0.8f;
|
||||
|
||||
for (u32 i = 0; i < 4; ++i)
|
||||
{
|
||||
frontRightSleeve.vertices[i] += etr;
|
||||
frontLeftSleeve.vertices[i] += etl;
|
||||
backRightSleeve.vertices[i] += etr;
|
||||
backLeftSleeve.vertices[i] += etl;
|
||||
}
|
||||
|
||||
// Perform sewing
|
||||
u32 count = 0;
|
||||
|
||||
// Sew bodies
|
||||
for (u32 i = 0; i < frontBody.vertexCount; ++i)
|
||||
{
|
||||
b3SewingLine line;
|
||||
line.p1 = 0;
|
||||
line.p2 = 3;
|
||||
line.v1 = i;
|
||||
line.v2 = i;
|
||||
|
||||
shirtSewingLines[count++] = line;
|
||||
}
|
||||
|
||||
// Sew sleeves
|
||||
for (u32 i = 0; i < frontRightSleeve.vertexCount; ++i)
|
||||
{
|
||||
b3SewingLine line;
|
||||
line.p1 = 1;
|
||||
line.p2 = 4;
|
||||
line.v1 = i;
|
||||
line.v2 = i;
|
||||
|
||||
shirtSewingLines[count++] = line;
|
||||
}
|
||||
|
||||
for (u32 i = 0; i < frontLeftSleeve.vertexCount; ++i)
|
||||
{
|
||||
b3SewingLine line;
|
||||
line.p1 = 2;
|
||||
line.p2 = 5;
|
||||
line.v1 = i;
|
||||
line.v2 = i;
|
||||
|
||||
shirtSewingLines[count++] = line;
|
||||
}
|
||||
|
||||
B3_ASSERT(12 == count);
|
||||
|
||||
shirtPatterns[0] = &frontBody;
|
||||
shirtPatterns[1] = &frontRightSleeve;
|
||||
shirtPatterns[2] = &frontLeftSleeve;
|
||||
|
||||
shirtPatterns[3] = &backBody;
|
||||
shirtPatterns[4] = &backRightSleeve;
|
||||
shirtPatterns[5] = &backLeftSleeve;
|
||||
|
||||
patternCount = 6;
|
||||
patterns = shirtPatterns;
|
||||
|
||||
sewingCount = 12;
|
||||
sewingLines = shirtSewingLines;
|
||||
}
|
||||
};
|
||||
|
||||
#endif
|
54
include/bounce/meshgen/cylinder_mesh.h
Normal file
54
include/bounce/meshgen/cylinder_mesh.h
Normal file
@ -0,0 +1,54 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
* arising from the use of this software.
|
||||
* Permission is granted to anyone to use this software for any purpose,
|
||||
* including commercial applications, and to alter it and redistribute it
|
||||
* freely, subject to the following restrictions:
|
||||
* 1. The origin of this software must not be misrepresented; you must not
|
||||
* claim that you wrote the original software. If you use this software
|
||||
* in a product, an acknowledgment in the product documentation would be
|
||||
* appreciated but is not required.
|
||||
* 2. Altered source versions must be plainly marked as such, and must not be
|
||||
* misrepresented as being the original software.
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef CYM_MESH_H
|
||||
#define CYM_MESH_H
|
||||
|
||||
#include <bounce/common/math/vec3.h>
|
||||
|
||||
// This structure represents a triangle mesh.
|
||||
struct cymMesh
|
||||
{
|
||||
cymMesh()
|
||||
{
|
||||
vertexCount = 0;
|
||||
vertices = nullptr;
|
||||
normals = nullptr;
|
||||
indexCount = 0;
|
||||
indices = nullptr;
|
||||
}
|
||||
|
||||
~cymMesh()
|
||||
{
|
||||
b3Free(vertices);
|
||||
b3Free(normals);
|
||||
b3Free(indices);
|
||||
}
|
||||
|
||||
u32 vertexCount; // number of unique vertices
|
||||
b3Vec3* vertices; // list of unique vertices
|
||||
b3Vec3* normals; // list of vertex normals
|
||||
u32 indexCount; // number of triangle vertex indices
|
||||
u32* indices; // list of triangle vertex index
|
||||
};
|
||||
|
||||
// Create a unit cylinder along the y-axis given the number of segments.
|
||||
// The number of segments must be greater than 2.
|
||||
void cymCreateMesh(cymMesh& output, u32 segments);
|
||||
|
||||
#endif
|
54
include/bounce/meshgen/sphere_mesh.h
Normal file
54
include/bounce/meshgen/sphere_mesh.h
Normal file
@ -0,0 +1,54 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
* arising from the use of this software.
|
||||
* Permission is granted to anyone to use this software for any purpose,
|
||||
* including commercial applications, and to alter it and redistribute it
|
||||
* freely, subject to the following restrictions:
|
||||
* 1. The origin of this software must not be misrepresented; you must not
|
||||
* claim that you wrote the original software. If you use this software
|
||||
* in a product, an acknowledgment in the product documentation would be
|
||||
* appreciated but is not required.
|
||||
* 2. Altered source versions must be plainly marked as such, and must not be
|
||||
* misrepresented as being the original software.
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef SM_MESH_H
|
||||
#define SM_MESH_H
|
||||
|
||||
#include <bounce/common/math/vec3.h>
|
||||
|
||||
// This structure represents a triangle mesh.
|
||||
struct smMesh
|
||||
{
|
||||
smMesh()
|
||||
{
|
||||
vertexCount = 0;
|
||||
vertices = nullptr;
|
||||
normals = nullptr;
|
||||
indexCount = 0;
|
||||
indices = nullptr;
|
||||
}
|
||||
|
||||
~smMesh()
|
||||
{
|
||||
b3Free(vertices);
|
||||
b3Free(normals);
|
||||
b3Free(indices);
|
||||
}
|
||||
|
||||
u32 vertexCount; // number of unique vertices
|
||||
b3Vec3* vertices; // list of unique vertices
|
||||
b3Vec3* normals; // list of vertex normals
|
||||
u32 indexCount; // number of triangle vertex indices
|
||||
u32* indices; // list of triangle vertex index
|
||||
};
|
||||
|
||||
// Create a unit icosphere given the number of subdivisions.
|
||||
// If the number of subdivisions to perform is zero then the output mesh is an octahedron.
|
||||
void smCreateMesh(smMesh& output, u32 subdivisions);
|
||||
|
||||
#endif
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2016 Irlan Robson http://www.irlan.net
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
123
include/bounce/softbody/block_softbody_mesh.h
Normal file
123
include/bounce/softbody/block_softbody_mesh.h
Normal file
@ -0,0 +1,123 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
* arising from the use of this software.
|
||||
* Permission is granted to anyone to use this software for any purpose,
|
||||
* including commercial applications, and to alter it and redistribute it
|
||||
* freely, subject to the following restrictions:
|
||||
* 1. The origin of this software must not be misrepresented; you must not
|
||||
* claim that you wrote the original software. If you use this software
|
||||
* in a product, an acknowledgment in the product documentation would be
|
||||
* appreciated but is not required.
|
||||
* 2. Altered source versions must be plainly marked as such, and must not be
|
||||
* misrepresented as being the original software.
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef B3_BLOCK_SOFT_BODY_MESH_H
|
||||
#define B3_BLOCK_SOFT_BODY_MESH_H
|
||||
|
||||
#include <bounce/softbody/softbody_mesh.h>
|
||||
|
||||
template<u32 W = 1, u32 H = 1, u32 D = 1>
|
||||
struct b3BlockSoftBodyMesh : public b3SoftBodyMesh
|
||||
{
|
||||
b3Vec3 blockVertices[(W + 1) * (H + 1) * (D + 1)];
|
||||
b3SoftBodyMeshTetrahedron blockTetrahedrons[5 * W * H * D];
|
||||
|
||||
b3BlockSoftBodyMesh()
|
||||
{
|
||||
vertexCount = 0;
|
||||
for (u32 x = 0; x <= W; ++x)
|
||||
{
|
||||
for (u32 y = 0; y <= H; ++y)
|
||||
{
|
||||
for (u32 z = 0; z <= D; ++z)
|
||||
{
|
||||
blockVertices[vertexCount++].Set(float32(x), float32(y), float32(z));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
B3_ASSERT(vertexCount == (W + 1) * (H + 1) * (D + 1));
|
||||
|
||||
b3Vec3 translation;
|
||||
translation.x = -0.5f * float32(W);
|
||||
translation.y = -0.5f * float32(H);
|
||||
translation.z = -0.5f * float32(D);
|
||||
|
||||
for (u32 i = 0; i < vertexCount; ++i)
|
||||
{
|
||||
blockVertices[i] += translation;
|
||||
}
|
||||
|
||||
tetrahedronCount = 0;
|
||||
for (u32 x = 0; x < W; ++x)
|
||||
{
|
||||
for (u32 y = 0; y < H; ++y)
|
||||
{
|
||||
for (u32 z = 0; z < D; ++z)
|
||||
{
|
||||
// 4*-----*7
|
||||
// /| /|
|
||||
// / | / |
|
||||
// 5*-----*6 |
|
||||
// | 0*--|--*3
|
||||
// | / | /
|
||||
// |/ |/
|
||||
// 1*-----*2
|
||||
u32 v0 = (x * (H + 1) + y) * (D + 1) + z;
|
||||
u32 v1 = v0 + 1;
|
||||
u32 v3 = ((x + 1) * (H + 1) + y) * (D + 1) + z;
|
||||
u32 v2 = v3 + 1;
|
||||
u32 v7 = ((x + 1) * (H + 1) + (y + 1)) * (D + 1) + z;
|
||||
u32 v6 = v7 + 1;
|
||||
u32 v4 = (x * (H + 1) + (y + 1)) * (D + 1) + z;
|
||||
u32 v5 = v4 + 1;
|
||||
|
||||
if ((x + y + z) % 2 == 1)
|
||||
{
|
||||
// CCW
|
||||
//blockTetrahedrons[tetrahedronCount++] = { v1, v2, v6, v3 };
|
||||
//blockTetrahedrons[tetrahedronCount++] = { v3, v6, v4, v7 };
|
||||
//blockTetrahedrons[tetrahedronCount++] = { v1, v4, v6, v5 };
|
||||
//blockTetrahedrons[tetrahedronCount++] = { v1, v3, v4, v0 };
|
||||
//blockTetrahedrons[tetrahedronCount++] = { v1, v6, v4, v3 };
|
||||
|
||||
// CW
|
||||
blockTetrahedrons[tetrahedronCount++] = { v2, v1, v6, v3 };
|
||||
blockTetrahedrons[tetrahedronCount++] = { v6, v3, v4, v7 };
|
||||
blockTetrahedrons[tetrahedronCount++] = { v4, v1, v6, v5 };
|
||||
blockTetrahedrons[tetrahedronCount++] = { v3, v1, v4, v0 };
|
||||
blockTetrahedrons[tetrahedronCount++] = { v6, v1, v4, v3 };
|
||||
}
|
||||
else
|
||||
{
|
||||
// CCW
|
||||
//blockTetrahedrons[tetrahedronCount++] = { v2, v0, v5, v1 };
|
||||
//blockTetrahedrons[tetrahedronCount++] = { v2, v7, v0, v3 };
|
||||
//blockTetrahedrons[tetrahedronCount++] = { v2, v5, v7, v6 };
|
||||
//blockTetrahedrons[tetrahedronCount++] = { v0, v7, v5, v4 };
|
||||
//blockTetrahedrons[tetrahedronCount++] = { v2, v0, v7, v5 };
|
||||
|
||||
// CW
|
||||
blockTetrahedrons[tetrahedronCount++] = { v0, v2, v5, v1 };
|
||||
blockTetrahedrons[tetrahedronCount++] = { v7, v2, v0, v3 };
|
||||
blockTetrahedrons[tetrahedronCount++] = { v5, v2, v7, v6 };
|
||||
blockTetrahedrons[tetrahedronCount++] = { v7, v0, v5, v4 };
|
||||
blockTetrahedrons[tetrahedronCount++] = { v0, v2, v7, v5 };
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
B3_ASSERT(tetrahedronCount == 5 * W * H * D);
|
||||
|
||||
vertices = blockVertices;
|
||||
tetrahedrons = blockTetrahedrons;
|
||||
}
|
||||
};
|
||||
|
||||
#endif
|
127
include/bounce/softbody/contacts/softbody_contact_solver.h
Normal file
127
include/bounce/softbody/contacts/softbody_contact_solver.h
Normal file
@ -0,0 +1,127 @@
|
||||
/*
|
||||
* Copyright (c) 2016-2019 Irlan Robson https://irlanrobson.github.io
|
||||
*
|
||||
* This software is provided 'as-is', without any express or implied
|
||||
* warranty. In no event will the authors be held liable for any damages
|
||||
* arising from the use of this software.
|
||||
* Permission is granted to anyone to use this software for any purpose,
|
||||
* including commercial applications, and to alter it and redistribute it
|
||||
* freely, subject to the following restrictions:
|
||||
* 1. The origin of this software must not be misrepresented; you must not
|
||||
* claim that you wrote the original software. If you use this software
|
||||
* in a product, an acknowledgment in the product documentation would be
|
||||
* appreciated but is not required.
|
||||
* 2. Altered source versions must be plainly marked as such, and must not be
|
||||
* misrepresented as being the original software.
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef B3_SOFT_BODY_CONTACT_SOLVER_H
|
||||
#define B3_SOFT_BODY_CONTACT_SOLVER_H
|
||||
|
||||
#include <bounce/common/math/mat22.h>
|
||||
#include <bounce/common/math/mat33.h>
|
||||
|
||||
class b3StackAllocator;
|
||||
|
||||
struct b3SoftBodyNode;
|
||||
class b3Body;
|
||||
|
||||
struct b3NodeBodyContact;
|
||||
|
||||
struct b3DenseVec3;
|
||||
|
||||
struct b3SoftBodySolverBodyContactVelocityConstraint
|
||||
{
|
||||
u32 indexA;
|
||||
float32 invMassA;
|
||||
b3Mat33 invIA;
|
||||
|
||||
b3Body* bodyB;
|
||||
float32 invMassB;
|
||||
b3Mat33 invIB;
|
||||
|
||||
float32 friction;
|
||||
|
||||
b3Vec3 point;
|
||||
b3Vec3 rA;
|
||||
b3Vec3 rB;
|
||||
|
||||
b3Vec3 normal;
|
||||
float32 normalMass;
|
||||
float32 normalImpulse;
|
||||
float32 velocityBias;
|
||||
|
||||
b3Vec3 tangent1;
|
||||
b3Vec3 tangent2;
|
||||
b3Mat22 tangentMass;
|
||||
b3Vec2 tangentImpulse;
|
||||
};
|
||||
|
||||
struct b3SoftBodySolverBodyContactPositionConstraint
|
||||
{
|
||||
u32 indexA;
|
||||
float32 invMassA;
|
||||
b3Mat33 invIA;
|
||||
float32 radiusA;
|
||||
b3Vec3 localCenterA;
|
||||
|
||||
b3Body* bodyB;
|
||||
float32 invMassB;
|
||||
b3Mat33 invIB;
|
||||
float32 radiusB;
|
||||
b3Vec3 localCenterB;
|
||||
|
||||
b3Vec3 rA;
|
||||
b3Vec3 rB;
|
||||
|
||||
b3Vec3 normalA;
|
||||
b3Vec3 localPointA;
|
||||
b3Vec3 localPointB;
|
||||
};
|
||||
|
||||
struct b3SoftBodyContactSolverDef
|
||||
{
|
||||
b3StackAllocator* allocator;
|
||||
|
||||
b3Vec3* positions;
|
||||
b3Vec3* velocities;
|
||||
|
||||
u32 bodyContactCount;
|
||||
b3NodeBodyContact** bodyContacts;
|
||||
};
|
||||
|
||||
inline float32 b3MixFriction(float32 u1, float32 u2)
|
||||
{
|
||||
return b3Sqrt(u1 * u2);
|
||||
}
|
||||
|
||||
class b3SoftBodyContactSolver
|
||||
{
|
||||
public:
|
||||
b3SoftBodyContactSolver(const b3SoftBodyContactSolverDef& def);
|
||||
~b3SoftBodyContactSolver();
|
||||
|
||||
void InitializeBodyContactConstraints();
|
||||
|
||||
void WarmStart();
|
||||
|
||||
void SolveBodyContactVelocityConstraints();
|
||||
|
||||
void StoreImpulses();
|
||||
|
||||
bool SolveBodyContactPositionConstraints();
|
||||
protected:
|
||||
b3StackAllocator* m_allocator;
|
||||
|
||||
b3Vec3* m_positions;
|
||||
b3Vec3* m_velocities;
|
||||
|
||||
u32 m_bodyContactCount;
|
||||
b3NodeBodyContact** m_bodyContacts;
|
||||
|
||||
b3SoftBodySolverBodyContactVelocityConstraint* m_bodyVelocityConstraints;
|
||||
b3SoftBodySolverBodyContactPositionConstraint* m_bodyPositionConstraints;
|
||||
};
|
||||
|
||||
#endif
|
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user