Browse Source

Removed bullet & collision algorithms work

Panagiotis Christopoulos Charitos 11 years ago
parent
commit
a6327b9932

+ 16 - 2
include/anki/collision/GjkEpa.h

@@ -7,6 +7,7 @@
 #define ANKI_COLLISION_GJK_EPA_H
 
 #include "anki/Math.h"
+#include "anki/collision/ContactPoint.h"
 
 namespace anki {
 
@@ -24,9 +25,9 @@ public:
 	/// Return true if the two convex shapes intersect
 	Bool intersect(const ConvexShape& shape0, const ConvexShape& shape1);
 
-private:
+protected:
 	U32 m_count; ///< Simplex count
-	Vec4 m_b, m_c, m_d; ///< Simplex
+	Vec4 m_a, m_b, m_c, m_d; ///< Simplex
 	Vec4 m_dir;
 
 	/// Compute the support
@@ -43,6 +44,19 @@ private:
 	}
 };
 
+/// The implementation of EPA
+class GjkEpa: public Gjk
+{
+public:
+	Bool intersect(const ConvexShape& shape0, const ConvexShape& shape1,
+		ContactPoint& contact);
+
+private:
+	Array<Vec4, 100> m_simplex;
+
+	void findClosestEdge(F32& distance, Vec4& normal, U& index);
+};
+
 /// @}
 
 } // end namespace anki

+ 23 - 10
include/anki/collision/Obb.h

@@ -7,6 +7,7 @@
 #define ANKI_COLLISION_OBB_H
 
 #include "anki/collision/ConvexShape.h"
+#include "anki/collision/Aabb.h"
 #include "anki/Math.h"
 #include "anki/util/Array.h"
 
@@ -38,10 +39,12 @@ public:
 	}
 	Vec4& getCenter()
 	{
+		makeDirty();
 		return m_center;
 	}
 	void setCenter(const Vec4& x)
 	{
+		makeDirty();
 		m_center = x;
 	}
 
@@ -51,10 +54,12 @@ public:
 	}
 	Mat3x4& getRotation()
 	{
+		makeDirty();
 		return m_rotation;
 	}
 	void setRotation(const Mat3x4& x)
 	{
+		makeDirty();
 		m_rotation = x;
 	}
 
@@ -64,23 +69,19 @@ public:
 	}
 	Vec4& getExtend()
 	{
+		makeDirty();
 		return m_extend;
 	}
 	void setExtend(const Vec4& x)
 	{
+		makeDirty();
 		m_extend = x;
 	}
 	/// @}
 
 	/// @name Operators
 	/// @{
-	Obb& operator=(const Obb& b)
-	{
-		m_center = b.m_center;
-		m_rotation = b.m_rotation;
-		m_extend = b.m_extend;
-		return *this;
-	}
+	Obb& operator=(const Obb& b);
 	/// @}
 
 	/// Implements CollisionShape::accept
@@ -123,14 +124,26 @@ public:
 	Vec4 computeSupport(const Vec4& dir) const;
 
 public:
-	/// @name Data
-	/// @{
 	Vec4 m_center;
 	Mat3x4 m_rotation;
 	/// With identity rotation this points to max (front, right, top in
 	/// our case)
 	Vec4 m_extend;
-	/// @}
+
+	class 
+	{
+	public:
+		mutable Aabb m_aabb;
+		mutable Array<Vec4, 8> m_extremePoints;
+		mutable Bool8 m_dirtyAabb = true;
+		mutable Bool8 m_dirtyExtremePoints = true;
+	} m_cache;
+
+	void makeDirty()
+	{
+		m_cache.m_dirtyAabb = true;
+		m_cache.m_dirtyExtremePoints = true;
+	}
 };
 
 /// @}

+ 2 - 2
include/anki/core/Logger.h

@@ -68,7 +68,7 @@ public:
 	using MessageHandlerCallback = void (*)(void*, const Info& info);
 
 	/// Initialize the logger
-	void init(InitFlags flags, HeapAllocator<U8>& alloc);
+	Logger(InitFlags flags, HeapAllocator<U8>& alloc);
 
 	/// Add a new message handler
 	void addMessageHandler(void* data, MessageHandlerCallback callback);
@@ -99,7 +99,7 @@ private:
 	static void logfileMessageHandler(void* vlogger, const Info& info);
 };
 
-typedef Singleton<Logger> LoggerSingleton;
+typedef SingletonInit<Logger> LoggerSingleton;
 /// @}
 
 } // end namespace

+ 0 - 60
include/anki/physics/Character.h

@@ -1,60 +0,0 @@
-// Copyright (C) 2014, Panagiotis Christopoulos Charitos.
-// All rights reserved.
-// Code licensed under the BSD License.
-// http://www.anki3d.org/LICENSE
-
-#ifndef ANKI_PHYSICS_CHARACTER_H
-#define ANKI_PHYSICS_CHARACTER_H
-
-#include "anki/Math.h"
-#include <memory>
-
-class btPairCachingGhostObject;
-class btConvexShape;
-class btKinematicCharacterController;
-class btGhostPairCallback;
-
-namespace anki {
-
-class MoveComponent;
-class PhysicsWorld;
-class MotionState;
-
-/// Its basically a wrapper around bullet character
-class Character
-{
-friend class PhysicsWorld;
-
-public:
-	/// Initializer class
-	struct Initializer
-	{
-		F32 characterHeight;
-		F32 characterWidth;
-		F32 stepHeight;
-		F32 jumpSpeed;
-		F32 maxJumpHeight;
-		MoveComponent* movable; ///< For the MotionState
-		Transform startTrf;
-
-		Initializer();
-	};
-
-	Character(PhysicsWorld* masterContainer, const Initializer& init);
-	~Character();
-	void rotate(F32 angle);
-	void moveForward(F32 distance);
-	void jump();
-
-private:
-	PhysicsWorld* masterContainer; ///< Know your father
-	btPairCachingGhostObject* ghostObject;
-	btConvexShape* convexShape;
-	btKinematicCharacterController* character;
-	btGhostPairCallback* ghostPairCallback;
-	std::unique_ptr<MotionState> motionState;
-};
-
-} // end namespace
-
-#endif

+ 0 - 95
include/anki/physics/Converters.h

@@ -1,95 +0,0 @@
-// Copyright (C) 2014, Panagiotis Christopoulos Charitos.
-// All rights reserved.
-// Code licensed under the BSD License.
-// http://www.anki3d.org/LICENSE
-
-#ifndef ANKI_PHYSICS_CONVERTERS_H
-#define ANKI_PHYSICS_CONVERTERS_H
-
-#include "anki/Math.h"
-#include <btBulletCollisionCommon.h>
-#include <btBulletDynamicsCommon.h>
-
-namespace anki {
-
-//==============================================================================
-// Bullet to AnKi                                                              =
-//==============================================================================
-
-inline Vec3 toAnki(const btVector3& v)
-{
-	return Vec3(v.x(), v.y(), v.z());
-}
-
-inline Vec4 toAnki(const btVector4& v)
-{
-	return Vec4(v.x(), v.y(), v.z(), v.w());
-}
-
-inline Mat3 toAnki(const btMatrix3x3& m)
-{
-	Mat3 m3;
-	m3.setRows(toAnki(m[0]), toAnki(m[1]), toAnki(m[2]));
-	return m3;
-}
-
-inline Quat toAnki(const btQuaternion& q)
-{
-	return Quat(q.x(), q.y(), q.z(), q.w());
-}
-
-inline Transform toAnki(const btTransform& t)
-{
-	Transform out;
-	out.setRotation(Mat3x4(toAnki(t.getBasis())));
-	out.setOrigin(Vec4(toAnki(t.getOrigin()), 0.0));
-	out.setScale(1.0);
-	return out;
-}
-
-//==============================================================================
-// AnKi to Bullet                                                              =
-//==============================================================================
-
-inline btVector3 toBt(const Vec3& v)
-{
-	return btVector3(v.x(),  v.y(), v.z());
-}
-
-inline btVector4 toBt(const Vec4& v)
-{
-	return btVector4(v.x(), v.y(), v.z(), v.w());
-}
-
-inline btMatrix3x3 toBt(const Mat3 m)
-{
-	btMatrix3x3 r;
-	r[0] = toBt(m.getRow(0));
-	r[1] = toBt(m.getRow(1));
-	r[2] = toBt(m.getRow(2));
-	return r;
-}
-
-inline btTransform toBt(const Mat4& m)
-{
-	btTransform r;
-	r.setFromOpenGLMatrix(&(m.getTransposed())[0]);
-	return r;
-}
-
-inline btQuaternion toBt(const Quat& q)
-{
-	return btQuaternion(q.x(), q.y(), q.z(), q.w());
-}
-
-inline btTransform toBt(const Transform& trf)
-{
-	btTransform r;
-	r.setOrigin(toBt(trf.getOrigin()));
-	r.setBasis(toBt(trf.getRotation().getRotationPart()));
-	return r;
-}
-
-} // end namespace anki
-
-#endif

+ 0 - 74
include/anki/physics/MotionState.h

@@ -1,74 +0,0 @@
-// Copyright (C) 2014, Panagiotis Christopoulos Charitos.
-// All rights reserved.
-// Code licensed under the BSD License.
-// http://www.anki3d.org/LICENSE
-
-#ifndef ANKI_PHYSICS_MOTION_STATE_H
-#define ANKI_PHYSICS_MOTION_STATE_H
-
-#include "anki/Math.h"
-#include "anki/physics/Converters.h"
-#include <LinearMath/btMotionState.h>
-
-namespace anki {
-
-/// A custom and generic bullet motion state
-class MotionState: public btMotionState
-{
-public:
-	MotionState()
-		: MotionState(toBt(Transform::getIdentity()))
-	{}
-
-	MotionState(const btTransform& worldTransform_)
-		: worldTransform(worldTransform_), updated(false)
-	{}
-
-	~MotionState()
-	{}
-
-	MotionState& operator=(const MotionState& b)
-	{
-		worldTransform = b.worldTransform;
-		updated = b.updated;
-		return *this;
-	}
-
-	/// @name Accessors
-	/// @{
-	Bool getUpdated() const
-	{
-		return updated;
-	}
-	void setUpdated(Bool x)
-	{
-		updated = x;
-	}
-	const btTransform& getWorldTransform2() const
-	{
-		return worldTransform;
-	}
-	/// @}
-
-	/// @name Bullet implementation of virtuals
-	/// @{
-	void getWorldTransform(btTransform& out) const
-	{
-		out = worldTransform;
-	}
-
-	void setWorldTransform(const btTransform& in)
-	{
-		worldTransform = in;
-		updated = true;
-	}
-	/// @}
-
-private:
-	btTransform worldTransform;
-	Bool8 updated;
-};
-
-} // end namespace anki
-
-#endif

+ 0 - 49
include/anki/physics/PhysicsObject.h

@@ -1,49 +0,0 @@
-// Copyright (C) 2014, Panagiotis Christopoulos Charitos.
-// All rights reserved.
-// Code licensed under the BSD License.
-// http://www.anki3d.org/LICENSE
-
-#ifndef ANKI_PHYSICS_PSYSICS_OBJECT_H
-#define ANKI_PHYSICS_PSYSICS_OBJECT_H
-
-#include "anki/util/Assert.h"
-#include "anki/scene/Common.h"
-
-namespace anki {
-
-class PhysicsWorld;
-
-// The base of all physics objects
-class PhysicsObject
-{
-public:
-	PhysicsObject(PhysicsWorld* world_)
-		: world(world_)
-	{
-		ANKI_ASSERT(world);
-	}
-
-	virtual ~PhysicsObject()
-	{}
-
-	/// @name Accessors
-	/// @{
-	PhysicsWorld& getPhysicsWorld()
-	{
-		return *world;
-	}
-	const PhysicsWorld& getPhysicsWorld() const
-	{
-		return *world;
-	}
-
-	SceneAllocator<U8> getSceneAllocator() const;
-	/// @}
-
-private:
-	PhysicsWorld* world;
-};
-
-} // end namespace anki
-
-#endif

+ 5 - 66
include/anki/physics/PhysicsWorld.h

@@ -6,86 +6,25 @@
 #ifndef ANKI_PHYSICS_PHYS_WORLD_H
 #define ANKI_PHYSICS_PHYS_WORLD_H
 
-#include "anki/physics/Converters.h"
-#include "anki/physics/PhysicsObject.h"
-#include "anki/util/Vector.h"
-#include "anki/scene/Common.h"
 #include <memory>
-#include <btBulletCollisionCommon.h>
-#include <btBulletDynamicsCommon.h>
-
-class btIDebugDraw;
 
 namespace anki {
 
-class Character;
-class RigidBody;
-class SceneGraph;
+/// @addtogroup physics
+/// @{
 
 /// The master container for all physics related stuff.
 class PhysicsWorld
 {
-	// Friends for registering and unregistering
-	friend class Character; 
-	friend class RigidBody;
-
 public:
-	/// Collision groups
-	enum CollisionGroup
-	{
-		CG_NOTHING = 0,
-		CG_MAP = 1 << 0,
-		CG_PARTICLE = 1 << 1,
-		CG_ALL = CG_MAP | CG_PARTICLE
-	};
-
-	PhysicsWorld(SceneGraph* scene);
+	PhysicsWorld();
 	~PhysicsWorld();
 
-	SceneAllocator<U8> getSceneAllocator() const;
-
-	/// @note This class takes ownership of the pointer
-	void setDebugDrawer(btIDebugDraw* newDebugDrawer);
-
-	void debugDraw();
-
-	/// Time as always in sec
-	void update(F32 prevUpdateTime, F32 crntTime);
-
-	/// Create a new SceneNode
-	template<typename Object, typename... Args>
-	void newPhysicsObject(Object*& object, Args&&... args)
-	{
-		SceneAllocator<Object> al = getSceneAllocator();
-		//object = al.newInstance(this, std::forward<Args>(args)...);
-		object = al.allocate(1);
-		al.construct(object, this, std::forward<Args>(args)...);
-	}
-
-	/// Delete a scene node. It actualy marks it for deletion
-	void deletePhysicsObject(PhysicsObject* object)
-	{
-		SceneAllocator<PhysicsObject> al = getSceneAllocator();
-		al.deleteInstance(object);
-	}
-
 private:
-	SceneGraph* scene;
-
-	/// Container for rigid bodied and constraints
-	btDiscreteDynamicsWorld* dynamicsWorld;
-	btDefaultCollisionConfiguration* collisionConfiguration;
-	/// Contains the algorithms of collision
-	btCollisionDispatcher* dispatcher;
-	btBroadphaseInterface* broadphase;
-	btSequentialImpulseConstraintSolver* sol;
-	/// Keep here for garbage collection
-	std::unique_ptr<btIDebugDraw> debugDrawer;
-	F32 defaultContactProcessingThreshold;
-
-	SceneVector<Character*> characters;
 };
 
+/// @}
+
 } // end namespace anki
 
 #endif

+ 0 - 65
include/anki/physics/Ragdoll.h

@@ -1,65 +0,0 @@
-// Copyright (C) 2014, Panagiotis Christopoulos Charitos.
-// All rights reserved.
-// Code licensed under the BSD License.
-// http://www.anki3d.org/LICENSE
-
-/*#ifndef ANKI_PHYSICS__RAGDOLL_H_
-#define ANKI_PHYSICS__RAGDOLL_H_
-
-#include "anki/physics/PhyCommon.h"
-
-
-class Ragdoll
-{
-	public:
-		enum
-		{
-			BP_PELVIS,
-			BP_SPINE,
-			BP_HEAD,
-
-			BP_LEFrustumType::UPPER_ARM,
-			BP_LEFrustumType::LOWER_ARM,
-			BP_LEFrustumType::PALM,
-			BP_LEFrustumType::UPPER_LEG,
-			BP_LEFrustumType::LOWER_LEG,
-			BP_LEFrustumType::FOOT,
-
-			BP_RIGHT_UPPER_ARM,
-			BP_RIGHT_LOWER_ARM,
-			BP_RIGHT_PALM,
-			BP_RIGHT_UPPER_LEG,
-			BP_RIGHT_LOWER_LEG,
-			BP_RIGHT_FOOT,
-
-			BP_NUM
-		};
-
-		enum
-		{
-			JOINT_PELVIS_SPINE,
-			JOINT_SPINE_HEAD,
-
-			JOINT_LEFrustumType::SHOULDER,
-			JOINT_LEFrustumType::ELBOW,
-			JOINT_LEFrustumType::WRIST,
-			JOINT_LEFrustumType::HIP,
-			JOINT_LEFrustumType::KNEE,
-			JOINT_LEFrustumType::ANKLE,
-
-			JOINT_RIGHT_SHOULDER,
-			JOINT_RIGHT_ELBOW,
-			JOINT_RIGHT_WRIST,
-			JOINT_RIGHT_HIP,
-			JOINT_RIGHT_KNEE,
-			JOINT_RIGHT_ANKLE,
-
-			JOINT_NUM
-		};
-
-		btRigidBody*       bodies[BP_NUM];
-		btTypedConstraint* joints[JOINT_NUM];
-};
-
-
-#endif */

+ 0 - 60
include/anki/physics/RigidBody.h

@@ -1,60 +0,0 @@
-// Copyright (C) 2014, Panagiotis Christopoulos Charitos.
-// All rights reserved.
-// Code licensed under the BSD License.
-// http://www.anki3d.org/LICENSE
-
-#ifndef ANKI_PHYSICS_RIGID_BODY_H
-#define ANKI_PHYSICS_RIGID_BODY_H
-
-#include "anki/physics/PhysicsObject.h"
-#include "anki/scene/SceneComponent.h"
-#include "anki/Math.h"
-#include "anki/physics/MotionState.h"
-#include <btBulletDynamicsCommon.h>
-#include <btBulletCollisionCommon.h>
-
-namespace anki {
-
-class MoveComponent;
-
-/// Wrapper for rigid body
-class RigidBody: public PhysicsObject, public btRigidBody, 
-	public SceneComponent
-{
-	friend class PhysicsWorld;
-
-public:
-	/// Initializer class
-	struct Initializer
-	{
-		F32 mass = 0.0;
-		Transform startTrf = Transform::getIdentity();
-		btCollisionShape* shape = nullptr;
-		I32 group = -1;
-		I32 mask = -1;
-		Bool kinematic = false;
-		SceneNode* node = nullptr;
-	};
-
-	/// Init and register. Only the PhysicsWorld can construct it
-	RigidBody(PhysicsWorld* world, const Initializer& init);
-
-	/// Unregister. Only the PhysicsWorld can destroy it
-	~RigidBody();
-
-	/// Override SceneComponent::update
-	Bool update(SceneNode& node, F32 prevTime, F32 crntTime,
-		UpdateType updateType) override;
-
-	static constexpr Type getClassType()
-	{
-		return RIGID_BODY;
-	}
-
-private:
-	MotionState motionState;
-};
-
-} // end namespace anki
-
-#endif

+ 0 - 42
include/anki/renderer/DebugDrawer.h

@@ -13,7 +13,6 @@
 #include "anki/scene/Forward.h"
 #include "anki/util/Array.h"
 #include <unordered_map>
-#include <LinearMath/btIDebugDraw.h>
 
 namespace anki {
 
@@ -122,47 +121,6 @@ private:
 	DebugDrawer* m_dbg; ///< The debug drawer
 };
 
-/// An implementation of btIDebugDraw used for debugging Bullet. See Bullet
-/// docs for details
-class PhysicsDebugDrawer: public btIDebugDraw
-{
-public:
-	PhysicsDebugDrawer(DebugDrawer* dbg)
-		: m_dbg(dbg)
-	{}
-
-	void drawLine(const btVector3& from, const btVector3& to,
-		const btVector3& color);
-
-	void drawContactPoint(const btVector3& pointOnB,
-		const btVector3& normalOnB, btScalar distance, int lifeTime,
-		const btVector3& color);
-
-	void drawSphere(btScalar radius, const btTransform& transform,
-		const btVector3& color);
-
-	void drawBox(const btVector3& bbMin, const btVector3& bbMax,
-		const btVector3& color);
-
-	void drawBox(const btVector3& bbMin, const btVector3& bbMax,
-		const btTransform& trans, const btVector3& color);
-
-	void reportErrorWarning(const char* warningString);
-	void draw3dText(const btVector3& location, const char* textString);
-	void setDebugMode(int debugMode)
-	{
-		m_debugMode = debugMode;
-	}
-	int getDebugMode() const
-	{
-		return m_debugMode;
-	}
-
-private:
-	int m_debugMode;
-	DebugDrawer* m_dbg;
-};
-
 // Forward
 class Renderer;
 

+ 0 - 8
include/anki/resource/Model.h

@@ -16,8 +16,6 @@
 #include "anki/resource/Animation.h"
 #include "anki/util/Vector.h"
 
-class btCollisionShape;
-
 namespace anki {
 
 /// Model patch interface class. Its very important class and it binds the
@@ -169,11 +167,6 @@ public:
 	{
 		return m_visibilityShape;
 	}
-
-	const btCollisionShape* getCollisionShape() const
-	{
-		return m_collShape.get();
-	}
 	/// @}
 
 	void load(const char* filename);
@@ -184,7 +177,6 @@ private:
 	Obb m_visibilityShape;
 	SkeletonResourcePointer m_skeleton;
 	Vector<AnimationResourcePointer> m_animations;
-	std::unique_ptr<btCollisionShape> m_collShape;
 };
 
 } // end namespace anki

+ 0 - 1
include/anki/scene/ParticleEmitter.h

@@ -10,7 +10,6 @@
 #include "anki/scene/MoveComponent.h"
 #include "anki/scene/SpatialComponent.h"
 #include "anki/scene/RenderComponent.h"
-#include "anki/physics/RigidBody.h"
 #include "anki/resource/ParticleEmitterResource.h"
 
 namespace anki {

+ 118 - 22
src/collision/GjkEpa.cpp

@@ -9,6 +9,10 @@
 
 namespace anki {
 
+//==============================================================================
+// Gjk                                                                         =
+//==============================================================================
+
 //==============================================================================
 Vec4 Gjk::support(const ConvexShape& shape0, const ConvexShape& shape1,
 	const Vec4& dir)
@@ -21,25 +25,7 @@ Vec4 Gjk::support(const ConvexShape& shape0, const ConvexShape& shape1,
 //==============================================================================
 Bool Gjk::update(const Vec4& a)
 {
-	if(m_count == 0)
-	{
-		m_b = a;
-		m_dir = -a;
-		++m_count;
-
-		return false;
-	}
-	else if(m_count == 1)
-	{
-		m_dir = crossAba(m_b - a, -a);
- 
-		m_c = m_b;
-		m_b = a;
-		++m_count;
-
-		return false;
-	}
-	else if(m_count == 2)
+	if(m_count == 2)
 	{
 		Vec4 ao = -a;
 		 
@@ -94,7 +80,7 @@ Bool Gjk::update(const Vec4& a)
 			m_dir = -abc;
 		}
 		 
-		++m_count;
+		m_count = 3;
 		 
 		// Again, need a tetrahedron to enclose the origin
 		return false;
@@ -149,6 +135,8 @@ Bool Gjk::update(const Vec4& a)
 		}
 		 
 		// Behind all three faces, the origin is in the tetrahedron, we're done
+		m_a = a;
+		m_count = 4;
 		return true;
 		 
 check_face:
@@ -176,7 +164,7 @@ check_face:
 		{
 			m_b = a;
 		 
-			m_dir = crossAba(ac,ao);
+			m_dir = crossAba(ac, ao);
 		 
 			m_count = 2;
 			return false;
@@ -199,8 +187,26 @@ check_face:
 //==============================================================================
 Bool Gjk::intersect(const ConvexShape& shape0, const ConvexShape& shape1)
 {
+	// Chose random direction
 	m_dir = Vec4(1.0, 0.0, 0.0, 0.0);
-	m_count = 0;
+
+	// Do cases 1, 2
+	m_c = support(shape0, shape1, m_dir);
+	if(m_c.dot(m_dir) < 0.0)
+	{
+		return false;
+	}
+ 
+	m_dir = -m_c;
+	m_b = support(shape0, shape1, m_dir);
+
+	if(m_b.dot(m_dir) < 0.0)
+	{
+		return false;
+	}
+
+	m_dir = crossAba(m_c - m_b, -m_b);
+	m_count = 2;
 
 	while(1)
 	{
@@ -218,5 +224,95 @@ Bool Gjk::intersect(const ConvexShape& shape0, const ConvexShape& shape1)
 	}
 }
 
+//==============================================================================
+// GjkEpa                                                                      =
+//==============================================================================
+
+//==============================================================================
+Bool GjkEpa::intersect(const ConvexShape& shape0, const ConvexShape& shape1,
+	ContactPoint& contact)
+{
+#if 0
+	// Do the intersection test
+	if(!intersect(shape0, shape1))
+	{
+		return false;
+	}
+
+	// Set the array simplex
+	ANKI_ASSER(m_count == 4);
+	m_simplex[0] = m_a;
+	m_simplex[1] = m_b;
+	m_simplex[2] = m_c;
+	m_simplex[3] = m_d;
+
+	while(1) 
+	{
+		F32 distance;
+		Vec4 normal;
+		U index;
+		findClosestEdge(distance, normal, index);	
+		
+		// Get new support
+		Vec4 p = support(shape0, shape1, normal);
+		F32 d = p.dot(e.normal);
+		if(d - e.distance < TOLERANCE) 
+		{
+			contact.m_normal = normal;
+			contact.m_depth = d;
+			break;
+		} 
+		else 
+		{
+			m_simplex[index] = p;
+		}
+	}
+#endif
+}
+
+//==============================================================================
+void GjkEpa::findClosestEdge(F32& distance, Vec4& normal, U& index)
+{
+#if 0
+	distance = F32_MAX;
+
+	// Iterate the simplex
+	for(U i = 0; i < m_count; i++) 
+	{
+		// Compute the next points index
+		U j = i + 1;
+		if(j == m_count)
+		{
+			j = 0;
+		}
+
+		Vec4 a = m_simplex[i];
+		Vec4 b = m_simplex[j];
+		
+		// Create the edge vector
+		Vec4 e = b - a;
+
+		// Get the vector from the origin to a
+		Vec4 oa = a;
+
+		// Get the vector from the edge towards the origin
+		Vec4 n = crossAba(e, oa);
+		n.normalize();
+
+		// Calculate the distance from the origin to the edge
+		F32 d = n.dot(a);
+
+		// Check the distance against the other distances
+		if(d < distance) 
+		{
+			// if this edge is closer then use it
+			distance = d;
+			normal = n;
+			index = j;
+		}
+	}
+#endif
+}
+
 } // end namespace anki
 

+ 52 - 40
src/collision/Obb.cpp

@@ -32,6 +32,18 @@ Obb::Obb(const Vec4& center, const Mat3x4& rotation, const Vec4& extend)
 		m_extend(extend)
 {}
 
+//==============================================================================
+Obb& Obb::operator=(const Obb& b)
+{
+	m_center = b.m_center;
+	m_rotation = b.m_rotation;
+	m_extend = b.m_extend;
+	
+	m_cache = b.m_cache;
+
+	return *this;
+}
+
 //==============================================================================
 F32 Obb::testPlane(const Plane& p) const
 {
@@ -98,6 +110,15 @@ Obb Obb::getCompoundShape(const Obb& b) const
 //==============================================================================
 void Obb::getExtremePoints(Array<Vec4, 8>& points) const
 {
+	if(!m_cache.m_dirtyExtremePoints)
+	{
+		points = m_cache.m_extremePoints;
+		return;
+	}
+
+	m_cache.m_dirtyExtremePoints = false;
+	
+
 	// L: left, R: right, T: top, B: bottom, F: front, B: back
 	enum
 	{
@@ -135,11 +156,22 @@ void Obb::getExtremePoints(Array<Vec4, 8>& points) const
 	{
 		point += m_center;
 	}
+
+	// Update cache
+	m_cache.m_extremePoints = points;
 }
 
 //==============================================================================
 void Obb::computeAabb(Aabb& aabb) const
 {
+	// Check cache
+	if(!m_cache.m_dirtyAabb)
+	{
+		aabb = m_cache.m_aabb;
+		return;
+	}
+	m_cache.m_dirtyAabb = false;
+
 	Mat3x4 absM;
 	for(U i = 0; i < 12; ++i)
 	{
@@ -152,6 +184,9 @@ void Obb::computeAabb(Aabb& aabb) const
 	Vec4 epsilon(Vec3(getEpsilon<F32>() * 100.0), 0.0);
 	aabb = Aabb(m_center - newE, 
 		m_center + newE + epsilon);
+
+	// Update cache
+	m_cache.m_aabb = aabb;
 }
 
 //==============================================================================
@@ -180,54 +215,31 @@ void Obb::setFromPointCloud(
 	m_center = (max + min) / 2.0;
 	m_rotation = Mat3x4::getIdentity();
 	m_extend = max - m_center;
+
+	// Invalidate cache
+	makeDirty();
 }
 
 //==============================================================================
 Vec4 Obb::computeSupport(const Vec4& dir) const
 {
-	Vec4 out(0.0);
-
-	Vec3 er3 = m_rotation * m_extend; // extend rotated
-	Vec4 er(er3, 0.0);
-
-	Vec4 xAxis = Vec4(m_rotation.getColumn(0), 0.0);
-	Vec4 yAxis = Vec4(m_rotation.getColumn(1), 0.0);
-	Vec4 zAxis = Vec4(m_rotation.getColumn(2), 0.0);
+	Array<Vec4, 8> points;
+	getExtremePoints(points);
 
-	if(dir.dot(xAxis) >= 0.0)
+	U best = 0;
+	F32 bestDot = points[0].dot(dir);
+ 
+	for(U i = 1; i < points.size(); i++)
 	{
-		// Right side of the box
-
-		out.x() = er.x();
-	}
-	else
-	{
-		out.x() = -er.x();
-	}
-
-	if(dir.dot(yAxis) >= 0.0)
-	{
-		// Top side
-
-		out.y() = er.y();
-	}
-	else
-	{
-		out.y() = -er.y();
-	}
-
-	if(dir.dot(zAxis) >= 0.0)
-	{
-		// Front side
-
-		out.z() = er.z();
-	}
-	else
-	{
-		out.z() = -er.z();
+		F32 d = points[i].dot(dir);
+		if(d > bestDot)
+		{
+			best = i;
+			bestDot = d;
+		}
 	}
-
-	return out;
+ 
+	return points[best];
 }
 
 } // end namespace anki

+ 1 - 1
src/core/Logger.cpp

@@ -14,7 +14,7 @@
 namespace anki {
 
 //==============================================================================
-void Logger::init(InitFlags flags, HeapAllocator<U8>& alloc)
+Logger::Logger(InitFlags flags, HeapAllocator<U8>& alloc)
 {
 	if((flags & InitFlags::WITH_SYSTEM_MESSAGE_HANDLER) != InitFlags::NONE)
 	{

+ 0 - 120
src/physics/Character.cpp

@@ -1,120 +0,0 @@
-// Copyright (C) 2014, Panagiotis Christopoulos Charitos.
-// All rights reserved.
-// Code licensed under the BSD License.
-// http://www.anki3d.org/LICENSE
-
-#include "anki/physics/Character.h"
-#include "anki/physics/PhysicsWorld.h"
-#include "anki/physics/MotionState.h"
-#include "anki/physics/RigidBody.h"
-#include "anki/physics/PhysicsWorld.h"
-#include <algorithm>
-#include <btBulletCollisionCommon.h>
-#include <btBulletDynamicsCommon.h>
-#include <BulletCollision/CollisionDispatch/btGhostObject.h>
-#include <BulletDynamics/Character/btKinematicCharacterController.h>
-
-namespace anki {
-
-#if 0
-
-//==============================================================================
-// Character::Initializer                                                      = 
-//==============================================================================
-
-//==============================================================================
-inline Character::Initializer::Initializer()
-	: characterHeight(2.0),
-		characterWidth(0.75),
-		stepHeight(1.0),
-		jumpSpeed(10.0),
-		maxJumpHeight(0.0),
-		movable(nullptr),
-		startTrf(Transform::getIdentity())
-{}
-
-//==============================================================================
-// Character                                                                   = 
-//==============================================================================
-
-//==============================================================================
-Character::Character(PhysicsWorld* masterContainer_,
-	const Initializer& init)
-	: masterContainer(masterContainer_)
-{
-	ghostObject = new btPairCachingGhostObject();
-
-	motionState.reset(new MotionState(init.startTrf, init.movable));
-
-	btAxisSweep3* sweepBp =
-		static_cast<btAxisSweep3*>(masterContainer->broadphase);
-	ANKI_ASSERT(sweepBp != nullptr);
-
-	ghostPairCallback = new btGhostPairCallback();
-	sweepBp->getOverlappingPairCache()->setInternalGhostPairCallback(
-		ghostPairCallback);
-	//collisionShape = new btCapsuleShape(init.characterWidth,
-	//	init.characterHeight);
-	convexShape = new btCylinderShape(btVector3(init.characterWidth,
-		init.characterHeight, init.characterWidth));
-
-	ghostObject->setCollisionShape(convexShape);
-	//ghostObject->setCollisionFlags(btCollisionObject::CF_CHARACTER_OBJECT);
-	ghostObject->setWorldTransform(toBt(init.startTrf));
-
-	character = new btKinematicCharacterController(ghostObject, convexShape,
-		init.stepHeight);
-
-	character->setJumpSpeed(init.jumpSpeed);
-	character->setMaxJumpHeight(init.maxJumpHeight);
-
-	// register
-	masterContainer->dynamicsWorld->addCollisionObject(ghostObject,
-		btBroadphaseProxy::CharacterFilter,
-		btBroadphaseProxy::StaticFilter|btBroadphaseProxy::DefaultFilter);
-
-	masterContainer->dynamicsWorld->addAction(character);
-
-	masterContainer->characters.push_back(this);
-}
-
-//==============================================================================
-Character::~Character()
-{
-	masterContainer->characters.erase(std::find(
-		masterContainer->characters.begin(),
-		masterContainer->characters.end(), this));
-	masterContainer->dynamicsWorld->removeAction(character);
-	masterContainer->dynamicsWorld->removeCollisionObject(ghostObject);
-
-	delete character;
-	delete convexShape;
-	delete ghostPairCallback;
-	delete ghostObject;
-}
-
-//==============================================================================
-void Character::rotate(float angle)
-{
-	btMatrix3x3 rot = ghostObject->getWorldTransform().getBasis();
-	rot *= btMatrix3x3(btQuaternion(btVector3(0, 1, 0), angle));
-	ghostObject->getWorldTransform().setBasis(rot);
-}
-
-//==============================================================================
-void Character::moveForward(float distance)
-{
-	btVector3 forward =
-		-ghostObject->getWorldTransform().getBasis().getColumn(2);
-	character->setWalkDirection(forward * distance);
-}
-
-//==============================================================================
-void Character::jump()
-{
-	character->jump();
-}
-
-#endif
-
-} // end namespace

+ 0 - 18
src/physics/PhysicsObject.cpp

@@ -1,18 +0,0 @@
-// Copyright (C) 2014, Panagiotis Christopoulos Charitos.
-// All rights reserved.
-// Code licensed under the BSD License.
-// http://www.anki3d.org/LICENSE
-
-#include "anki/physics/PhysicsObject.h"
-#include "anki/physics/PhysicsWorld.h"
-
-namespace anki {
-
-//==============================================================================
-SceneAllocator<U8> PhysicsObject::getSceneAllocator() const
-{
-	return world->getSceneAllocator();
-}
-
-} // end namespace anki
-

+ 3 - 72
src/physics/PhysicsWorld.cpp

@@ -4,84 +4,15 @@
 // http://www.anki3d.org/LICENSE
 
 #include "anki/physics/PhysicsWorld.h"
-#include "anki/scene/SceneGraph.h"
-#include "anki/physics/Character.h"
-#include "anki/physics/MotionState.h"
-#include <BulletCollision/CollisionDispatch/btGhostObject.h>
 
 namespace anki {
 
 //==============================================================================
-PhysicsWorld::PhysicsWorld(SceneGraph* scene_)
-	:	scene(scene_),
-		defaultContactProcessingThreshold(BT_LARGE_FLOAT),
-		characters(getSceneAllocator())
-
-{
-	SceneAllocator<U8> alloc = getSceneAllocator();
-
-	collisionConfiguration = 
-		alloc.newInstance<btDefaultCollisionConfiguration>();
-
-	dispatcher = alloc.newInstance<btCollisionDispatcher>(
-		collisionConfiguration);
-
-	broadphase = alloc.newInstance<btAxisSweep3>(
-		btVector3(-1000, -1000, -1000),
-		btVector3(1000, 1000, 1000));
-
-	sol = alloc.newInstance<btSequentialImpulseConstraintSolver>();
-
-	dynamicsWorld = alloc.newInstance<btDiscreteDynamicsWorld>(
-		dispatcher, broadphase, sol, collisionConfiguration);
-
-	dynamicsWorld->setGravity(btVector3(0, -10, 0));
-}
+PhysicsWorld::PhysicsWorld()
+{}
 
 //==============================================================================
 PhysicsWorld::~PhysicsWorld()
-{
-	SceneAllocator<U8> alloc = getSceneAllocator();
-
-	alloc.deleteInstance(dynamicsWorld);
-	alloc.deleteInstance(sol);
-	alloc.deleteInstance(broadphase);
-	alloc.deleteInstance(dispatcher);
-	alloc.deleteInstance(collisionConfiguration);
-}
-
-//==============================================================================
-SceneAllocator<U8> PhysicsWorld::getSceneAllocator() const
-{
-	return scene->getAllocator();
-}
-
-//==============================================================================
-void PhysicsWorld::setDebugDrawer(btIDebugDraw* newDebugDrawer)
-{
-	debugDrawer.reset(newDebugDrawer);
-	dynamicsWorld->setDebugDrawer(debugDrawer.get());
-	debugDrawer->setDebugMode(btIDebugDraw::DBG_DrawWireframe);
-}
-
-//==============================================================================
-void PhysicsWorld::update(F32 prevUpdateTime, F32 crntTime)
-{
-	F32 dt = crntTime - prevUpdateTime;
-	dynamicsWorld->stepSimulation(dt);
-
-	// updateNonRigidBodiesMotionStates
-	for(U i = 0; i < characters.size(); i++)
-	{
-		characters[i]->motionState->setWorldTransform(
-			characters[i]->ghostObject->getWorldTransform());
-	}
-}
-
-//==============================================================================
-void PhysicsWorld::debugDraw()
-{
-	dynamicsWorld->debugDrawWorld();
-}
+{}
 
 } // end namespace anki

+ 0 - 114
src/physics/RigidBody.cpp

@@ -1,114 +0,0 @@
-// Copyright (C) 2014, Panagiotis Christopoulos Charitos.
-// All rights reserved.
-// Code licensed under the BSD License.
-// http://www.anki3d.org/LICENSE
-
-#include "anki/physics/RigidBody.h"
-#include "anki/physics/PhysicsWorld.h"
-#include "anki/scene/SceneGraph.h"
-#include "anki/scene/MoveComponent.h"
-
-namespace anki {
-
-//==============================================================================
-RigidBody::RigidBody(PhysicsWorld* world, const Initializer& init)
-	:	PhysicsObject(world),
-		btRigidBody(btRigidBody::btRigidBodyConstructionInfo(0.0, nullptr, 
-			nullptr, btVector3(0.0, 0.0, 0.0))), // dummy init
-		SceneComponent(RIGID_BODY, init.node)
-{
-	ANKI_ASSERT(init.shape != nullptr 
-		&& init.shape->getShapeType() != INVALID_SHAPE_PROXYTYPE);
-
-	Bool isDynamic = (init.mass != 0.0);
-
-	btVector3 localInertia;
-	if(isDynamic)
-	{
-		init.shape->calculateLocalInertia(init.mass, localInertia);
-	}
-	else
-	{
-		localInertia = btVector3(0.0, 0.0, 0.0);
-	}
-
-	motionState = MotionState(toBt(init.startTrf));
-
-	btRigidBody::btRigidBodyConstructionInfo cInfo(
-		init.mass, &motionState, init.shape, localInertia);
-
-	setupRigidBody(cInfo);
-
-	setContactProcessingThreshold(
-		getPhysicsWorld().defaultContactProcessingThreshold);
-
-	if(init.kinematic)
-	{
-		// XXX
-	}
-
-	//forceActivationState(ISLAND_SLEEPING);
-
-	// register
-	if(init.mask == -1 || init.group == -1)
-	{
-		getPhysicsWorld().dynamicsWorld->addRigidBody(this);
-	}
-	else
-	{
-		getPhysicsWorld().dynamicsWorld->addRigidBody(
-			this, init.group, init.mask);
-	}
-}
-
-//==============================================================================
-RigidBody::~RigidBody()
-{
-	getPhysicsWorld().dynamicsWorld->removeRigidBody(this);
-}
-
-//==============================================================================
-Bool RigidBody::update(SceneNode& node, F32 prevTime, F32 crntTime,
-	UpdateType updateType)
-{
-	if(updateType == ASYNC_UPDATE)
-	{
-		return false;
-	}
-
-	MoveComponent* move = node.tryGetComponent<MoveComponent>();
-	if(ANKI_UNLIKELY(move == nullptr))
-	{
-		return false;
-	}
-
-	//Bool moveUpdated = move->bitsEnabled(MoveComponent::MF_MARKED_FOR_UPDATE);
-	//Transform oldTrf = move->getLocalTransform();
-
-	Bool mstateUpdated = motionState.getUpdated();
-
-	// Sync from motion state to move component
-	if(mstateUpdated)
-	{
-		// Set local transform and preserve scale
-		Transform newTrf;
-		F32 originalScale = move->getLocalTransform().getScale();
-		newTrf = toAnki(motionState.getWorldTransform2());
-		newTrf.setScale(originalScale);
-		move->setLocalTransform(newTrf);
-
-		// Set the flag
-		motionState.setUpdated(false);
-	}
-
-	// Sync from move component to motion state
-	/*if(moveUpdated)
-	{
-		setWorldTransform(toBt(oldTrf));
-		activate();
-	}*/
-
-	return mstateUpdated;
-}
-
-} // end namespace anki

+ 13 - 4
src/renderer/Dbg.cpp

@@ -99,7 +99,7 @@ void Dbg::run(GlJobChainHandle& jobs)
 	// Physics
 	if(bitsEnabled(DF_PHYSICS))
 	{
-		scene.getPhysics().debugDraw();
+		//scene.getPhysics().debugDraw();
 	}
 
 	// XXX
@@ -192,14 +192,14 @@ void Dbg::run(GlJobChainHandle& jobs)
 			getComponent<MoveComponent>().getWorldTransform().getRotation();
 
 
-		Aabb s0(pos0 - Vec4(1.01, 1.0, 2.02, 0.0), pos0 + Vec4(1.0, 1.0, 2.0, 0.0));
-		Obb s1(pos1, rot1, Vec4(1.01, 0.501, 2.51, 0.0));
+		Aabb s0(pos0 - Vec4(1.0, 1.0, 2.0, 0.0), pos0 + Vec4(1.0, 1.0, 2.0, 0.0));
+		Obb s1(pos1, rot1, Vec4(1.0, 0.5, 2.5, 0.0));
 
 		CollisionDebugDrawer dr(m_drawer.get());
 
 		Gjk gjk;
 
-		Bool intersect = gjk.intersect(s1, s0);
+		Bool intersect = gjk.intersect(s0, s1);
 
 
 		if(intersect)
@@ -213,6 +213,15 @@ void Dbg::run(GlJobChainHandle& jobs)
 
 		s0.accept(dr);
 		s1.accept(dr);
+
+		/*m_drawer->setColor(Vec4(0.0, 1.0, 0.0, 1.0));
+		m_drawer->setModelMatrix(Mat4::getIdentity());
+		m_drawer->begin();
+		m_drawer->pushBackVertex(gjk.m_a.xyz());
+		m_drawer->pushBackVertex(gjk.m_b.xyz());
+		m_drawer->pushBackVertex(gjk.m_b.xyz());
+		m_drawer->pushBackVertex(gjk.m_c.xyz());
+		m_drawer->end();*/
 	}
 #endif
 

+ 0 - 76
src/renderer/DebugDrawer.cpp

@@ -5,7 +5,6 @@
 
 #include "anki/renderer/DebugDrawer.h"
 #include "anki/resource/ProgramResource.h"
-#include "anki/physics/Converters.h"
 #include "anki/Collision.h"
 #include "anki/Scene.h"
 #include "anki/resource/TextureResource.h"
@@ -381,81 +380,6 @@ void CollisionDebugDrawer::visit(const Frustum& f)
 	}
 }
 
-//==============================================================================
-// PhysicsDebugDrawer                                                          =
-//==============================================================================
-
-//==============================================================================
-void PhysicsDebugDrawer::drawLine(const btVector3& from, const btVector3& to,
-	const btVector3& color)
-{
-	m_dbg->drawLine(toAnki(from), toAnki(to), Vec4(toAnki(color), 1.0));
-}
-
-//==============================================================================
-void PhysicsDebugDrawer::drawSphere(btScalar radius,
-	const btTransform& transform,
-	const btVector3& color)
-{
-	m_dbg->setColor(toAnki(color));
-	m_dbg->setModelMatrix(Mat4(toAnki(transform)));
-	m_dbg->drawSphere(radius);
-}
-
-//==============================================================================
-void PhysicsDebugDrawer::drawBox(const btVector3& min, const btVector3& max,
-	const btVector3& color)
-{
-	Mat4 trf(Mat4::getIdentity());
-	trf(0, 0) = max.getX() - min.getX();
-	trf(1, 1) = max.getY() - min.getY();
-	trf(2, 2) = max.getZ() - min.getZ();
-	trf(0, 3) = (max.getX() + min.getX()) / 2.0;
-	trf(1, 3) = (max.getY() + min.getY()) / 2.0;
-	trf(2, 3) = (max.getZ() + min.getZ()) / 2.0;
-	m_dbg->setModelMatrix(trf);
-	m_dbg->setColor(toAnki(color));
-	m_dbg->drawCube(1.0);
-}
-
-//==============================================================================
-void PhysicsDebugDrawer::drawBox(const btVector3& min, const btVector3& max,
-	const btTransform& trans, const btVector3& color)
-{
-	Mat4 trf(Mat4::getIdentity());
-	trf(0, 0) = max.getX() - min.getX();
-	trf(1, 1) = max.getY() - min.getY();
-	trf(2, 2) = max.getZ() - min.getZ();
-	trf(0, 3) = (max.getX() + min.getX()) / 2.0;
-	trf(1, 3) = (max.getY() + min.getY()) / 2.0;
-	trf(2, 3) = (max.getZ() + min.getZ()) / 2.0;
-	trf = Mat4::combineTransformations(Mat4(toAnki(trans)), trf);
-	m_dbg->setModelMatrix(trf);
-	m_dbg->setColor(toAnki(color));
-	m_dbg->drawCube(1.0);
-}
-
-//==============================================================================
-void PhysicsDebugDrawer::drawContactPoint(const btVector3& /*pointOnB*/,
-	const btVector3& /*normalOnB*/,
-	btScalar /*distance*/, int /*lifeTime*/, const btVector3& /*color*/)
-{
-	//ANKI_LOGW("Unimplemented");
-}
-
-//==============================================================================
-void PhysicsDebugDrawer::reportErrorWarning(const char* warningString)
-{
-	throw ANKI_EXCEPTION(warningString);
-}
-
-//==============================================================================
-void PhysicsDebugDrawer::draw3dText(const btVector3& /*location*/,
-	const char* /*textString*/)
-{
-	//ANKI_LOGW("Unimplemented");
-}
-
 //==============================================================================
 // SceneDebugDrawer                                                            =
 //==============================================================================

+ 4 - 6
src/resource/Model.cpp

@@ -8,8 +8,7 @@
 #include "anki/resource/Mesh.h"
 #include "anki/resource/ProgramResource.h"
 #include "anki/misc/Xml.h"
-#include "anki/physics/Converters.h"
-#include <btBulletCollisionCommon.h>
+#include "anki/core/Logger.h"
 
 namespace anki {
 
@@ -297,16 +296,15 @@ void Model::load(const char* filename)
 
 			if(type == "sphere")
 			{
-				m_collShape.reset(new btSphereShape(valEl.getFloat()));
+				ANKI_LOGW("TODO");
 			}
 			else if(type == "box")
 			{
-				Vec3 extend = valEl.getVec3();
-				m_collShape.reset(new btBoxShape(toBt(extend)));
+				ANKI_LOGW("TODO");
 			}
 			else if(type == "mesh")
 			{
-				ANKI_ASSERT(0 && "TODO");
+				ANKI_LOGW("TODO");
 			}
 			else
 			{

+ 4 - 1
src/scene/ModelNode.cpp

@@ -9,7 +9,6 @@
 #include "anki/scene/Misc.h"
 #include "anki/resource/Model.h"
 #include "anki/resource/Skeleton.h"
-#include "anki/physics/RigidBody.h"
 #include "anki/physics/PhysicsWorld.h"
 
 namespace anki {
@@ -233,6 +232,7 @@ ModelNode::ModelNode(
 	}
 
 	// Load rigid body
+#if 0
 	if(m_model->getCollisionShape() != nullptr)
 	{
 		RigidBody::Initializer init;
@@ -247,16 +247,19 @@ ModelNode::ModelNode(
 
 		addComponent(static_cast<RigidBody*>(body));
 	}
+#endif
 }
 
 //==============================================================================
 ModelNode::~ModelNode()
 {
+#if 0
 	RigidBody* body = tryGetComponent<RigidBody>();
 	if(body)
 	{
 		getSceneGraph().getPhysics().deletePhysicsObject(body);
 	}
+#endif
 }
 
 //==============================================================================

+ 2 - 3
src/scene/SceneGraph.cpp

@@ -12,7 +12,6 @@
 #include "anki/core/Counters.h"
 #include "anki/renderer/Renderer.h"
 #include "anki/misc/Xml.h"
-#include "anki/physics/RigidBody.h"
 
 namespace anki {
 
@@ -86,7 +85,7 @@ SceneGraph::SceneGraph(AllocAlignedCallback allocCb, void* allocCbUserData)
 			ANKI_SCENE_FRAME_ALLOCATOR_SIZE)),
 		m_nodes(m_alloc),
 		m_dict(10, DictionaryHasher(), DictionaryEqual(), m_alloc),
-		m_physics(this),
+		m_physics(),
 		m_sectorGroup(this),
 		m_events(this)
 {
@@ -230,7 +229,7 @@ void SceneGraph::update(F32 prevUpdateTime, F32 crntTime, Renderer& renderer)
 	(void)threadPool;
 
 	// XXX Do that in parallel
-	m_physics.update(prevUpdateTime, crntTime);
+	//m_physics.update(prevUpdateTime, crntTime);
 	renderer.getTiler().updateTiles(*m_mainCam);
 	m_events.updateAllEvents(prevUpdateTime, crntTime);
 

+ 3 - 5
src/util/Memory.cpp

@@ -648,11 +648,7 @@ public:
 			crntMaxSize = std::min(crntMaxSize, (PtrSize)m_maxSize);
 		}
 
-		size = std::max(crntMaxSize, size) 
-			+ sizeof(StackMemoryPool::Implementation::MemoryBlockHeader)
-			+ m_alignmentBytes;
-
-		ANKI_ASSERT(size <= m_maxSize && "To big chunk");
+		size = std::max(crntMaxSize, size) + 16;
 
 		//
 		// Create the chunk
@@ -701,6 +697,8 @@ public:
 	/// Allocate memory
 	void* allocate(PtrSize size, PtrSize alignment) throw()
 	{
+		ANKI_ASSERT(size <= m_maxSize);
+
 		Chunk* ch;
 		void* mem = nullptr;
 

+ 2 - 5
testapp/Main.cpp

@@ -9,11 +9,8 @@
 #include "anki/resource/Mesh.h"
 #include "anki/resource/Material.h"
 #include "anki/resource/SkelAnim.h"
-#include "anki/physics/Character.h"
 #include "anki/renderer/Renderer.h"
 #include "anki/renderer/MainRenderer.h"
-#include "anki/physics/Character.h"
-#include "anki/physics/RigidBody.h"
 #include "anki/script/ScriptManager.h"
 #include "anki/core/StdinListener.h"
 #include "anki/resource/Model.h"
@@ -42,6 +39,7 @@ HeapAllocator<U8> globAlloc;
 //==============================================================================
 void initPhysics()
 {
+#if 0
 	SceneGraph& scene = SceneGraphSingleton::get();
 
 	btCollisionShape* groundShape = new btBoxShape(
@@ -60,7 +58,6 @@ void initPhysics()
 
 	new RigidBody(&SceneGraphSingleton::get().getPhysics(), init);
 
-#if 0
 	btCollisionShape* colShape = new btBoxShape(
 	    btVector3(1, 1, 1));
 
@@ -603,7 +600,7 @@ void initSubsystems(int argc, char* argv[])
 	globAlloc = HeapAllocator<U8>(HeapMemoryPool(allocAligned, nullptr));
 
 	// Logger
-	LoggerSingleton::get().init(
+	LoggerSingleton::init(
 		Logger::InitFlags::WITH_SYSTEM_MESSAGE_HANDLER, globAlloc);
 
 	// App

+ 4 - 3
tests/Main.cpp

@@ -10,16 +10,17 @@ using namespace anki;
 
 int main(int argc, char** argv)
 {
-	HeapAllocator<U8> alloc(HeapMemoryPool(0));
+	HeapAllocator<U8> alloc(HeapMemoryPool(allocAligned, nullptr));
 
 	// Call a few singletons to avoid memory leak confusion
-	LoggerSingleton::get();
-	LoggerSingleton::get().init(
+	LoggerSingleton::init(
 		Logger::InitFlags::WITH_SYSTEM_MESSAGE_HANDLER,
 		alloc);
 
 	int exitcode = getTesterSingleton().run(argc, argv);
 
+	LoggerSingleton::destroy();
+
 	deleteTesterSingleton();
 
 	return exitcode;

+ 2 - 1
tests/script/LuaBinder.cpp

@@ -16,7 +16,8 @@ v3:setZ(0.1)
 
 ANKI_TEST(Script, LuaBinder)
 {
-	ScriptManager sm;
+	HeapAllocator<U8> alloc(HeapMemoryPool(allocAligned, nullptr));
+	ScriptManager sm(alloc);
 	Vec2 v2(2.0, 3.0);
 	Vec3 v3(1.1, 2.2, 3.3);
 

+ 4 - 2
tests/util/Allocator.cpp

@@ -14,7 +14,8 @@ ANKI_TEST(Allocators, StackAllocator)
 
 	// With simple string
 	{
-		StackAllocator<char, false> alloc(128);
+		StackAllocator<char, false> alloc(
+			StackMemoryPool(allocAligned, nullptr, 128));
 		typedef std::basic_string<char, std::char_traits<char>, 
 			StackAllocator<char, false>> Str;
 
@@ -27,7 +28,8 @@ ANKI_TEST(Allocators, StackAllocator)
 	// With vector
 	{
 		typedef StackAllocator<Foo, false> All;
-		All alloc(StackMemoryPool((sizeof(Foo) + 1) * 10, 1));
+		All alloc(StackMemoryPool(allocAligned, nullptr, 
+			(sizeof(Foo) + 1) * 10, 1));
 		std::vector<Foo, All> vec(alloc);
 
 		vec.reserve(10);

+ 20 - 12
tests/util/Memory.cpp

@@ -41,17 +41,16 @@ ANKI_TEST(Memory, ChainMemoryPool)
 {
 	// Basic test
 	{
-		const U size = sizeof(PtrSize) + 10;
+		const U size = 8;
 		ChainMemoryPool pool(
-			size, size, ChainMemoryPool::MULTIPLY, 2, 1);
+			allocAligned, nullptr,
+			size, size + 1, ChainMemoryPool::MULTIPLY, 2, 1);
 
-		void* mem = pool.allocate(1, 1);
+		void* mem = pool.allocate(5, 1);
 		ANKI_TEST_EXPECT_NEQ(mem, nullptr);
-		ANKI_TEST_EXPECT_EQ(pool.getChunksCount(), 1);
 
-		void* mem1 = pool.allocate(10, 1);
+		void* mem1 = pool.allocate(5, 1);
 		ANKI_TEST_EXPECT_NEQ(mem1, nullptr);
-		ANKI_TEST_EXPECT_EQ(pool.getChunksCount(), 2);
 
 		pool.free(mem1);
 		pool.free(mem);
@@ -62,18 +61,27 @@ ANKI_TEST(Memory, ChainMemoryPool)
 	{
 		const U size = sizeof(PtrSize) + 10;
 		ChainMemoryPool pool(
-			size, size, ChainMemoryPool::MULTIPLY, 2, 1);
+			allocAligned, nullptr,
+			size, size * 2, ChainMemoryPool::MULTIPLY, 2, 1);
 
-		void* mem = pool.allocate(1, 1);
+		void* mem = pool.allocate(size, 1);
 		ANKI_TEST_EXPECT_NEQ(mem, nullptr);
-		ANKI_TEST_EXPECT_EQ(pool.getChunksCount(), 1);
 
-		void* mem1 = pool.allocate(10, 1);
+		void* mem1 = pool.allocate(size, 1);
 		ANKI_TEST_EXPECT_NEQ(mem1, nullptr);
-		ANKI_TEST_EXPECT_EQ(pool.getChunksCount(), 2);
 
-		pool.free(mem);
+		void* mem3 = pool.allocate(size, 1);
+		ANKI_TEST_EXPECT_NEQ(mem1, nullptr);
+
+		pool.free(mem1);
+
+		mem1 = pool.allocate(size, 1);
+		ANKI_TEST_EXPECT_NEQ(mem1, nullptr);
+
+		pool.free(mem3);
 		pool.free(mem1);
+		pool.free(mem);
+
 		ANKI_TEST_EXPECT_EQ(pool.getChunksCount(), 0);
 	}
 }