Selaa lähdekoodia

Merge branch 'master' into gltf

Daniel Salvadori 7 vuotta sitten
vanhempi
commit
0954644078
81 muutettua tiedostoa jossa 6084 lisäystä ja 680 poistoa
  1. 9 0
      core/node.go
  2. 55 0
      experimental/physics/broadphase.go
  3. 15 0
      experimental/physics/collision/contact.go
  4. 63 0
      experimental/physics/collision/matrix.go
  5. 39 0
      experimental/physics/collision/matrix_test.go
  6. 83 0
      experimental/physics/constraint/conetwist.go
  7. 95 0
      experimental/physics/constraint/constraint.go
  8. 49 0
      experimental/physics/constraint/distance.go
  9. 86 0
      experimental/physics/constraint/hinge.go
  10. 95 0
      experimental/physics/constraint/lock.go
  11. 65 0
      experimental/physics/constraint/pointtopoint.go
  12. 94 0
      experimental/physics/debug.go
  13. 8 0
      experimental/physics/doc.go
  14. 88 0
      experimental/physics/equation/cone.go
  15. 124 0
      experimental/physics/equation/contact.go
  16. 245 0
      experimental/physics/equation/equation.go
  17. 82 0
      experimental/physics/equation/friction.go
  18. 51 0
      experimental/physics/equation/jacobian.go
  19. 89 0
      experimental/physics/equation/rotational.go
  20. 80 0
      experimental/physics/equation/rotationalmotor.go
  21. 164 0
      experimental/physics/forcefield.go
  22. 12 0
      experimental/physics/logger.go
  23. 43 0
      experimental/physics/material.go
  24. 643 0
      experimental/physics/narrowphase.go
  25. 769 0
      experimental/physics/object/body.go
  26. 31 0
      experimental/physics/particle.go
  27. 5 0
      experimental/physics/shape/box.go
  28. 6 0
      experimental/physics/shape/capsule.go
  29. 465 0
      experimental/physics/shape/convexhull.go
  30. 6 0
      experimental/physics/shape/cylinder.go
  31. 6 0
      experimental/physics/shape/heightfield.go
  32. 76 0
      experimental/physics/shape/plane.go
  33. 37 0
      experimental/physics/shape/shape.go
  34. 75 0
      experimental/physics/shape/sphere.go
  35. 583 0
      experimental/physics/simulation.go
  36. 139 0
      experimental/physics/solver/gs.go
  37. 59 0
      experimental/physics/solver/solver.go
  38. 18 4
      geometry/box.go
  39. 6 4
      geometry/circle.go
  40. 107 107
      geometry/cylinder.go
  41. 277 91
      geometry/geometry.go
  42. 144 0
      geometry/morph.go
  43. 11 3
      geometry/plane.go
  44. 9 5
      geometry/sphere.go
  45. 3 3
      geometry/torus.go
  46. 60 71
      gls/program.go
  47. 58 0
      gls/shaderdefines.go
  48. 140 52
      gls/vbo.go
  49. 2 2
      graphic/axis_helper.go
  50. 3 4
      graphic/grid_helper.go
  51. 1 1
      graphic/lines.go
  52. 12 52
      graphic/mesh.go
  53. 5 5
      graphic/normals_helper.go
  54. 6 24
      graphic/points.go
  55. 4 5
      graphic/sprite.go
  56. 3 4
      gui/chart.go
  57. 3 4
      gui/panel.go
  58. 5 13
      loader/collada/geometry.go
  59. 3 3
      loader/obj/obj.go
  60. 50 58
      material/material.go
  61. 1 2
      material/phong.go
  62. 10 10
      material/physical.go
  63. 154 14
      math32/matrix3.go
  64. 44 21
      math32/matrix4.go
  65. 28 8
      math32/quaternion.go
  66. 28 0
      math32/vector2.go
  67. 56 0
      math32/vector3.go
  68. 17 0
      math32/vector4.go
  69. 11 4
      renderer/renderer.go
  70. 3 4
      renderer/shaders/include/lights.glsl
  71. 6 0
      renderer/shaders/include/morphtarget_vertex.glsl
  72. 4 0
      renderer/shaders/include/morphtarget_vertex_declaration.glsl
  73. 4 0
      renderer/shaders/include/morphtarget_vertex_declaration2.glsl
  74. 0 2
      renderer/shaders/include/phong_model.glsl
  75. 4 1
      renderer/shaders/phong_vertex.glsl
  76. 6 1
      renderer/shaders/physical_vertex.glsl
  77. 1 1
      renderer/shaders/shaders.go
  78. 50 19
      renderer/shaders/sources.go
  79. 9 7
      renderer/shaders/standard_vertex.glsl
  80. 81 68
      renderer/shaman.go
  81. 3 3
      window/glfw.go

+ 9 - 0
core/node.go

@@ -12,6 +12,7 @@ import (
 
 // INode is the interface for all node types.
 type INode interface {
+	IDispatcher
 	GetNode() *Node
 	UpdateMatrixWorld()
 	Raycast(*Raycaster, *[]Intersect)
@@ -414,6 +415,14 @@ func (n *Node) SetRotationVec(vrot *math32.Vector3) {
 	n.changed = true
 }
 
+// SetRotationQuat sets the rotation based on the specified quaternion pointer.
+// The stored quaternion is updated accordingly.
+func (n *Node) SetRotationQuat(quat *math32.Quaternion) {
+
+	n.quaternion = *quat
+	n.changed = true
+}
+
 // SetRotationX sets the X rotation to the specified angle in radians.
 // The stored quaternion is updated accordingly.
 func (n *Node) SetRotationX(x float32) {

+ 55 - 0
experimental/physics/broadphase.go

@@ -0,0 +1,55 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+// Package collision implements collision related algorithms and data structures.
+package physics
+
+import (
+	"github.com/g3n/engine/experimental/physics/object"
+)
+
+// CollisionPair is a pair of bodies that may be colliding.
+type CollisionPair struct {
+	BodyA *object.Body
+	BodyB *object.Body
+}
+
+// Broadphase is the base class for broadphase implementations.
+type Broadphase struct {}
+
+// NewBroadphase creates and returns a pointer to a new Broadphase.
+func NewBroadphase() *Broadphase {
+
+	b := new(Broadphase)
+	return b
+}
+
+// FindCollisionPairs (naive implementation)
+func (b *Broadphase) FindCollisionPairs(objects []*object.Body) []CollisionPair {
+
+	pairs := make([]CollisionPair,0)
+
+	for iA, bodyA := range objects {
+		for _, bodyB := range objects[iA+1:] {
+			if b.NeedTest(bodyA, bodyB) {
+				BBa := bodyA.BoundingBox()
+				BBb := bodyB.BoundingBox()
+				if BBa.IsIntersectionBox(&BBb) {
+					pairs = append(pairs, CollisionPair{bodyA, bodyB})
+				}
+			}
+		}
+	}
+
+	return pairs
+}
+
+func (b *Broadphase) NeedTest(bodyA, bodyB *object.Body) bool {
+
+	if !bodyA.CollidableWith(bodyB) || (bodyA.Sleeping() && bodyB.Sleeping()) {
+		return false
+	}
+
+	return true
+}

+ 15 - 0
experimental/physics/collision/contact.go

@@ -0,0 +1,15 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+// Package collision implements collision related algorithms and data structures.
+package collision
+
+import "github.com/g3n/engine/math32"
+
+// Contact describes a contact point, normal, and depth.
+type Contact struct {
+	Point  math32.Vector3
+	Normal math32.Vector3
+	Depth  float32
+}

+ 63 - 0
experimental/physics/collision/matrix.go

@@ -0,0 +1,63 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+// Package collision implements collision related algorithms and data structures.
+package collision
+
+// Matrix is a triangular collision matrix indicating which pairs of bodies are colliding.
+type Matrix [][]bool
+
+// NewMatrix creates and returns a pointer to a new collision Matrix.
+func NewMatrix() Matrix {
+
+	return make([][]bool, 0)
+}
+
+// Set sets whether i and j are colliding.
+func (m *Matrix) Set(i, j int, val bool) {
+
+	var s, l int
+	if i < j {
+		s = i
+		l = j
+	} else {
+		s = j
+		l = i
+	}
+	diff := s + 1 - len(*m)
+	if diff > 0 {
+		for i := 0; i < diff; i++ {
+			*m = append(*m, make([]bool, 0))
+		}
+	}
+	for idx := range *m {
+		diff = l + 1 - len((*m)[idx]) - idx
+		if diff > 0 {
+			for i := 0; i < diff; i++ {
+				(*m)[idx] = append((*m)[idx], false)
+			}
+		}
+	}
+	(*m)[s][l-s] = val
+}
+
+// Get returns whether i and j are colliding.
+func (m *Matrix) Get(i, j int) bool {
+
+	var s, l int
+	if i < j {
+		s = i
+		l = j
+	} else {
+		s = j
+		l = i
+	}
+	return (*m)[s][l-s]
+}
+
+// Reset clears all values.
+func (m *Matrix) Reset() {
+
+	*m = make([][]bool, 0)
+}

+ 39 - 0
experimental/physics/collision/matrix_test.go

@@ -0,0 +1,39 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+// Package collision implements collision related algorithms and data structures.
+package collision
+
+import "testing"
+
+// Test simple matrix operations
+func Test(t *testing.T) {
+
+	m := NewMatrix()
+
+	// m.Get(1, 1) // panics with "runtime error: index out of range" as expected
+
+	m.Set(2,4, true)
+	m.Set(3,2, true)
+	if m.Get(1,1) != false {
+		t.Error("Get failed")
+	}
+	if m.Get(2,4) != true {
+		t.Error("Get failed")
+	}
+	if m.Get(3,2) != true {
+		t.Error("Get failed")
+	}
+
+	m.Set(2,4, false)
+	m.Set(3,2, false)
+	if m.Get(2,4) != false {
+		t.Error("Get failed")
+	}
+	if m.Get(3,2) != false {
+		t.Error("Get failed")
+	}
+
+	// m.Get(100, 100) // panics with "runtime error: index out of range" as expected
+}

+ 83 - 0
experimental/physics/constraint/conetwist.go

@@ -0,0 +1,83 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package constraint
+
+import (
+	"github.com/g3n/engine/math32"
+	"github.com/g3n/engine/experimental/physics/equation"
+)
+
+// ConeTwist constraint.
+type ConeTwist struct {
+	PointToPoint
+	axisA      *math32.Vector3 // Rotation axis, defined locally in bodyA.
+	axisB      *math32.Vector3 // Rotation axis, defined locally in bodyB.
+	coneEq     *equation.Cone
+	twistEq    *equation.Rotational
+	angle      float32
+	twistAngle float32
+}
+
+// NewConeTwist creates and returns a pointer to a new ConeTwist constraint object.
+func NewConeTwist(bodyA, bodyB IBody, pivotA, pivotB, axisA, axisB *math32.Vector3, angle, twistAngle, maxForce float32) *ConeTwist {
+
+	ctc := new(ConeTwist)
+
+	// Default of pivots and axes should be vec3(0)
+
+	ctc.initialize(bodyA, bodyB, pivotA, pivotB, maxForce)
+
+	ctc.axisA = axisA
+	ctc.axisB = axisB
+	ctc.axisA.Normalize()
+	ctc.axisB.Normalize()
+
+	ctc.angle = angle
+	ctc.twistAngle = twistAngle
+
+	ctc.coneEq = equation.NewCone(bodyA, bodyB, ctc.axisA, ctc.axisB, ctc.angle, maxForce)
+
+	ctc.twistEq = equation.NewRotational(bodyA, bodyB, maxForce)
+	ctc.twistEq.SetAxisA(ctc.axisA)
+	ctc.twistEq.SetAxisB(ctc.axisB)
+
+	// Make the cone equation push the bodies toward the cone axis, not outward
+	ctc.coneEq.SetMaxForce(0)
+	ctc.coneEq.SetMinForce(-maxForce)
+
+	// Make the twist equation add torque toward the initial position
+	ctc.twistEq.SetMaxForce(0)
+	ctc.twistEq.SetMinForce(-maxForce)
+
+	ctc.AddEquation(ctc.coneEq)
+	ctc.AddEquation(ctc.twistEq)
+
+	return ctc
+}
+
+// Update updates the equations with data.
+func (ctc *ConeTwist) Update() {
+
+	ctc.PointToPoint.Update()
+
+	// Update the axes to the cone constraint
+	worldAxisA := ctc.bodyA.VectorToWorld(ctc.axisA)
+	worldAxisB := ctc.bodyB.VectorToWorld(ctc.axisB)
+
+	ctc.coneEq.SetAxisA(&worldAxisA)
+	ctc.coneEq.SetAxisB(&worldAxisB)
+
+	// Update the world axes in the twist constraint
+	tA, _ := ctc.axisA.RandomTangents()
+	worldTA := ctc.bodyA.VectorToWorld(tA)
+	ctc.twistEq.SetAxisA(&worldTA)
+
+	tB, _ := ctc.axisB.RandomTangents()
+	worldTB := ctc.bodyB.VectorToWorld(tB)
+	ctc.twistEq.SetAxisB(&worldTB)
+
+	ctc.coneEq.SetAngle(ctc.angle)
+	ctc.twistEq.SetMaxAngle(ctc.twistAngle)
+}

+ 95 - 0
experimental/physics/constraint/constraint.go

@@ -0,0 +1,95 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+// Package constraint implements physics constraints.
+package constraint
+
+import (
+	"github.com/g3n/engine/experimental/physics/equation"
+	"github.com/g3n/engine/math32"
+)
+
+type IBody interface {
+	equation.IBody
+	WakeUp()
+	VectorToWorld(*math32.Vector3) math32.Vector3
+	PointToLocal(*math32.Vector3) math32.Vector3
+	VectorToLocal(*math32.Vector3) math32.Vector3
+	Quaternion() *math32.Quaternion
+}
+
+type IConstraint interface {
+	Update() // Update all the equations with data.
+	Equations() []equation.IEquation
+	CollideConnected() bool
+	BodyA() IBody
+	BodyB() IBody
+}
+
+// Constraint base struct.
+type Constraint struct {
+	equations []equation.IEquation // Equations to be solved in this constraint
+	bodyA     IBody
+	bodyB     IBody
+	colConn   bool // Set to true if you want the bodies to collide when they are connected.
+}
+
+// NewConstraint creates and returns a pointer to a new Constraint object.
+//func NewConstraint(bodyA, bodyB IBody, colConn, wakeUpBodies bool) *Constraint {
+//
+//	c := new(Constraint)
+//	c.initialize(bodyA, bodyB, colConn, wakeUpBodies)
+//	return c
+//}
+
+func (c *Constraint) initialize(bodyA, bodyB IBody, colConn, wakeUpBodies bool) {
+
+	c.bodyA = bodyA
+	c.bodyB = bodyB
+	c.colConn = colConn // true
+
+	if wakeUpBodies { // true
+		if bodyA != nil {
+			bodyA.WakeUp()
+		}
+		if bodyB != nil {
+			bodyB.WakeUp()
+		}
+	}
+}
+
+// AddEquation adds an equation to the constraint.
+func (c *Constraint) AddEquation(eq equation.IEquation) {
+
+	c.equations = append(c.equations, eq)
+}
+
+// Equations returns the constraint's equations.
+func (c *Constraint) Equations() []equation.IEquation {
+
+	return c.equations
+}
+
+func (c *Constraint) CollideConnected() bool {
+
+	return c.colConn
+}
+
+func (c *Constraint) BodyA() IBody {
+
+	return c.bodyA
+}
+
+func (c *Constraint) BodyB() IBody {
+
+	return c.bodyB
+}
+
+// SetEnable sets the enabled flag of the constraint equations.
+func (c *Constraint) SetEnabled(state bool) {
+
+	for i := range c.equations {
+		c.equations[i].SetEnabled(state)
+	}
+}

+ 49 - 0
experimental/physics/constraint/distance.go

@@ -0,0 +1,49 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package constraint
+
+import (
+	"github.com/g3n/engine/experimental/physics/equation"
+)
+
+// Distance is a distance constraint.
+// Constrains two bodies to be at a constant distance from each others center of mass.
+type Distance struct {
+	Constraint
+	distance   float32 // Distance
+	equation   *equation.Contact
+}
+
+// NewDistance creates and returns a pointer to a new Distance constraint object.
+func NewDistance(bodyA, bodyB IBody, distance, maxForce float32) *Distance {
+
+	dc := new(Distance)
+	dc.initialize(bodyA, bodyB, true, true)
+
+	// Default distance should be: bodyA.position.distanceTo(bodyB.position)
+	// Default maxForce should be: 1e6
+
+	dc.distance = distance
+
+	dc.equation = equation.NewContact(bodyA, bodyB, -maxForce, maxForce) // Make it bidirectional
+	dc.AddEquation(dc.equation)
+
+	return dc
+}
+
+// Update updates the equation with data.
+func (dc *Distance) Update() {
+
+	halfDist := dc.distance * 0.5
+
+	posA := dc.bodyA.Position()
+	posB := dc.bodyB.Position()
+
+	normal := posB.Sub(&posA)
+	normal.Normalize()
+
+	dc.equation.SetRA(normal.Clone().MultiplyScalar(halfDist))
+	dc.equation.SetRB(normal.Clone().MultiplyScalar(-halfDist))
+}

+ 86 - 0
experimental/physics/constraint/hinge.go

@@ -0,0 +1,86 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package constraint
+
+import (
+	"github.com/g3n/engine/experimental/physics/equation"
+	"github.com/g3n/engine/math32"
+)
+
+// Hinge constraint.
+// Think of it as a door hinge.
+// It tries to keep the door in the correct place and with the correct orientation.
+type Hinge struct {
+	PointToPoint
+	axisA   *math32.Vector3           // Rotation axis, defined locally in bodyA.
+	axisB   *math32.Vector3           // Rotation axis, defined locally in bodyB.
+	rotEq1  *equation.Rotational
+	rotEq2  *equation.Rotational
+	motorEq *equation.RotationalMotor
+}
+
+// NewHinge creates and returns a pointer to a new Hinge constraint object.
+func NewHinge(bodyA, bodyB IBody, pivotA, pivotB, axisA, axisB *math32.Vector3, maxForce float32) *Hinge {
+
+	hc := new(Hinge)
+
+	hc.initialize(bodyA, bodyB, pivotA, pivotB, maxForce)
+
+	hc.axisA = axisA
+	hc.axisB = axisB
+	hc.axisA.Normalize()
+	hc.axisB.Normalize()
+
+	hc.rotEq1 = equation.NewRotational(bodyA, bodyB, maxForce)
+	hc.rotEq2 = equation.NewRotational(bodyA, bodyB, maxForce)
+	hc.motorEq = equation.NewRotationalMotor(bodyA, bodyB, maxForce)
+	hc.motorEq.SetEnabled(false) // Not enabled by default
+
+	hc.AddEquation(hc.rotEq1)
+	hc.AddEquation(hc.rotEq2)
+	hc.AddEquation(hc.motorEq)
+
+	return hc
+}
+
+func (hc *Hinge) SetMotorEnabled(state bool) {
+
+	hc.motorEq.SetEnabled(state)
+}
+
+func (hc *Hinge) SetMotorSpeed(speed float32) {
+
+	hc.motorEq.SetTargetSpeed(speed)
+}
+
+func (hc *Hinge) SetMotorMaxForce(maxForce float32) {
+
+	hc.motorEq.SetMaxForce(maxForce)
+	hc.motorEq.SetMinForce(-maxForce)
+}
+
+// Update updates the equations with data.
+func (hc *Hinge) Update() {
+
+	hc.PointToPoint.Update()
+
+	// Get world axes
+	quatA := hc.bodyA.Quaternion()
+	quatB := hc.bodyB.Quaternion()
+
+	worldAxisA := hc.axisA.Clone().ApplyQuaternion(quatA)
+	worldAxisB := hc.axisB.Clone().ApplyQuaternion(quatB)
+
+	t1, t2 := worldAxisA.RandomTangents()
+	hc.rotEq1.SetAxisA(t1)
+	hc.rotEq2.SetAxisA(t2)
+	hc.rotEq1.SetAxisB(worldAxisB)
+	hc.rotEq2.SetAxisB(worldAxisB)
+
+	if hc.motorEq.Enabled() {
+		hc.motorEq.SetAxisA(hc.axisA.Clone().ApplyQuaternion(quatA))
+		hc.motorEq.SetAxisB(hc.axisB.Clone().ApplyQuaternion(quatB))
+	}
+}

+ 95 - 0
experimental/physics/constraint/lock.go

@@ -0,0 +1,95 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package constraint
+
+import (
+	"github.com/g3n/engine/experimental/physics/equation"
+	"github.com/g3n/engine/math32"
+)
+
+// Lock constraint.
+// Removes all degrees of freedom between the bodies.
+type Lock struct {
+	PointToPoint
+	rotEq1 *equation.Rotational
+	rotEq2 *equation.Rotational
+	rotEq3 *equation.Rotational
+	xA     *math32.Vector3
+	xB     *math32.Vector3
+	yA     *math32.Vector3
+	yB     *math32.Vector3
+	zA     *math32.Vector3
+	zB     *math32.Vector3
+}
+
+// NewLock creates and returns a pointer to a new Lock constraint object.
+func NewLock(bodyA, bodyB IBody, maxForce float32) *Lock {
+
+	lc := new(Lock)
+
+	// Set pivot point in between
+	posA := bodyA.Position()
+	posB := bodyB.Position()
+
+	halfWay := math32.NewVec3().AddVectors(&posA, &posB)
+	halfWay.MultiplyScalar(0.5)
+
+	pivotB := bodyB.PointToLocal(halfWay)
+	pivotA := bodyA.PointToLocal(halfWay)
+
+	// The point-to-point constraint will keep a point shared between the bodies
+	lc.initialize(bodyA, bodyB, &pivotA, &pivotB, maxForce)
+
+	// Store initial rotation of the bodies as unit vectors in the local body spaces
+	UnitX := math32.NewVector3(1,0,0)
+
+	localA := bodyA.VectorToLocal(UnitX)
+	localB := bodyB.VectorToLocal(UnitX)
+
+	lc.xA = &localA
+	lc.xB = &localB
+	lc.yA = &localA
+	lc.yB = &localB
+	lc.zA = &localA
+	lc.zB = &localB
+
+	// ...and the following rotational equations will keep all rotational DOF's in place
+
+	lc.rotEq1 = equation.NewRotational(bodyA, bodyB, maxForce)
+	lc.rotEq2 = equation.NewRotational(bodyA, bodyB, maxForce)
+	lc.rotEq3 = equation.NewRotational(bodyA, bodyB, maxForce)
+
+	lc.AddEquation(lc.rotEq1)
+	lc.AddEquation(lc.rotEq2)
+	lc.AddEquation(lc.rotEq3)
+
+	return lc
+}
+
+// Update updates the equations with data.
+func (lc *Lock) Update() {
+
+	lc.PointToPoint.Update()
+
+	// These vector pairs must be orthogonal
+
+	xAw := lc.bodyA.VectorToWorld(lc.xA)
+	yBw := lc.bodyA.VectorToWorld(lc.yB)
+
+	yAw := lc.bodyA.VectorToWorld(lc.yA)
+	zBw := lc.bodyB.VectorToWorld(lc.zB)
+
+	zAw := lc.bodyA.VectorToWorld(lc.zA)
+	xBw := lc.bodyB.VectorToWorld(lc.xB)
+
+	lc.rotEq1.SetAxisA(&xAw)
+	lc.rotEq1.SetAxisB(&yBw)
+
+	lc.rotEq2.SetAxisA(&yAw)
+	lc.rotEq2.SetAxisB(&zBw)
+
+	lc.rotEq3.SetAxisA(&zAw)
+	lc.rotEq3.SetAxisB(&xBw)
+}

+ 65 - 0
experimental/physics/constraint/pointtopoint.go

@@ -0,0 +1,65 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package constraint
+
+import (
+	"github.com/g3n/engine/experimental/physics/equation"
+	"github.com/g3n/engine/math32"
+)
+
+// PointToPoint is an offset constraint.
+// Connects two bodies at the specified offset points.
+type PointToPoint struct {
+	Constraint
+	pivotA *math32.Vector3   // Pivot, defined locally in bodyA.
+	pivotB *math32.Vector3   // Pivot, defined locally in bodyB.
+	eqX    *equation.Contact
+	eqY    *equation.Contact
+	eqZ    *equation.Contact
+}
+
+// NewPointToPoint creates and returns a pointer to a new PointToPoint constraint object.
+func NewPointToPoint(bodyA, bodyB IBody, pivotA, pivotB *math32.Vector3, maxForce float32) *PointToPoint {
+
+	ptpc := new(PointToPoint)
+	ptpc.initialize(bodyA, bodyB, pivotA, pivotB, maxForce)
+
+	return ptpc
+}
+
+func (ptpc *PointToPoint) initialize(bodyA, bodyB IBody, pivotA, pivotB *math32.Vector3, maxForce float32) {
+
+	ptpc.Constraint.initialize(bodyA, bodyB, true, true)
+
+	ptpc.pivotA = pivotA // default is zero vec3
+	ptpc.pivotB = pivotB // default is zero vec3
+
+	ptpc.eqX = equation.NewContact(bodyA, bodyB, -maxForce, maxForce)
+	ptpc.eqY = equation.NewContact(bodyA, bodyB, -maxForce, maxForce)
+	ptpc.eqZ = equation.NewContact(bodyA, bodyB, -maxForce, maxForce)
+
+	ptpc.eqX.SetNormal(&math32.Vector3{1,0,0})
+	ptpc.eqY.SetNormal(&math32.Vector3{0,1,0})
+	ptpc.eqZ.SetNormal(&math32.Vector3{0,0,1})
+
+	ptpc.AddEquation(&ptpc.eqX.Equation)
+	ptpc.AddEquation(&ptpc.eqY.Equation)
+	ptpc.AddEquation(&ptpc.eqZ.Equation)
+}
+
+// Update updates the equations with data.
+func (ptpc *PointToPoint) Update() {
+
+	// Rotate the pivots to world space
+	xRi := ptpc.pivotA.Clone().ApplyQuaternion(ptpc.bodyA.Quaternion())
+	xRj := ptpc.pivotA.Clone().ApplyQuaternion(ptpc.bodyA.Quaternion())
+
+	ptpc.eqX.SetRA(xRi)
+	ptpc.eqX.SetRB(xRj)
+	ptpc.eqY.SetRA(xRi)
+	ptpc.eqY.SetRB(xRj)
+	ptpc.eqZ.SetRA(xRi)
+	ptpc.eqZ.SetRB(xRj)
+}

+ 94 - 0
experimental/physics/debug.go

@@ -0,0 +1,94 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+// Package physics implements a basic physics engine.
+package physics
+
+import (
+	"github.com/g3n/engine/core"
+	"github.com/g3n/engine/math32"
+	"github.com/g3n/engine/geometry"
+	"github.com/g3n/engine/gls"
+	"github.com/g3n/engine/graphic"
+	"github.com/g3n/engine/material"
+	"github.com/g3n/engine/experimental/physics/collision"
+)
+
+// This file contains helpful infrastructure for debugging physics
+type DebugHelper struct {
+
+}
+
+func ShowWorldFace(scene *core.Node, face []math32.Vector3, color *math32.Color) {
+
+	if len(face) == 0 {
+		return
+	}
+
+	vertices := math32.NewArrayF32(0, 16)
+	for i := range face {
+		vertices.AppendVector3(&face[i])
+	}
+	vertices.AppendVector3(&face[0])
+
+	geom := geometry.NewGeometry()
+	geom.AddVBO(gls.NewVBO(vertices).AddAttrib(gls.VertexPosition, 3))
+
+	mat := material.NewStandard(color)
+	faceGraphic := graphic.NewLineStrip(geom, mat)
+	scene.Add(faceGraphic)
+}
+
+func ShowPenAxis(scene *core.Node, axis *math32.Vector3) {//}, min, max float32) {
+
+	vertices := math32.NewArrayF32(0, 16)
+
+	size := float32(100)
+	minPoint := axis.Clone().MultiplyScalar(size)
+	maxPoint := axis.Clone().MultiplyScalar(-size)
+	//vertices.AppendVector3(minPoint.Clone().SetX(minPoint.X - size))
+	//vertices.AppendVector3(minPoint.Clone().SetX(minPoint.X + size))
+	//vertices.AppendVector3(minPoint.Clone().SetY(minPoint.Y - size))
+	//vertices.AppendVector3(minPoint.Clone().SetY(minPoint.Y + size))
+	//vertices.AppendVector3(minPoint.Clone().SetZ(minPoint.Z - size))
+	//vertices.AppendVector3(minPoint.Clone().SetZ(minPoint.Z + size))
+	vertices.AppendVector3(minPoint)
+	//vertices.AppendVector3(maxPoint.Clone().SetX(maxPoint.X - size))
+	//vertices.AppendVector3(maxPoint.Clone().SetX(maxPoint.X + size))
+	//vertices.AppendVector3(maxPoint.Clone().SetY(maxPoint.Y - size))
+	//vertices.AppendVector3(maxPoint.Clone().SetY(maxPoint.Y + size))
+	//vertices.AppendVector3(maxPoint.Clone().SetZ(maxPoint.Z - size))
+	//vertices.AppendVector3(maxPoint.Clone().SetZ(maxPoint.Z + size))
+	vertices.AppendVector3(maxPoint)
+
+	geom := geometry.NewGeometry()
+	geom.AddVBO(gls.NewVBO(vertices).AddAttrib(gls.VertexPosition, 3))
+
+	mat := material.NewStandard(&math32.Color{1,1,1})
+	faceGraphic := graphic.NewLines(geom, mat)
+	scene.Add(faceGraphic)
+}
+
+func ShowContact(scene *core.Node, contact *collision.Contact) {
+
+	vertices := math32.NewArrayF32(0, 16)
+
+	size := float32(0.0005)
+	otherPoint := contact.Point.Clone().Add(contact.Normal.Clone().MultiplyScalar(-contact.Depth))
+	vertices.AppendVector3(contact.Point.Clone().SetX(contact.Point.X - size))
+	vertices.AppendVector3(contact.Point.Clone().SetX(contact.Point.X + size))
+	vertices.AppendVector3(contact.Point.Clone().SetY(contact.Point.Y - size))
+	vertices.AppendVector3(contact.Point.Clone().SetY(contact.Point.Y + size))
+	vertices.AppendVector3(contact.Point.Clone().SetZ(contact.Point.Z - size))
+	vertices.AppendVector3(contact.Point.Clone().SetZ(contact.Point.Z + size))
+	vertices.AppendVector3(contact.Point.Clone())
+	vertices.AppendVector3(otherPoint)
+
+	geom := geometry.NewGeometry()
+	geom.AddVBO(gls.NewVBO(vertices).AddAttrib(gls.VertexPosition, 3))
+
+	mat := material.NewStandard(&math32.Color{0,0,1})
+	faceGraphic := graphic.NewLines(geom, mat)
+	scene.Add(faceGraphic)
+}

+ 8 - 0
experimental/physics/doc.go

@@ -0,0 +1,8 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+// Package physics implements a basic physics engine.
+// WARNING: This package is experimental and incomplete!
+package physics
+

+ 88 - 0
experimental/physics/equation/cone.go

@@ -0,0 +1,88 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package equation
+
+import (
+	"github.com/g3n/engine/math32"
+)
+
+// Cone is a cone constraint equation.
+// Works to keep the given body world vectors aligned, or tilted within a given angle from each other.
+type Cone struct {
+	Equation
+	axisA    *math32.Vector3 // Local axis in A
+	axisB    *math32.Vector3 // Local axis in B
+	angle    float32         // The "cone angle" to keep
+}
+
+// NewCone creates and returns a pointer to a new Cone equation object.
+func NewCone(bodyA, bodyB IBody, axisA, axisB *math32.Vector3, angle, maxForce float32) *Cone {
+
+	ce := new(Cone)
+
+	ce.axisA = axisA // new Vec3(1, 0, 0)
+	ce.axisB = axisB // new Vec3(0, 1, 0)
+	ce.angle = angle // 0
+
+	ce.Equation.initialize(bodyA, bodyB, -maxForce, maxForce)
+
+	return ce
+}
+
+// SetAxisA sets the axis of body A.
+func (ce *Cone) SetAxisA(axisA *math32.Vector3) {
+
+	ce.axisA = axisA
+}
+
+// AxisA returns the axis of body A.
+func (ce *Cone) AxisA() math32.Vector3 {
+
+	return *ce.axisA
+}
+
+// SetAxisB sets the axis of body B.
+func (ce *Cone) SetAxisB(axisB *math32.Vector3) {
+
+	ce.axisB = axisB
+}
+
+// AxisB returns the axis of body B.
+func (ce *Cone) AxisB() math32.Vector3 {
+
+	return *ce.axisB
+}
+
+// SetAngle sets the cone angle.
+func (ce *Cone) SetAngle(angle float32) {
+
+	ce.angle = angle
+}
+
+// MaxAngle returns the cone angle.
+func (ce *Cone) Angle() float32 {
+
+	return ce.angle
+}
+
+// ComputeB
+func (ce *Cone) ComputeB(h float32) float32 {
+
+	// The angle between two vector is:
+	// cos(theta) = a * b / (length(a) * length(b) = { len(a) = len(b) = 1 } = a * b
+
+	// g = a * b
+	// gdot = (b x a) * wi + (a x b) * wj
+	// G = [0 bxa 0 axb]
+	// W = [vi wi vj wj]
+	ce.jeA.SetRotational(math32.NewVec3().CrossVectors(ce.axisB, ce.axisA))
+	ce.jeB.SetRotational(math32.NewVec3().CrossVectors(ce.axisA, ce.axisB))
+
+	g := math32.Cos(ce.angle) - ce.axisA.Dot(ce.axisB)
+	GW := ce.ComputeGW()
+	GiMf := ce.ComputeGiMf()
+
+	return -g*ce.a - GW*ce.b - h*GiMf
+}

+ 124 - 0
experimental/physics/equation/contact.go

@@ -0,0 +1,124 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package equation
+
+import (
+	"github.com/g3n/engine/math32"
+)
+
+// Contact is a contact/non-penetration constraint equation.
+type Contact struct {
+	Equation
+	restitution float32         // "bounciness": u1 = -e*u0
+	rA          *math32.Vector3 // World-oriented vector that goes from the center of bA to the contact point.
+	rB          *math32.Vector3 // World-oriented vector that goes from the center of bB to the contact point.
+	nA          *math32.Vector3 // Contact normal, pointing out of body A.
+}
+
+// NewContact creates and returns a pointer to a new Contact equation object.
+func NewContact(bodyA, bodyB IBody, minForce, maxForce float32) *Contact {
+
+	ce := new(Contact)
+
+	// minForce default should be 0.
+
+	ce.restitution = 0.5
+	ce.rA = &math32.Vector3{0,0,0}
+	ce.rB = &math32.Vector3{0,0,0}
+	ce.nA = &math32.Vector3{0,0,0}
+
+	ce.Equation.initialize(bodyA, bodyB, minForce, maxForce)
+
+	return ce
+}
+
+func (ce *Contact) SetRestitution(r float32) {
+
+	ce.restitution = r
+}
+
+func (ce *Contact) Restitution() float32 {
+
+	return ce.restitution
+}
+
+func (ce *Contact) SetNormal(newNormal *math32.Vector3)  {
+
+	ce.nA = newNormal
+}
+
+func (ce *Contact) Normal() math32.Vector3 {
+
+	return *ce.nA
+}
+
+func (ce *Contact) SetRA(newRa *math32.Vector3)  {
+
+	ce.rA = newRa
+}
+
+func (ce *Contact) RA() math32.Vector3 {
+
+	return *ce.rA
+}
+
+func (ce *Contact) SetRB(newRb *math32.Vector3)  {
+
+	ce.rB = newRb
+}
+
+func (ce *Contact) RB() math32.Vector3 {
+
+	return *ce.rB
+}
+
+// ComputeB
+func (ce *Contact) ComputeB(h float32) float32 {
+
+	vA := ce.bA.Velocity()
+	wA := ce.bA.AngularVelocity()
+
+	vB := ce.bB.Velocity()
+	wB := ce.bB.AngularVelocity()
+
+	// Calculate cross products
+	rnA := math32.NewVec3().CrossVectors(ce.rA, ce.nA)
+	rnB := math32.NewVec3().CrossVectors(ce.rB, ce.nA)
+
+	// g = xj+rB -(xi+rA)
+	// G = [ -nA  -rnA  nA  rnB ]
+	ce.jeA.SetSpatial(ce.nA.Clone().Negate())
+	ce.jeA.SetRotational(rnA.Clone().Negate())
+	ce.jeB.SetSpatial(ce.nA.Clone())
+	ce.jeB.SetRotational(rnB.Clone())
+
+	// Calculate the penetration vector
+	posA := ce.bA.Position()
+	posB := ce.bB.Position()
+	penetrationVec := ce.rB.Clone().Add(&posB).Sub(ce.rA).Sub(&posA)
+
+	g := ce.nA.Dot(penetrationVec)
+
+	// Compute iteration
+	ePlusOne := ce.restitution + 1
+	GW := ePlusOne * vB.Dot(ce.nA) - ePlusOne * vA.Dot(ce.nA) + wB.Dot(rnB) - wA.Dot(rnA)
+	GiMf := ce.ComputeGiMf()
+
+	return -g*ce.a - GW*ce.b - h*GiMf
+}
+
+//// GetImpactVelocityAlongNormal returns the current relative velocity at the contact point.
+//func (ce *Contact) GetImpactVelocityAlongNormal() float32 {
+//
+//	xi := ce.bA.Position().Add(ce.rA)
+//	xj := ce.bB.Position().Add(ce.rB)
+//
+//	vi := ce.bA.GetVelocityAtWorldPoint(xi)
+//	vj := ce.bB.GetVelocityAtWorldPoint(xj)
+//
+//	relVel := math32.NewVec3().SubVectors(vi, vj)
+//
+//    return ce.nA.Dot(relVel)
+//}

+ 245 - 0
experimental/physics/equation/equation.go

@@ -0,0 +1,245 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+// Package equation implements SPOOK equations based on
+// the 2007 PhD thesis of Claude Lacoursière titled
+// "Ghosts and Machines: Regularized Variational Methods for
+// Interactive Simulations of Multibodies with Dry Frictional Contacts"
+package equation
+
+import (
+	"github.com/g3n/engine/math32"
+)
+
+// IBody is the interface of all body types.
+type IBody interface {
+	Index() int
+	Position() math32.Vector3
+	Velocity() math32.Vector3
+	AngularVelocity() math32.Vector3
+	Force() math32.Vector3
+	Torque() math32.Vector3
+	InvMassEff() float32
+	InvRotInertiaWorldEff() *math32.Matrix3
+}
+
+// IEquation is the interface type for all equations types.
+type IEquation interface {
+	SetBodyA(IBody)
+	BodyA() IBody
+	SetBodyB(IBody)
+	BodyB() IBody
+	JeA() JacobianElement
+	JeB() JacobianElement
+	SetEnabled(state bool)
+	Enabled() bool
+	MinForce() float32
+	MaxForce() float32
+	Eps() float32
+	SetMultiplier(multiplier float32)
+	ComputeB(h float32) float32
+	ComputeC() float32
+}
+
+// Equation is a SPOOK constraint equation.
+type Equation struct {
+	id         int
+	minForce   float32       // Minimum (read: negative max) force to be applied by the constraint.
+	maxForce   float32       // Maximum (read: positive max) force to be applied by the constraint.
+	bA         IBody // Body "i"
+	bB         IBody // Body "j"
+	a          float32       // SPOOK parameter
+	b          float32       // SPOOK parameter
+	eps        float32       // SPOOK parameter
+	jeA        JacobianElement
+	jeB        JacobianElement
+	enabled    bool
+	multiplier float32 // A number, proportional to the force added to the bodies.
+}
+
+// NewEquation creates and returns a pointer to a new Equation object.
+func NewEquation(bi, bj IBody, minForce, maxForce float32) *Equation {
+
+	e := new(Equation)
+	e.initialize(bi, bj, minForce, maxForce)
+	return e
+}
+
+func (e *Equation) initialize(bi, bj IBody, minForce, maxForce float32) {
+
+	//e.id = Equation.id++
+	e.minForce = minForce //-1e6
+	e.maxForce = maxForce //1e6
+
+	e.bA = bi
+	e.bB = bj
+	e.a = 0
+	e.b = 0
+	e.eps = 0
+	e.enabled = true
+	e.multiplier = 0
+
+	// Set typical spook params (k, d, dt)
+	e.SetSpookParams(1e7, 3, 1/60)
+}
+
+func (e *Equation) SetBodyA(ibody IBody) {
+
+	e.bA = ibody
+}
+
+func (e *Equation) BodyA() IBody {
+
+	return e.bA
+}
+
+func (e *Equation) SetBodyB(ibody IBody) {
+
+	e.bB = ibody
+}
+
+func (e *Equation) BodyB() IBody {
+
+	return e.bB
+}
+
+func (e *Equation) JeA() JacobianElement {
+
+	return e.jeA
+}
+
+func (e *Equation) JeB() JacobianElement {
+
+	return e.jeB
+}
+
+// SetMinForce sets the minimum force to be applied by the constraint.
+func (e *Equation) SetMinForce(minForce float32) {
+
+	e.minForce = minForce
+}
+
+// MinForce returns the minimum force to be applied by the constraint.
+func (e *Equation) MinForce() float32 {
+
+	return e.minForce
+}
+
+// SetMaxForce sets the maximum force to be applied by the constraint.
+func (e *Equation) SetMaxForce(maxForce float32) {
+
+	e.maxForce = maxForce
+}
+
+// MaxForce returns the maximum force to be applied by the constraint.
+func (e *Equation) MaxForce() float32 {
+
+	return e.maxForce
+}
+
+// Returns epsilon - the regularization constant which is multiplied by the identity matrix.
+func (e *Equation) Eps() float32 {
+
+	return e.eps
+}
+
+// SetMultiplier sets the multiplier.
+func (e *Equation) SetMultiplier(multiplier float32) {
+
+	e.multiplier = multiplier
+}
+
+// MaxForce returns the multiplier.
+func (e *Equation) Multiplier() float32 {
+
+	return e.multiplier
+}
+
+// SetEnable sets the enabled flag of the equation.
+func (e *Equation) SetEnabled(state bool) {
+
+	e.enabled = state
+}
+
+// Enabled returns the enabled flag of the equation.
+func (e *Equation) Enabled() bool {
+
+	return e.enabled
+}
+
+// SetSpookParams recalculates a, b, eps.
+func (e *Equation) SetSpookParams(stiffness, relaxation float32, timeStep float32) {
+
+	e.a = 4.0 / (timeStep * (1 + 4*relaxation))
+	e.b = (4.0 * relaxation) / (1 + 4*relaxation)
+	e.eps = 4.0 / (timeStep * timeStep * stiffness * (1 + 4*relaxation))
+}
+
+// ComputeB computes the RHS of the SPOOK equation.
+func (e *Equation) ComputeB(h float32) float32 {
+
+	GW := e.ComputeGW()
+	Gq := e.ComputeGq()
+	GiMf := e.ComputeGiMf()
+	return -Gq*e.a - GW*e.b - GiMf*h
+}
+
+// ComputeGq computes G*q, where q are the generalized body coordinates.
+func (e *Equation) ComputeGq() float32 {
+
+	xi := e.bA.Position()
+	xj := e.bB.Position()
+	spatA := e.jeA.Spatial()
+	spatB := e.jeB.Spatial()
+	return (&spatA).Dot(&xi) + (&spatB).Dot(&xj)
+}
+
+// ComputeGW computes G*W, where W are the body velocities.
+func (e *Equation) ComputeGW() float32 {
+
+	vA := e.bA.Velocity()
+	vB := e.bB.Velocity()
+	wA := e.bA.AngularVelocity()
+	wB := e.bB.AngularVelocity()
+	return e.jeA.MultiplyVectors(&vA, &wA) + e.jeB.MultiplyVectors(&vB, &wB)
+}
+
+// ComputeGiMf computes G*inv(M)*f, where M is the mass matrix with diagonal blocks for each body, and f are the forces on the bodies.
+func (e *Equation) ComputeGiMf() float32 {
+
+	forceA := e.bA.Force()
+	forceB := e.bB.Force()
+
+	iMfA := forceA.MultiplyScalar(e.bA.InvMassEff())
+	iMfB := forceB.MultiplyScalar(e.bB.InvMassEff())
+
+	torqueA := e.bA.Torque()
+	torqueB := e.bB.Torque()
+
+	invIiTaui := torqueA.ApplyMatrix3(e.bA.InvRotInertiaWorldEff())
+	invIjTauj := torqueB.ApplyMatrix3(e.bB.InvRotInertiaWorldEff())
+
+	return e.jeA.MultiplyVectors(iMfA, invIiTaui) + e.jeB.MultiplyVectors(iMfB, invIjTauj)
+}
+
+// ComputeGiMGt computes G*inv(M)*G'.
+func (e *Equation) ComputeGiMGt() float32 {
+
+	rotA := e.jeA.Rotational()
+	rotB := e.jeB.Rotational()
+	rotAcopy := e.jeA.Rotational()
+	rotBcopy := e.jeB.Rotational()
+
+	result := e.bA.InvMassEff() + e.bB.InvMassEff()
+	result += rotA.ApplyMatrix3(e.bA.InvRotInertiaWorldEff()).Dot(&rotAcopy)
+	result += rotB.ApplyMatrix3(e.bB.InvRotInertiaWorldEff()).Dot(&rotBcopy)
+
+	return result
+}
+
+// ComputeC computes the denominator part of the SPOOK equation: C = G*inv(M)*G' + eps.
+func (e *Equation) ComputeC() float32 {
+
+	return e.ComputeGiMGt() + e.eps
+}

+ 82 - 0
experimental/physics/equation/friction.go

@@ -0,0 +1,82 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package equation
+
+import (
+	"github.com/g3n/engine/math32"
+)
+
+// Friction is a friction constraint equation.
+type Friction struct {
+	Equation
+	rA *math32.Vector3 // World-oriented vector that goes from the center of bA to the contact point.
+	rB *math32.Vector3 // World-oriented vector that starts in body j position and goes to the contact point.
+	t  *math32.Vector3 // Contact tangent
+}
+
+// NewFriction creates and returns a pointer to a new Friction equation object.
+// slipForce should be +-F_friction = +-mu * F_normal = +-mu * m * g
+func NewFriction(bodyA, bodyB IBody, slipForce float32) *Friction {
+
+	fe := new(Friction)
+
+	fe.rA = math32.NewVec3()
+	fe.rB = math32.NewVec3()
+	fe.t = math32.NewVec3()
+
+	fe.Equation.initialize(bodyA, bodyB, -slipForce, slipForce)
+
+	return fe
+}
+
+func (fe *Friction) SetTangent(newTangent *math32.Vector3)  {
+
+	fe.t = newTangent
+}
+
+func (fe *Friction) Tangent() math32.Vector3 {
+
+	return *fe.t
+}
+
+func (fe *Friction) SetRA(newRa *math32.Vector3)  {
+
+	fe.rA = newRa
+}
+
+func (fe *Friction) RA() math32.Vector3 {
+
+	return *fe.rA
+}
+
+func (fe *Friction) SetRB(newRb *math32.Vector3)  {
+
+	fe.rB = newRb
+}
+
+func (fe *Friction) RB() math32.Vector3 {
+
+	return *fe.rB
+}
+
+// ComputeB
+func (fe *Friction) ComputeB(h float32) float32 {
+
+	// Calculate cross products
+	rtA := math32.NewVec3().CrossVectors(fe.rA, fe.t)
+	rtB := math32.NewVec3().CrossVectors(fe.rB, fe.t)
+
+	// G = [-t -rtA t rtB]
+	// And remember, this is a pure velocity constraint, g is always zero!
+	fe.jeA.SetSpatial(fe.t.Clone().Negate())
+	fe.jeA.SetRotational(rtA.Clone().Negate())
+	fe.jeB.SetSpatial(fe.t.Clone())
+	fe.jeB.SetRotational(rtB.Clone())
+
+	var GW = fe.ComputeGW()
+	var GiMf = fe.ComputeGiMf()
+
+	return -GW*fe.b - h*GiMf
+}

+ 51 - 0
experimental/physics/equation/jacobian.go

@@ -0,0 +1,51 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package equation
+
+import "github.com/g3n/engine/math32"
+
+// JacobianElement contains 6 entries, 3 spatial and 3 rotational degrees of freedom.
+type JacobianElement struct {
+	spatial    math32.Vector3
+	rotational math32.Vector3
+}
+
+// SetSpatial sets the spatial component of the JacobianElement.
+func (je *JacobianElement) SetSpatial(spatial *math32.Vector3) {
+
+	je.spatial = *spatial
+}
+
+// Spatial returns the spatial component of the JacobianElement.
+func (je *JacobianElement) Spatial() math32.Vector3 {
+
+	return je.spatial
+}
+
+// Rotational sets the rotational component of the JacobianElement.
+func (je *JacobianElement) SetRotational(rotational *math32.Vector3) {
+
+	je.rotational = *rotational
+}
+
+// Rotational returns the rotational component of the JacobianElement.
+func (je *JacobianElement) Rotational() math32.Vector3 {
+
+	return je.rotational
+}
+
+// MultiplyElement multiplies the JacobianElement with another JacobianElement.
+// None of the elements are changed.
+func (je *JacobianElement) MultiplyElement(je2 *JacobianElement) float32 {
+
+	return je.spatial.Dot(&je2.spatial) + je.rotational.Dot(&je2.rotational)
+}
+
+// MultiplyElement multiplies the JacobianElement with two vectors.
+// None of the elements are changed.
+func (je *JacobianElement) MultiplyVectors(spatial *math32.Vector3, rotational *math32.Vector3) float32 {
+
+	return je.spatial.Dot(spatial) + je.rotational.Dot(rotational)
+}

+ 89 - 0
experimental/physics/equation/rotational.go

@@ -0,0 +1,89 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package equation
+
+import (
+	"github.com/g3n/engine/math32"
+)
+
+// Rotational is a rotational constraint equation.
+// Works to keep the local vectors orthogonal to each other in world space.
+type Rotational struct {
+	Equation
+	axisA    *math32.Vector3 // Local axis in A
+	axisB    *math32.Vector3 // Local axis in B
+	maxAngle float32        // Max angle
+}
+
+// NewRotational creates and returns a pointer to a new Rotational equation object.
+func NewRotational(bodyA, bodyB IBody, maxForce float32) *Rotational {
+
+	re := new(Rotational)
+
+	re.axisA = math32.NewVector3(1, 0, 0)
+	re.axisB = math32.NewVector3(0, 1, 0)
+	re.maxAngle = math32.Pi / 2
+
+	re.Equation.initialize(bodyA, bodyB, -maxForce, maxForce)
+
+	return re
+}
+
+// SetAxisA sets the axis of body A.
+func (re *Rotational) SetAxisA(axisA *math32.Vector3) {
+
+	re.axisA = axisA
+}
+
+// AxisA returns the axis of body A.
+func (re *Rotational) AxisA() math32.Vector3 {
+
+	return *re.axisA
+}
+
+// SetAxisB sets the axis of body B.
+func (re *Rotational) SetAxisB(axisB *math32.Vector3) {
+
+	re.axisB = axisB
+}
+
+// AxisB returns the axis of body B.
+func (re *Rotational) AxisB() math32.Vector3 {
+
+	return *re.axisB
+}
+
+// SetAngle sets the maximum angle.
+func (re *Rotational) SetMaxAngle(angle float32) {
+
+	re.maxAngle = angle
+}
+
+// MaxAngle returns the maximum angle.
+func (re *Rotational) MaxAngle() float32 {
+
+	return re.maxAngle
+}
+
+// ComputeB
+func (re *Rotational) ComputeB(h float32) float32 {
+
+	// Calculate cross products
+	nAnB := math32.NewVec3().CrossVectors(re.axisA, re.axisB)
+	nBnA := math32.NewVec3().CrossVectors(re.axisB, re.axisA)
+
+	// g = nA * nj
+	// gdot = (nj x nA) * wi + (nA x nj) * wj
+	// G = [0 nBnA 0 nAnB]
+	// W = [vi wi vj wj]
+	re.jeA.SetRotational(nBnA)
+	re.jeB.SetRotational(nAnB)
+
+	g := math32.Cos(re.maxAngle) - re.axisA.Dot(re.axisB)
+	GW := re.ComputeGW()
+	GiMf := re.ComputeGiMf()
+
+	return -g*re.a - GW*re.b - h*GiMf
+}

+ 80 - 0
experimental/physics/equation/rotationalmotor.go

@@ -0,0 +1,80 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package equation
+
+import (
+	"github.com/g3n/engine/math32"
+)
+
+// RotationalMotor is a rotational motor constraint equation.
+// Tries to keep the relative angular velocity of the bodies to a given value.
+type RotationalMotor struct {
+	Equation // TODO maybe this should embed Rotational instead ?
+	axisA       *math32.Vector3 // World oriented rotational axis
+	axisB       *math32.Vector3 // World oriented rotational axis
+	targetSpeed float32         // Target speed
+}
+
+// NewRotationalMotor creates and returns a pointer to a new RotationalMotor equation object.
+func NewRotationalMotor(bodyA, bodyB IBody, maxForce float32) *RotationalMotor {
+
+	re := new(RotationalMotor)
+	re.Equation.initialize(bodyA, bodyB, -maxForce, maxForce)
+
+	return re
+}
+
+// SetAxisA sets the axis of body A.
+func (ce *RotationalMotor) SetAxisA(axisA *math32.Vector3) {
+
+	ce.axisA = axisA
+}
+
+// AxisA returns the axis of body A.
+func (ce *RotationalMotor) AxisA() math32.Vector3 {
+
+	return *ce.axisA
+}
+
+// SetAxisB sets the axis of body B.
+func (ce *RotationalMotor) SetAxisB(axisB *math32.Vector3) {
+
+	ce.axisB = axisB
+}
+
+// AxisB returns the axis of body B.
+func (ce *RotationalMotor) AxisB() math32.Vector3 {
+
+	return *ce.axisB
+}
+
+// SetTargetSpeed sets the target speed.
+func (ce *RotationalMotor) SetTargetSpeed(speed float32) {
+
+	ce.targetSpeed = speed
+}
+
+// TargetSpeed returns the target speed.
+func (ce *RotationalMotor) TargetSpeed() float32 {
+
+	return ce.targetSpeed
+}
+
+// ComputeB
+func (re *RotationalMotor) ComputeB(h float32) float32 {
+
+	// g = 0
+	// gdot = axisA * wi - axisB * wj
+	// gdot = G * W = G * [vi wi vj wj]
+	// =>
+	// G = [0 axisA 0 -axisB]
+	re.jeA.SetRotational(re.axisA.Clone())
+	re.jeB.SetRotational(re.axisB.Clone().Negate())
+
+	GW := re.ComputeGW() - re.targetSpeed
+	GiMf := re.ComputeGiMf()
+
+	return -GW*re.b - h*GiMf
+}

+ 164 - 0
experimental/physics/forcefield.go

@@ -0,0 +1,164 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package physics
+
+import "github.com/g3n/engine/math32"
+
+// ForceField represents a force field. A force is defined for every point.
+type ForceField interface {
+	ForceAt(pos *math32.Vector3) math32.Vector3
+}
+
+//
+// ConstantForceField is a constant force field.
+// It can be used to simulate surface gravity.
+//
+type ConstantForceField struct {
+	force math32.Vector3
+}
+
+// NewConstantForceField creates and returns a pointer to a new ConstantForceField.
+func NewConstantForceField(force *math32.Vector3) *ConstantForceField {
+
+	g := new(ConstantForceField)
+	g.force = *force
+	return g
+}
+
+// SetForce sets the force of the force field.
+func (g *ConstantForceField) SetForce(newDirection *math32.Vector3) {
+
+	g.force = *newDirection
+}
+
+// Force returns the force of the force field.
+func (g *ConstantForceField) Force() *math32.Vector3 {
+
+	return &g.force
+}
+
+// ForceAt satisfies the ForceField interface and returns the force at the specified position.
+func (g *ConstantForceField) ForceAt(pos *math32.Vector3) math32.Vector3 {
+
+	return g.force
+}
+
+//
+// AttractorForceField is a force field where all forces point to a single point.
+// The force strength changes with the inverse distance squared.
+// This can be used to model planetary attractions.
+//
+type AttractorForceField struct {
+	position math32.Vector3
+	mass     float32
+}
+
+// NewAttractorForceField creates and returns a pointer to a new AttractorForceField.
+func NewAttractorForceField(position *math32.Vector3, mass float32) *AttractorForceField {
+
+	pa := new(AttractorForceField)
+	pa.position = *position
+	pa.mass = mass
+	return pa
+}
+
+// SetPosition sets the position of the AttractorForceField.
+func (pa *AttractorForceField) SetPosition(newPosition *math32.Vector3) {
+
+	pa.position = *newPosition
+}
+
+// Position returns the position of the AttractorForceField.
+func (pa *AttractorForceField) Position() *math32.Vector3 {
+
+	return &pa.position
+}
+
+// SetMass sets the mass of the AttractorForceField.
+func (pa *AttractorForceField) SetMass(newMass float32) {
+
+	pa.mass = newMass
+}
+
+// Mass returns the mass of the AttractorForceField.
+func (pa *AttractorForceField) Mass() float32 {
+
+	return pa.mass
+}
+
+// ForceAt satisfies the ForceField interface and returns the force at the specified position.
+func (pa *AttractorForceField) ForceAt(pos *math32.Vector3) math32.Vector3 {
+
+	dir := pos
+	dir.Negate()
+	dir.Add(&pa.position)
+	dist := dir.Length()
+	dir.Normalize()
+	var val float32
+	//log.Error("dist %v", dist)
+	if dist > 0 {
+		val = pa.mass/(dist*dist)
+	} else {
+		val = 0
+	}
+	val = math32.Min(val, 100) // TODO deal with instability
+	//log.Error("%v", val)
+	dir.MultiplyScalar(val) // TODO multiply by gravitational constant: 6.673×10−11 (N–m2)/kg2
+	return *dir
+}
+
+//
+// RepellerForceField is a force field where all forces point away from a single point.
+// The force strength changes with the inverse distance squared.
+//
+type RepellerForceField struct {
+	position math32.Vector3
+	mass     float32
+}
+
+// NewRepellerForceField creates and returns a pointer to a new RepellerForceField.
+func NewRepellerForceField(position *math32.Vector3, mass float32) *RepellerForceField {
+
+	pr := new(RepellerForceField)
+	pr.position = *position
+	pr.mass = mass
+	return pr
+}
+
+// SetPosition sets the position of the RepellerForceField.
+func (pr *RepellerForceField) SetPosition(newPosition *math32.Vector3) {
+
+	pr.position = *newPosition
+}
+
+// Position returns the position of the RepellerForceField.
+func (pr *RepellerForceField) Position() *math32.Vector3 {
+
+	return &pr.position
+}
+
+// SetMass sets the mass of the RepellerForceField.
+func (pr *RepellerForceField) SetMass(newMass float32) {
+
+	pr.mass = newMass
+}
+
+// Mass returns the mass of the RepellerForceField.
+func (pr *RepellerForceField) Mass() float32 {
+
+	return pr.mass
+}
+
+// ForceAt satisfies the ForceField interface and returns the force at the specified position.
+func (pr *RepellerForceField) ForceAt(pos *math32.Vector3) math32.Vector3 {
+
+	dir := pr.position
+	dir.Negate()
+	dir.Add(pos)
+	dist := dir.Length()
+	dir.Normalize()
+	dir.MultiplyScalar(pr.mass/(dist*dist)) // TODO multiply by gravitational constant: 6.673×10−11 (N–m2)/kg2
+	return dir
+}

+ 12 - 0
experimental/physics/logger.go

@@ -0,0 +1,12 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package physics
+
+import (
+	"github.com/g3n/engine/util/logger"
+)
+
+// Package logger
+var log = logger.New("PHYSICS", logger.Default)

+ 43 - 0
experimental/physics/material.go

@@ -0,0 +1,43 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+// Package physics implements a basic physics engine.
+package physics
+
+type Material struct {
+	name        string
+	friction    float32
+	restitution float32
+}
+
+type ContactMaterial struct {
+	mat1                       *Material
+	mat2                       *Material
+	friction                   float32
+	restitution                float32
+	contactEquationStiffness   float32
+	contactEquationRelaxation  float32
+	frictionEquationStiffness  float32
+	frictionEquationRelaxation float32
+}
+
+func NewContactMaterial() *ContactMaterial {
+
+	cm := new(ContactMaterial)
+	cm.friction = 0.3
+	cm.restitution = 0.3
+	cm.contactEquationStiffness = 1e7
+	cm.contactEquationRelaxation = 3
+	cm.frictionEquationStiffness = 1e7
+	cm.frictionEquationRelaxation = 3
+	return cm
+}
+
+
+//type intPair struct {
+//	i int
+//	j int
+//}
+
+//type ContactMaterialTable map[intPair]*ContactMaterial

+ 643 - 0
experimental/physics/narrowphase.go

@@ -0,0 +1,643 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package physics
+
+import (
+	"github.com/g3n/engine/experimental/physics/object"
+	"github.com/g3n/engine/experimental/physics/equation"
+	"github.com/g3n/engine/math32"
+	"github.com/g3n/engine/experimental/physics/shape"
+)
+
+// Narrowphase
+type Narrowphase struct {
+	simulation              *Simulation
+	currentContactMaterial  *ContactMaterial
+	enableFrictionReduction bool // If true friction is computed as average
+	debugging               bool
+}
+
+// NewNarrowphase creates and returns a pointer to a new Narrowphase.
+func NewNarrowphase(simulation *Simulation) *Narrowphase {
+
+	n := new(Narrowphase)
+	n.simulation = simulation
+	//n.enableFrictionReduction = true
+
+	// FOR DEBUGGING
+	//n.debugging = true
+
+	return n
+}
+
+// createFrictionEquationsFromContact
+func (n *Narrowphase) createFrictionEquationsFromContact(contactEquation *equation.Contact) (*equation.Friction, *equation.Friction) {
+
+	bodyA := n.simulation.bodies[contactEquation.BodyA().Index()]
+	bodyB := n.simulation.bodies[contactEquation.BodyB().Index()]
+
+	// TODO materials
+	// friction = n.currentContactMaterial.friction
+	// if materials are defined then override: friction = matA.friction * matB.friction
+	//var mug = friction * world.gravity.length()
+	//var reducedMass = bodyA.InvMass() + bodyB.InvMass()
+	//if reducedMass > 0 {
+	//	reducedMass = 1/reducedMass
+	//}
+	slipForce := float32(0.5) //mug*reducedMass
+
+	fricEq1 := equation.NewFriction(bodyA, bodyB, slipForce)
+	fricEq2 := equation.NewFriction(bodyA, bodyB, slipForce)
+
+	fricEq1.SetSpookParams(1e7, 3, n.simulation.dt)
+	fricEq2.SetSpookParams(1e7, 3, n.simulation.dt)
+
+	// Copy over the relative vectors
+	cRA := contactEquation.RA()
+	cRB := contactEquation.RB()
+	fricEq1.SetRA(&cRA)
+	fricEq1.SetRB(&cRB)
+	fricEq2.SetRA(&cRA)
+	fricEq2.SetRB(&cRB)
+
+	// Construct and set tangents
+	cNormal := contactEquation.Normal()
+	t1, t2 := cNormal.RandomTangents()
+	fricEq1.SetTangent(t1)
+	fricEq2.SetTangent(t2)
+
+	// Copy enabled state
+	cEnabled := contactEquation.Enabled()
+	fricEq1.SetEnabled(cEnabled)
+	fricEq2.SetEnabled(cEnabled)
+
+	return fricEq1, fricEq2
+}
+
+// TODO test this
+func (n *Narrowphase) createFrictionFromAverage(contactEqs []*equation.Contact) (*equation.Friction, *equation.Friction) {
+
+	// The last contactEquation
+	lastContactEq := contactEqs[len(contactEqs)-1]
+
+	// Create a friction equation based on the last contact (we will modify it to take into account all contacts)
+	fEq1, fEq2 := n.createFrictionEquationsFromContact(lastContactEq)
+	if (fEq1 == nil && fEq2 == nil) || len(contactEqs) == 1 {
+		return fEq1, fEq2
+	}
+
+	averageNormal := math32.NewVec3()
+	averageContactPointA := math32.NewVec3()
+	averageContactPointB := math32.NewVec3()
+
+	bodyA := lastContactEq.BodyA()
+	//bodyB := lastContactEq.BodyB()
+	normal := lastContactEq.Normal()
+	rA := lastContactEq.RA()
+	rB := lastContactEq.RB()
+
+	for _, cEq := range contactEqs {
+		if cEq.BodyA() != bodyA {
+			averageNormal.Add(&normal)
+			averageContactPointA.Add(&rA)
+			averageContactPointB.Add(&rB)
+		} else {
+			averageNormal.Sub(&normal)
+			averageContactPointA.Add(&rB)
+			averageContactPointB.Add(&rA)
+		}
+	}
+
+	invNumContacts := float32(1) / float32(len(contactEqs))
+
+	averageContactPointA.MultiplyScalar(invNumContacts)
+	averageContactPointB.MultiplyScalar(invNumContacts)
+
+	// Should be the same for both friction equations
+	fEq1.SetRA(averageContactPointA)
+	fEq1.SetRB(averageContactPointB)
+	fEq2.SetRA(averageContactPointA)
+	fEq2.SetRB(averageContactPointB)
+
+	// Set tangents
+	averageNormal.Normalize()
+	t1, t2 := averageNormal.RandomTangents()
+	fEq1.SetTangent(t1)
+	fEq2.SetTangent(t2)
+
+	return fEq1, fEq2
+}
+
+// GenerateEquations is the Narrowphase entry point.
+func (n *Narrowphase) GenerateEquations(pairs []CollisionPair) ([]*equation.Contact, []*equation.Friction) {
+
+	// TODO don't "make" every time, simply re-slice
+	allContactEqs := make([]*equation.Contact, 0)
+	allFrictionEqs := make([]*equation.Friction, 0)
+
+	for k := 0; k < len(pairs); k++ {
+
+		// Get current collision bodies
+		bodyA := pairs[k].BodyA
+		bodyB := pairs[k].BodyB
+
+		bodyTypeA := bodyA.BodyType()
+		bodyTypeB := bodyB.BodyType()
+
+		// For now these collisions are ignored
+		// TODO future: just want to check for collision (in order to dispatch events) and not create equations
+		justTest := (bodyTypeA == object.Kinematic) && (bodyTypeB == object.Static) ||
+				    (bodyTypeA == object.Static)    && (bodyTypeB == object.Kinematic) ||
+				    (bodyTypeA == object.Kinematic) && (bodyTypeB == object.Kinematic)
+
+		// Get contacts
+		if !justTest {
+			//contactEqs, frictionEqs := n.Resolve(bodyA, bodyB)
+			contactEqs, frictionEqs := n.ResolveCollision(bodyA, bodyB)
+			allContactEqs = append(allContactEqs, contactEqs...)
+			allFrictionEqs = append(allFrictionEqs, frictionEqs...)
+		}
+   }
+
+   return allContactEqs, allFrictionEqs
+}
+
+// ResolveCollision figures out which implementation of collision detection and contact resolution to use depending on the shapes involved.
+func (n *Narrowphase) ResolveCollision(bodyA, bodyB *object.Body) ([]*equation.Contact, []*equation.Friction) {
+
+	shapeA := bodyA.Shape()
+	shapeB := bodyB.Shape()
+	posA := bodyA.Position()
+	posB := bodyB.Position()
+	quatA := bodyA.Quaternion()
+	quatB := bodyB.Quaternion()
+
+	switch sA := shapeA.(type) {
+	case *shape.Sphere:
+		switch sB := shapeB.(type) {
+		case *shape.Sphere:
+			return n.SphereSphere(bodyA, bodyB, sA, sB, &posA, &posB, quatA, quatB)
+		case *shape.Plane:
+			return n.SpherePlane(bodyA, bodyB, sA, sB, &posA, &posB, quatA, quatB)
+		case *shape.ConvexHull:
+			return n.SphereConvex(bodyA, bodyB, sA, sB, &posA, &posB, quatA, quatB)
+		}
+	case *shape.Plane:
+		switch sB := shapeB.(type) {
+		case *shape.Sphere:
+			return n.SpherePlane(bodyB, bodyA, sB, sA, &posB, &posA, quatB, quatA)
+		//case *shape.Plane: // plane-plane collision never happens...
+		//	return n.PlanePlane(bodyA, bodyB, sA, sB, &posA, &posB, quatA, quatB)
+		case *shape.ConvexHull:
+			return n.PlaneConvex(bodyA, bodyB, sA, sB, &posA, &posB, quatA, quatB)
+		}
+	case *shape.ConvexHull:
+		switch sB := shapeB.(type) {
+		case *shape.Sphere:
+			return n.SphereConvex(bodyB, bodyA, sB, sA, &posB, &posA, quatB, quatA)
+		case *shape.Plane:
+			return n.PlaneConvex(bodyB, bodyA, sB, sA, &posB, &posA, quatB, quatA)
+		case *shape.ConvexHull:
+			return n.ConvexConvex(bodyA, bodyB, sA, sB, &posA, &posB, quatA, quatB)
+		}
+	}
+
+	return []*equation.Contact{}, []*equation.Friction{}
+}
+
+// SphereSphere resolves the collision between two spheres analytically.
+func (n *Narrowphase) SphereSphere(bodyA, bodyB *object.Body, sphereA, sphereB *shape.Sphere, posA, posB *math32.Vector3, quatA, quatB *math32.Quaternion) ([]*equation.Contact, []*equation.Friction) {
+
+	contactEqs := make([]*equation.Contact, 0, 1)
+	frictionEqs := make([]*equation.Friction, 0, 2)
+
+	radiusA := sphereA.Radius()
+	radiusB := sphereB.Radius()
+
+	if posA.DistanceToSquared(posB) > math32.Pow(radiusA + radiusB, 2) {
+		// No collision
+		return contactEqs, frictionEqs
+	}
+
+	// Find penetration axis
+	penAxis := posB.Clone().Sub(posA).Normalize()
+
+	// Create contact equation
+	contactEq := equation.NewContact(bodyA, bodyB, 0, 1e6)
+	contactEq.SetSpookParams(1e6, 3, n.simulation.dt)
+	//contactEq.SetEnabled(sphereA.CollisionResponse() && sphereB.CollisionResponse()) // TODO
+	contactEq.SetNormal(penAxis.Clone())
+	contactEq.SetRA(penAxis.Clone().MultiplyScalar(radiusB))
+	contactEq.SetRB(penAxis.Clone().MultiplyScalar(-radiusB))
+	contactEqs = append(contactEqs, contactEq)
+
+	// Create friction equations
+	fEq1, fEq2 := n.createFrictionEquationsFromContact(contactEq)
+	frictionEqs = append(frictionEqs, fEq1, fEq2)
+
+	return contactEqs, frictionEqs
+}
+
+// SpherePlane resolves the collision between a sphere and a plane analytically.
+func (n *Narrowphase) SpherePlane(bodyA, bodyB *object.Body, sphereA *shape.Sphere, planeB *shape.Plane, posA, posB *math32.Vector3, quatA, quatB *math32.Quaternion) ([]*equation.Contact, []*equation.Friction) {
+
+	contactEqs := make([]*equation.Contact, 0)
+	frictionEqs := make([]*equation.Friction, 0)
+
+	sphereRadius := sphereA.Radius()
+	localNormal := planeB.Normal()
+	normal := localNormal.Clone().ApplyQuaternion(quatB).Negate().Normalize()
+
+	// Project down sphere on plane
+	point_on_plane_to_sphere := math32.NewVec3().SubVectors(posA, posB)
+	plane_to_sphere_ortho := normal.Clone().MultiplyScalar(normal.Dot(point_on_plane_to_sphere))
+
+	if -point_on_plane_to_sphere.Dot(normal) <= sphereRadius {
+
+		//if justTest {
+		//	return true
+		//}
+
+		// We will have one contact in this case
+		contactEq := equation.NewContact(bodyA, bodyB, 0, 1e6)
+		contactEq.SetSpookParams(1e6, 3, n.simulation.dt)
+		contactEq.SetNormal(normal) // Normalize() might not be needed
+		contactEq.SetRA(normal.Clone().MultiplyScalar(sphereRadius)) // Vector from sphere center to contact point
+		contactEq.SetRB(math32.NewVec3().SubVectors(point_on_plane_to_sphere, plane_to_sphere_ortho)) // The sphere position projected to plane
+		contactEqs = append(contactEqs, contactEq)
+
+		// Create friction equations
+		fEq1, fEq2 := n.createFrictionEquationsFromContact(contactEq)
+		frictionEqs = append(frictionEqs, fEq1, fEq2)
+	}
+
+	return contactEqs, frictionEqs
+}
+
+// TODO The second half of this method is untested!!!
+func (n *Narrowphase) SphereConvex(bodyA, bodyB *object.Body, sphereA *shape.Sphere, convexB *shape.ConvexHull, posA, posB *math32.Vector3, quatA, quatB *math32.Quaternion) ([]*equation.Contact, []*equation.Friction) {
+
+	contactEqs := make([]*equation.Contact, 0)
+	frictionEqs := make([]*equation.Friction, 0)
+
+	// TODO
+	//v3pool := this.v3pool
+	//convex_to_sphere := math32.NewVec3().SubVectors(posA, posB)
+    //normals := sj.faceNormals
+    //faces := sj.faces
+    //verts := sj.vertices
+    //R :=     si.radius
+    //penetrating_sides := []
+
+    // COMMENTED OUT
+	// if(convex_to_sphere.norm2() > si.boundingSphereRadius + sj.boundingSphereRadius){
+	//     return;
+	// }
+	sphereRadius := sphereA.Radius()
+
+	// First check if any vertex of the convex hull is inside the sphere
+	done := false
+	convexB.GetGeometry().ReadVertices(func(vertex math32.Vector3) bool {
+		worldVertex := vertex.ApplyQuaternion(quatA).Add(posB)
+		sphereToCorner := math32.NewVec3().SubVectors(worldVertex, posA)
+		if sphereToCorner.LengthSq() < sphereRadius * sphereRadius {
+			// Colliding! worldVertex is inside sphere.
+
+			// Create contact equation
+			contactEq := equation.NewContact(bodyA, bodyB, 0, 1e6)
+			contactEq.SetSpookParams(1e6, 3, n.simulation.dt)
+			//contactEq.SetEnabled(sphereA.CollisionResponse() && sphereB.CollisionResponse()) // TODO
+			normalizedSphereToCorner := sphereToCorner.Clone().Normalize()
+			contactEq.SetNormal(normalizedSphereToCorner)
+			contactEq.SetRA(normalizedSphereToCorner.Clone().MultiplyScalar(sphereRadius))
+			contactEq.SetRB(worldVertex.Clone().Sub(posB))
+			contactEqs = append(contactEqs, contactEq)
+			// Create friction equations
+			fEq1, fEq2 := n.createFrictionEquationsFromContact(contactEq)
+			frictionEqs = append(frictionEqs, fEq1, fEq2)
+			// Set done flag
+			done = true
+			// Break out of loop
+			return true
+		}
+		return false
+	})
+	if done {
+		return contactEqs, frictionEqs
+	}
+
+	//Check side (plane) intersections TODO NOTE THIS IS UNTESTED
+    convexFaces := convexB.Faces()
+    convexWorldFaceNormals := convexB.WorldFaceNormals()
+    for i := 0; i < len(convexFaces); i++ {
+		worldNormal := convexWorldFaceNormals[i]
+     	face := convexFaces[i]
+     	// Get a world vertex from the face
+     	var worldPoint = face[0].Clone().ApplyQuaternion(quatB).Add(posB)
+     	// Get a point on the sphere, closest to the face normal
+     	var worldSpherePointClosestToPlane = worldNormal.Clone().MultiplyScalar(-sphereRadius).Add(posA)
+     	// Vector from a face point to the closest point on the sphere
+     	var penetrationVec = math32.NewVec3().SubVectors(worldSpherePointClosestToPlane, worldPoint)
+     	// The penetration. Negative value means overlap.
+     	var penetration = penetrationVec.Dot(&worldNormal)
+     	var worldPointToSphere = math32.NewVec3().SubVectors(posA, worldPoint)
+     	if penetration < 0 && worldPointToSphere.Dot(&worldNormal) > 0 {
+         	// Intersects plane. Now check if the sphere is inside the face polygon
+         	worldFace := convexB.WorldFace(face, posB, quatB)
+         	if n.pointBehindFace(worldFace, &worldNormal, posA) { // Is the sphere center behind the face (inside the convex polygon?
+				// TODO NEVER GETTING INSIDE THIS IF STATEMENT!
+				ShowWorldFace(n.simulation.Scene(), worldFace[:], &math32.Color{0,0,2})
+
+				// if justTest {
+             	//    return true
+             	//}
+
+				// Create contact equation
+				contactEq := equation.NewContact(bodyA, bodyB, 0, 1e6)
+				contactEq.SetSpookParams(1e6, 3, n.simulation.dt)
+				//contactEq.SetEnabled(sphereA.CollisionResponse() && sphereB.CollisionResponse()) // TODO
+				contactEq.SetNormal(worldNormal.Clone().Negate())
+				contactEq.SetRA(worldNormal.Clone().MultiplyScalar(-sphereRadius))
+				penetrationVec2 := worldNormal.Clone().MultiplyScalar(-penetration)
+				penetrationSpherePoint := worldNormal.Clone().MultiplyScalar(-sphereRadius)
+				contactEq.SetRB(posA.Clone().Sub(posB).Add(penetrationSpherePoint).Add(penetrationVec2))
+				contactEqs = append(contactEqs, contactEq)
+				// Create friction equations
+				fEq1, fEq2 := n.createFrictionEquationsFromContact(contactEq)
+				frictionEqs = append(frictionEqs, fEq1, fEq2)
+				// Exit method (we only expect *one* face contact)
+             	return contactEqs, frictionEqs
+         	} else {
+				// Edge?
+             	for j := 0; j < len(worldFace); j++ {
+             		// Get two world transformed vertices
+                	v1 := worldFace[(j+1)%3].Clone()//.ApplyQuaternion(quatB).Add(posB)
+                	v2 := worldFace[(j+2)%3].Clone()//.ApplyQuaternion(quatB).Add(posB)
+                	// Construct edge vector
+                	edge := math32.NewVec3().SubVectors(v2, v1)
+                	// Construct the same vector, but normalized
+                	edgeUnit := edge.Clone().Normalize()
+                	// p is xi projected onto the edge
+                	v1ToPosA := math32.NewVec3().SubVectors(posA, v1)
+                	dot := v1ToPosA.Dot(edgeUnit)
+					p := edgeUnit.Clone().MultiplyScalar(dot).Add(v1)
+                	// Compute a vector from p to the center of the sphere
+                	var posAtoP = math32.NewVec3().SubVectors(p, posA)
+                	// Collision if the edge-sphere distance is less than the radius AND if p is in between v1 and v2
+                	edgeL2 := edge.LengthSq()
+                	patp2 := posAtoP.LengthSq()
+                	if (dot > 0) && (dot*dot < edgeL2) && (patp2 < sphereRadius*sphereRadius) { // Collision if the edge-sphere distance is less than the radius
+                	   // Edge contact!
+                	   //if justTest {
+                	   //    return true
+                	   //}
+						// Create contact equation
+						contactEq := equation.NewContact(bodyA, bodyB, 0, 1e6)
+						contactEq.SetSpookParams(1e6, 3, n.simulation.dt)
+						//contactEq.SetEnabled(sphereA.CollisionResponse() && sphereB.CollisionResponse()) // TODO
+						normal := p.Clone().Sub(posA).Normalize()
+						contactEq.SetNormal(normal)
+						contactEq.SetRA(normal.Clone().MultiplyScalar(sphereRadius))
+						contactEq.SetRB(p.Clone().Sub(posB))
+						contactEqs = append(contactEqs, contactEq)
+						// Create friction equations
+						//fEq1, fEq2 := n.createFrictionEquationsFromContact(contactEq)
+						//frictionEqs = append(frictionEqs, fEq1, fEq2)
+						// Exit method (we only expect *one* edge contact)
+						return contactEqs, frictionEqs
+                	}
+             	}
+			}
+     	}
+    }
+
+	return contactEqs, frictionEqs
+}
+
+func (n *Narrowphase) pointBehindFace(worldFace [3]math32.Vector3, faceNormal, point *math32.Vector3) bool {
+
+	pointInFace := worldFace[0].Clone()
+	planeDelta := -pointInFace.Dot(faceNormal)
+	depth := faceNormal.Dot(point) + planeDelta
+	if depth > 0 {
+		return false
+	} else {
+		return true
+	}
+}
+
+// Checks if a given point is inside the polygon. I believe this is a generalization of checking whether a point is behind a face/plane when the face has more than 3 vertices.
+//func (n *Narrowphase) pointInPolygon(verts []math32.Vector3, normal, p *math32.Vector3) bool {
+//
+//	firstTime := true
+//    positiveResult := true // first value of positive result doesn't matter
+//    N := len(verts)
+//    for i := 0; i < N; i++ {
+//        v := verts[i].Clone()
+//        // Get edge to the next vertex
+//        edge := math32.NewVec3().SubVectors(verts[(i+1)%N].Clone(), v)
+//        // Get cross product between polygon normal and the edge
+//        edgeCrossNormal := math32.NewVec3().CrossVectors(edge, normal)
+//        // Get vector between point and current vertex
+//        vertexToP := math32.NewVec3().SubVectors(p, v)
+//        // This dot product determines which side of the edge the point is
+//        r := edgeCrossNormal.Dot(vertexToP)
+//        // If all such dot products have same sign, we are inside the polygon.
+//        if firstTime || (r > 0 && positiveResult == true) || (r <= 0 && positiveResult == false) {
+//            if firstTime {
+//                positiveResult = r > 0
+//				firstTime = false
+//            }
+//            continue
+//        } else {
+//            return false // Encountered some other sign. Exit.
+//        }
+//    }
+//    // If we got here, all dot products were of the same sign.
+//    return true
+//}
+
+// ConvexConvex implements collision detection and contact resolution between two convex hulls.
+func (n *Narrowphase) ConvexConvex(bodyA, bodyB *object.Body, convexA, convexB *shape.ConvexHull, posA, posB *math32.Vector3, quatA, quatB *math32.Quaternion) ([]*equation.Contact, []*equation.Friction) {
+
+	contactEqs := make([]*equation.Contact, 0)
+	frictionEqs := make([]*equation.Friction, 0)
+
+	// Check if colliding and find penetration axis
+	penetrating, penAxis := convexA.FindPenetrationAxis(convexB, posA, posB, quatA, quatB)
+	if !penetrating {
+		return contactEqs, frictionEqs
+	}
+
+	if n.debugging {
+		ShowPenAxis(n.simulation.Scene(), &penAxis) //, -1000, 1000)
+		log.Error("Colliding (%v|%v) penAxis: %v", bodyA.Name(), bodyB.Name(), penAxis)
+	}
+
+	// Colliding! Find contacts.
+	contacts := convexA.ClipAgainstHull(convexB, posA, posB, quatA, quatB, &penAxis, -100, 100)
+
+	// For each contact found create a contact equation and the two associated friction equations
+	for j := 0; j < len(contacts); j++ {
+
+		contact := contacts[j]
+		if n.debugging {
+			ShowContact(n.simulation.Scene(), &contact) // TODO DEBUGGING
+		}
+
+		// Note - contact Normals point from B to A (contacts live in B)
+		// Create contact equation and append it
+		contactEq := equation.NewContact(bodyA, bodyB, 0, 1e6)
+		contactEq.SetSpookParams(1e6, 3, n.simulation.dt)
+		contactEq.SetEnabled(bodyA.CollisionResponse() && bodyB.CollisionResponse())
+		contactEq.SetNormal(penAxis.Clone())
+		contactEq.SetRA(contact.Normal.Clone().MultiplyScalar(-contact.Depth).Add(&contact.Point).Sub(posA))
+		contactEq.SetRB(contact.Point.Clone().Sub(posB))
+		contactEqs = append(contactEqs, contactEq)
+
+		// If enableFrictionReduction is true then skip creating friction equations for individual contacts
+		// We will create average friction equations later based on all contacts
+		if !n.enableFrictionReduction {
+			fEq1, fEq2 := n.createFrictionEquationsFromContact(contactEq)
+			frictionEqs = append(frictionEqs, fEq1, fEq2)
+		}
+	}
+
+	// If enableFrictionReduction is true then we skipped creating friction equations for individual contacts
+	// We now want to create average friction equations based on all contact points.
+	// If we only have one contact however, then friction is small and we don't need to create the friction equations at all.
+	// TODO
+	if n.enableFrictionReduction && len(contactEqs) > 1 {
+		//fEq1, fEq2 := n.createFrictionFromAverage(contactEqs)
+		//frictionEqs = append(frictionEqs, fEq1, fEq2)
+	}
+
+	return contactEqs, frictionEqs
+}
+
+
+//// TODO ?
+//func (n *Narrowphase) GetAveragePointLocal(target) {
+//
+//	target = target || new Vec3()
+//   n := this.vertices.length
+//   verts := this.vertices
+//   for i := 0; i < n; i++ {
+//       target.vadd(verts[i],target)
+//   }
+//   target.mult(1/n,target)
+//   return target
+//}
+
+
+// Checks whether p is inside the polyhedra. Must be in local coords.
+// The point lies outside of the convex hull of the other points if and only if
+// the direction of all the vectors from it to those other points are on less than one half of a sphere around it.
+// p is A point given in local coordinates
+//func (n *Narrowphase) PointIsInside(p) {
+//
+//	verts := this.vertices
+//	faces := this.faces
+//	normals := this.faceNormals
+//  positiveResult := null
+//  N := this.faces.length
+//  pointInside := ConvexPolyhedron_pointIsInside
+//  this.getAveragePointLocal(pointInside)
+//  for i := 0; i < N; i++ {
+//      numVertices := this.faces[i].length
+//      n := normals[i]
+//      v := verts[faces[i][0]] // We only need one point in the face
+//
+//      // This dot product determines which side of the edge the point is
+//      vToP := ConvexPolyhedron_vToP
+//      p.vsub(v,vToP)
+//      r1 := n.dot(vToP)
+//
+//      vToPointInside := ConvexPolyhedron_vToPointInside
+//      pointInside.vsub(v,vToPointInside)
+//      r2 := n.dot(vToPointInside)
+//
+//      if (r1<0 && r2>0) || (r1>0 && r2<0) {
+//          return false // Encountered some other sign. Exit.
+//      }
+//  }
+//
+//  // If we got here, all dot products were of the same sign.
+//  return positiveResult ? 1 : -1
+//}
+
+// TODO
+func (n *Narrowphase) PlaneConvex(bodyA, bodyB *object.Body, planeA *shape.Plane, convexB *shape.ConvexHull, posA, posB *math32.Vector3, quatA, quatB *math32.Quaternion) ([]*equation.Contact, []*equation.Friction) {
+
+	contactEqs := make([]*equation.Contact, 0)
+	frictionEqs := make([]*equation.Friction, 0)
+
+	//planeShape,
+	//convexShape,
+	//planePosition,
+	//convexPosition,
+	//planeQuat,
+	//convexQuat,
+	//planeBody,
+	//convexBody,
+	//si,
+	//sj,
+	//justTest) {
+   //
+	//// Simply return the points behind the plane.
+   //worldVertex := planeConvex_v
+   //worldNormal := planeConvex_normal
+   //worldNormal.set(0,0,1)
+   //planeQuat.vmult(worldNormal,worldNormal) // Turn normal according to plane orientation
+   //
+   //var numContacts = 0
+   //var relpos = planeConvex_relpos
+   //for i := 0; i < len(convexShape.vertices); i++ {
+   //
+   //    // Get world convex vertex
+   //    worldVertex.copy(convexShape.vertices[i])
+   //    convexQuat.vmult(worldVertex, worldVertex)
+   //    convexPosition.vadd(worldVertex, worldVertex)
+   //    worldVertex.vsub(planePosition, relpos)
+   //
+   //    var dot = worldNormal.dot(relpos)
+   //    if dot <= 0.0 {
+   //        if justTest {
+   //            return true
+   //        }
+   //
+   //        var r = this.createContactEquation(planeBody, convexBody, planeShape, convexShape, si, sj)
+   //
+   //        // Get vertex position projected on plane
+   //        var projected = planeConvex_projected
+   //        worldNormal.mult(worldNormal.dot(relpos),projected)
+   //        worldVertex.vsub(projected, projected)
+   //        projected.vsub(planePosition, r.ri) // From plane to vertex projected on plane
+   //
+   //        r.ni.copy(worldNormal) // Contact normal is the plane normal out from plane
+   //
+   //        // rj is now just the vector from the convex center to the vertex
+   //        worldVertex.vsub(convexPosition, r.rj)
+   //
+   //        // Make it relative to the body
+   //        r.ri.vadd(planePosition, r.ri)
+   //        r.ri.vsub(planeBody.position, r.ri)
+   //        r.rj.vadd(convexPosition, r.rj)
+   //        r.rj.vsub(convexBody.position, r.rj)
+   //
+   //        this.result.push(r)
+   //        numContacts++
+   //        if !this.enableFrictionReduction {
+   //            this.createFrictionEquationsFromContact(r, this.frictionResult)
+   //        }
+   //    }
+   //}
+   //
+   //if this.enableFrictionReduction && numContacts {
+   //    this.createFrictionFromAverage(numContacts)
+   //}
+
+   return contactEqs, frictionEqs
+}

+ 769 - 0
experimental/physics/object/body.go

@@ -0,0 +1,769 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package object
+
+import (
+	"github.com/g3n/engine/graphic"
+	"github.com/g3n/engine/math32"
+	"github.com/g3n/engine/material"
+	"github.com/g3n/engine/experimental/physics/shape"
+)
+
+// Body represents a physics-driven body.
+type Body struct {
+	*graphic.Graphic // TODO future - embed core.Node instead and calculate properties recursively
+
+	material             *material.Material   // Physics material specifying friction and restitution
+	index int
+	name string
+
+	// Mass properties
+	mass       float32 // Total mass
+	invMass    float32
+	invMassEff float32 // Effective inverse mass
+
+	// Rotational inertia and related properties
+	rotInertia            *math32.Matrix3 // Angular mass i.e. moment of inertia in local coordinates
+	invRotInertia         *math32.Matrix3 // Inverse rotational inertia in local coordinates
+	invRotInertiaEff      *math32.Matrix3 // Effective inverse rotational inertia in local coordinates
+	invRotInertiaWorld    *math32.Matrix3 // Inverse rotational inertia in world coordinates
+	invRotInertiaWorldEff *math32.Matrix3 // Effective rotational inertia in world coordinates
+	fixedRotation         bool            // Set to true if you don't want the body to rotate. Make sure to run .updateMassProperties() after changing this.
+
+	// Position
+	position       *math32.Vector3 // World position of the center of gravity (World space position of the body.)
+	initPosition   *math32.Vector3 // Initial position of the body.
+	prevPosition   *math32.Vector3 // Previous position
+	interpPosition *math32.Vector3 // Interpolated position of the body.
+
+	// Rotation
+	quaternion       *math32.Quaternion // World space orientation of the body.
+	initQuaternion   *math32.Quaternion
+	prevQuaternion   *math32.Quaternion
+	interpQuaternion *math32.Quaternion // Interpolated orientation of the body.
+
+	// Linear and angular velocities
+	velocity            *math32.Vector3 // Linear velocity (World space velocity of the body.)
+	initVelocity        *math32.Vector3 // Initial linear velocity (World space velocity of the body.)
+	angularVelocity     *math32.Vector3 // Angular velocity of the body, in world space. Think of the angular velocity as a vector, which the body rotates around. The length of this vector determines how fast (in radians per second) the body rotates.
+	initAngularVelocity *math32.Vector3
+
+	// Force and torque
+	force  *math32.Vector3 // Linear force on the body in world space.
+	torque *math32.Vector3 // World space rotational force on the body, around center of mass.
+
+	// Damping and factors
+	linearDamping  float32
+	angularDamping float32
+	linearFactor   *math32.Vector3 // Use this property to limit the motion along any world axis. (1,1,1) will allow motion along all axes while (0,0,0) allows none.
+	angularFactor  *math32.Vector3 // Use this property to limit the rotational motion along any world axis. (1,1,1) will allow rotation along all axes while (0,0,0) allows none.
+
+	// Body type and sleep settings
+	bodyType        BodyType
+	sleepState      BodySleepState // Current sleep state.
+	allowSleep      bool           // If true, the body will automatically fall to sleep.
+	sleepSpeedLimit float32        // If the speed (the norm of the velocity) is smaller than this value, the body is considered sleepy.
+	sleepTimeLimit  float32        // If the body has been sleepy for this sleepTimeLimit seconds, it is considered sleeping.
+	timeLastSleepy  float32
+	wakeUpAfterNarrowphase bool
+
+	// Collision settings
+	colFilterGroup int  // Collision filter group
+	colFilterMask  int  // Collision filter mask
+	colResponse    bool // Whether to produce contact forces when in contact with other bodies. Note that contacts will be generated, but they will be disabled.
+
+	aabb            *math32.Box3 // World space bounding box of the body and its shapes.
+	aabbNeedsUpdate bool         // Indicates if the AABB needs to be updated before use.
+	boundingRadius  float32      // Total bounding radius of the body (TODO including its shapes, relative to body.position.)
+
+	// Cached geometry properties
+	faces            [][3]math32.Vector3
+
+	faceNormals      []math32.Vector3
+	worldFaceNormals []math32.Vector3
+
+	uniqueEdges      []math32.Vector3
+	worldUniqueEdges []math32.Vector3
+
+	shape shape.IShape
+
+	// TODO future (for now a body is a single graphic with a single geometry)
+	// shapes          []*Shape
+	// shapeOffsets    []float32 // Position of each Shape in the body, given in local Body space.
+	// shapeOrientations [] ?
+}
+
+// BodyType specifies how the body is affected during the simulation.
+type BodyType int
+
+const (
+	// A static body does not move during simulation and behaves as if it has infinite mass.
+	// Static bodies can be moved manually by setting the position of the body.
+	// The velocity of a static body is always zero.
+	// Static bodies do not collide with other static or kinematic bodies.
+	Static = BodyType(iota)
+
+	// A kinematic body moves under simulation according to its velocity.
+	// They do not respond to forces.
+	// They can be moved manually, but normally a kinematic body is moved by setting its velocity.
+	// A kinematic body behaves as if it has infinite mass.
+	// Kinematic bodies do not collide with other static or kinematic bodies.
+	Kinematic
+
+	// A dynamic body is fully simulated.
+	// Can be moved manually by the user, but normally they move according to forces.
+	// A dynamic body can collide with all body types.
+	// A dynamic body always has finite, non-zero mass.
+	Dynamic
+)
+
+// TODO Update simulation checks for BodyType to use bitwise operators ?
+
+// BodyStatus specifies
+type BodySleepState int
+
+const (
+	Awake = BodySleepState(iota)
+	Sleepy
+	Sleeping
+)
+
+// Events
+const (
+	SleepyEvent  = "physics.SleepyEvent"  // Dispatched after a body has gone in to the sleepy state.
+	SleepEvent   = "physics.SleepEvent"   // Dispatched after a body has fallen asleep.
+	WakeUpEvent  = "physics.WakeUpEvent"  // Dispatched after a sleeping body has woken up.
+	CollideEvent = "physics.CollideEvent" // Dispatched after two bodies collide. This event is dispatched on each of the two bodies involved in the collision.
+)
+
+// TODO
+type HullType int
+const (
+	Sphere = HullType(iota)
+	Capsule
+	Mesh // use mesh itself
+)
+
+
+// NewBody creates and returns a pointer to a new RigidBody.
+// The igraphic's geometry *must* be convex.
+func NewBody(igraphic graphic.IGraphic) *Body {
+
+	b := new(Body)
+	b.Graphic = igraphic.GetGraphic()
+	b.bodyType = Dynamic
+
+	// Rotational inertia and related properties
+	b.rotInertia = math32.NewMatrix3()
+	b.invRotInertia = math32.NewMatrix3()
+	b.invRotInertiaEff = math32.NewMatrix3()
+	b.invRotInertiaWorld = math32.NewMatrix3()
+	b.invRotInertiaWorldEff = math32.NewMatrix3()
+
+	// Position
+	pos := b.GetNode().Position()
+	b.position = pos.Clone()
+	b.prevPosition = pos.Clone()
+	b.interpPosition = pos.Clone()
+	b.initPosition = pos.Clone()
+
+	// Rotation
+	quat := b.GetNode().Quaternion()
+	b.quaternion = quat.Clone()
+	b.prevQuaternion = quat.Clone()
+	b.interpQuaternion = quat.Clone()
+	b.initQuaternion = quat.Clone()
+
+	// Linear and angular velocities
+	b.velocity = math32.NewVec3()
+	b.initVelocity = math32.NewVec3()
+	b.angularVelocity = math32.NewVec3()
+	b.initAngularVelocity = math32.NewVec3()
+
+	// Force and torque
+	b.force = math32.NewVec3()
+	b.torque = math32.NewVec3()
+
+	// Damping and factors
+	b.linearDamping = 0.01
+	b.angularDamping = 0.01
+	b.linearFactor = math32.NewVector3(1, 1, 1)
+	b.angularFactor = math32.NewVector3(1, 1, 1)
+
+	// Sleep settings
+	b.allowSleep = true
+	b.sleepState = Awake
+	b.sleepSpeedLimit = 0.1
+	b.sleepTimeLimit = 1
+	b.timeLastSleepy = 0
+
+	// Collision filtering
+	b.colFilterGroup = 1
+	b.colFilterMask = -1
+
+	//b.fixedRotation = true
+
+	b.wakeUpAfterNarrowphase = false
+
+	b.SetShape(shape.NewConvexHull(b.GetGeometry()))
+
+	b.SetMass(1)
+	b.UpdateMassProperties()
+	b.UpdateEffectiveMassProperties()
+
+	return b
+}
+
+// TODO future: modify this to be "AddShape" and keep track of list of shapes, their positions and orientations
+// For now each body can only be a single shape or a single geometry
+func (b *Body) SetShape(shape shape.IShape) {
+
+	b.shape = shape
+}
+
+func (b *Body) Shape() shape.IShape {
+
+	return b.shape
+}
+
+func (b *Body) BoundingBox() math32.Box3 {
+
+	// TODO future allow multiple shapes
+	mat4 := math32.NewMatrix4().Compose(b.position, b.quaternion, math32.NewVector3(1,1,1))
+	localBB := b.shape.BoundingBox()
+	worldBB := localBB.ApplyMatrix4(mat4)
+	return *worldBB
+}
+
+func (b *Body) SetMass(mass float32) {
+
+	// Do nothing if current mass is already the specified mass
+	if mass == b.mass {
+		return
+	}
+
+	// Set mass and update inverse mass
+	b.mass = mass
+	if b.mass > 0 {
+		b.invMass = 1.0 / b.mass
+	} else {
+		// Body mass is zero - this means that the body is static
+		b.invMass = 0
+		b.bodyType = Static
+	}
+
+	b.UpdateMassProperties()
+}
+
+func (b *Body) SetIndex(i int) {
+
+	b.index = i
+}
+
+func (b *Body) SetName(name string) {
+
+	b.name = name
+}
+
+func (b *Body) Name() string {
+
+	return b.name
+}
+
+func (b *Body) Index() int {
+
+	return b.index
+}
+
+func (b *Body) Material() *material.Material {
+
+	return b.material
+}
+
+func (b *Body) SetAllowSleep(state bool) {
+
+	b.allowSleep = state
+}
+
+func (b *Body) AllowSleep() bool {
+
+	return b.allowSleep
+}
+
+func (b *Body) SleepSpeedLimit() float32 {
+
+	return b.sleepSpeedLimit
+}
+
+func (b *Body) SleepState() BodySleepState {
+
+	return b.sleepState
+}
+
+// SetBodyType sets the body type.
+func (b *Body) SetBodyType(bodyType BodyType) {
+
+	// Do nothing if body is already of the specified bodyType
+	if b.bodyType == bodyType {
+		return
+	}
+
+	// If we want the body to be static we need to zero its mass
+	if bodyType == Static {
+		b.mass = 0
+	}
+
+	// Temporarily save original body type and update current body type
+	origBodyType := b.bodyType
+	b.bodyType = bodyType
+
+	// If changed body type to or from Static then we need to update mass properties
+	if origBodyType == Static || b.bodyType == Static {
+		b.UpdateMassProperties()
+	}
+}
+
+func (b *Body) BodyType() BodyType {
+
+	return b. bodyType
+}
+
+func (b *Body) SetWakeUpAfterNarrowphase(state bool) {
+
+	b.wakeUpAfterNarrowphase = state
+}
+
+func (b *Body) WakeUpAfterNarrowphase() bool {
+
+	return b.wakeUpAfterNarrowphase
+}
+
+// ApplyVelocityDeltas adds the specified deltas to the body's linear and angular velocities.
+func (b *Body) ApplyVelocityDeltas(linearD, angularD *math32.Vector3) {
+
+	b.velocity.Add(linearD.Multiply(b.linearFactor))
+	b.angularVelocity.Add(angularD.Multiply(b.angularFactor))
+}
+
+// ClearForces clears all forces on the body.
+func (b *Body) ClearForces() {
+
+	b.force.Zero()
+	b.torque.Zero()
+}
+
+func (b *Body) InvMassEff() float32 {
+
+	return b.invMassEff
+}
+
+func (b *Body) InvRotInertiaWorldEff() *math32.Matrix3 {
+
+	return b.invRotInertiaWorldEff
+}
+
+func (b *Body) Position() math32.Vector3 {
+
+	return *b.position
+}
+
+func (b *Body) Quaternion() *math32.Quaternion {
+
+	return b.quaternion.Clone()
+}
+
+func (b *Body) SetVelocity(vel *math32.Vector3) {
+
+	b.velocity = vel
+}
+
+func (b *Body) Velocity() math32.Vector3 {
+
+	return *b.velocity
+}
+
+func (b *Body) SetAngularVelocity(vel *math32.Vector3) {
+
+	b.angularVelocity = vel
+}
+
+func (b *Body) AngularVelocity() math32.Vector3 {
+
+	return *b.angularVelocity
+}
+
+func (b *Body) Force() math32.Vector3 {
+
+	return *b.force
+}
+
+func (b *Body) Torque() math32.Vector3 {
+
+	return *b.torque
+}
+
+func (b *Body) SetLinearDamping(d float32) {
+
+	b.linearDamping = d
+}
+
+func (b *Body) LinearDamping() float32 {
+
+	return b.linearDamping
+}
+
+func (b *Body) SetAngularDamping(d float32) {
+
+	b.angularDamping = d
+}
+
+func (b *Body) AngularDamping() float32 {
+
+	return b.angularDamping
+}
+
+func (b *Body) ApplyDamping(dt float32) {
+
+	b.velocity.MultiplyScalar(math32.Pow(1.0 - b.linearDamping, dt))
+	b.angularVelocity.MultiplyScalar(math32.Pow(1.0 - b.angularDamping, dt))
+}
+
+func (b *Body) SetLinearFactor(factor *math32.Vector3) {
+
+	b.linearFactor = factor
+}
+
+func (b *Body) LinearFactor() math32.Vector3 {
+
+	return *b.linearFactor
+}
+
+func (b *Body) SetAngularFactor(factor *math32.Vector3) {
+
+	b.angularFactor = factor
+}
+
+func (b *Body) AngularFactor() math32.Vector3 {
+
+	return *b.angularFactor
+}
+
+// SetFixedRotation specifies whether the body should rotate.
+func (b *Body) SetFixedRotation(state bool) {
+
+	// Do nothing if the fixedRotation flag already has the specified value
+	if b.fixedRotation == state {
+		return
+	}
+
+	// Set the fixedRotation flag and update mass properties
+	b.fixedRotation = state
+	b.UpdateMassProperties()
+}
+
+// WakeUp wakes the body up.
+func (b *Body) WakeUp() {
+
+	state := b.sleepState
+	b.sleepState = Awake
+	b.wakeUpAfterNarrowphase = false
+	if state == Sleeping {
+		b.Dispatch(WakeUpEvent, nil)
+	}
+}
+
+// Sleep forces the body to sleep.
+func (b *Body) Sleep() {
+
+	b.sleepState = Sleeping
+	b.velocity.Set(0, 0, 0)
+	b.angularVelocity.Set(0, 0, 0)
+	b.wakeUpAfterNarrowphase = false
+}
+
+// Called every timestep to update internal sleep timer and change sleep state if needed.
+// time: The world time in seconds
+func (b *Body) SleepTick(time float32) {
+
+	if b.allowSleep {
+		speedSquared := b.velocity.LengthSq() + b.angularVelocity.LengthSq()
+		speedLimitSquared := math32.Pow(b.sleepSpeedLimit, 2)
+		if b.sleepState == Awake && speedSquared < speedLimitSquared {
+			b.sleepState = Sleepy
+			b.timeLastSleepy = time
+			b.Dispatch(SleepyEvent, nil)
+		} else if b.sleepState == Sleepy && speedSquared > speedLimitSquared {
+			b.WakeUp() // Wake up
+		} else if b.sleepState == Sleepy && (time-b.timeLastSleepy) > b.sleepTimeLimit {
+			b.Sleep() // Sleeping
+			b.Dispatch(SleepEvent, nil)
+		}
+	}
+}
+
+// If checkSleeping is true then returns false if both bodies are currently sleeping.
+func (b *Body) Sleeping() bool {
+
+	return b.sleepState == Sleeping
+}
+
+// CollidableWith returns whether the body can collide with the specified body.
+func (b *Body) CollidableWith(other *Body) bool {
+
+	if (b.colFilterGroup & other.colFilterMask == 0) ||
+		(other.colFilterGroup & b.colFilterMask == 0) ||
+		(b.bodyType == Static) && (other.bodyType == Static) {
+		return false
+	}
+
+	return true
+}
+
+func (b *Body) CollisionResponse() bool {
+
+	return b.colResponse
+}
+
+// PointToLocal converts a world point to local body frame. TODO maybe move to Node
+func (b *Body) PointToLocal(worldPoint *math32.Vector3) math32.Vector3 {
+
+	return *worldPoint.Clone().Sub(b.position).ApplyQuaternion(b.quaternion.Conjugate())
+}
+
+// VectorToLocal converts a world vector to local body frame. TODO maybe move to Node
+func (b *Body) VectorToLocal(worldVector *math32.Vector3) math32.Vector3 {
+
+	return *worldVector.Clone().ApplyQuaternion(b.quaternion.Conjugate())
+}
+
+// PointToWorld converts a local point to world frame. TODO maybe move to Node
+func (b *Body) PointToWorld(localPoint *math32.Vector3) math32.Vector3 {
+
+	return *localPoint.Clone().ApplyQuaternion(b.quaternion).Add(b.position)
+}
+
+// VectorToWorld converts a local vector to world frame. TODO maybe move to Node
+func (b *Body) VectorToWorld(localVector *math32.Vector3) math32.Vector3 {
+
+	return *localVector.Clone().ApplyQuaternion(b.quaternion)
+}
+
+// UpdateEffectiveMassProperties
+// If the body is sleeping, it should be immovable and thus have infinite mass during solve.
+// This is solved by having a separate "effective mass" and other "effective" properties
+func (b *Body) UpdateEffectiveMassProperties() {
+
+	if b.sleepState == Sleeping || b.bodyType == Kinematic {
+		b.invMassEff = 0
+		b.invRotInertiaEff.Zero()
+		b.invRotInertiaWorldEff.Zero()
+	} else {
+		b.invMassEff = b.invMass
+		b.invRotInertiaEff.Copy(b.invRotInertia)
+		b.invRotInertiaWorldEff.Copy(b.invRotInertiaWorld)
+	}
+}
+
+// UpdateMassProperties
+// Should be called whenever you change the body shape or mass.
+func (b *Body) UpdateMassProperties() {
+
+	if b.mass > 0 {
+		b.invMass = 1.0 / b.mass
+	} else {
+		b.invMass = 0
+	}
+
+	if b.fixedRotation || b.bodyType == Static {
+		b.rotInertia.Zero()
+		b.invRotInertia.Zero()
+	} else {
+		*b.rotInertia = b.GetGeometry().RotationalInertia(b.mass)
+		b.rotInertia.MultiplyScalar(10) // multiply by high density // TODO remove this ?
+		b.invRotInertia.GetInverse(b.rotInertia) // Note: rotInertia is always positive definite and thus always invertible
+	}
+
+	b.UpdateInertiaWorld(true)
+}
+
+// Update .inertiaWorld and .invRotInertiaWorld
+func (b *Body) UpdateInertiaWorld(force bool) {
+
+	iRI := b.invRotInertia
+	// If rotational inertia M = s*I, where I is identity and s a scalar, then
+	//    R*M*R' = R*(s*I)*R' = s*R*I*R' = s*R*R' = s*I = M
+	// where R is the rotation matrix.
+	// In other words, we don't have to do the transformation if all diagonal entries are equal.
+	if iRI[0] != iRI[4] || iRI[4] != iRI[8] || force {
+		// iRIW = R * iRI * R'
+		m1 := math32.NewMatrix3().MakeRotationFromQuaternion(b.quaternion)
+		m2 := m1.Clone().Transpose()
+		m2.Multiply(iRI)
+		b.invRotInertiaWorld.MultiplyMatrices(m2, m1)
+	}
+}
+
+// Forces from a force field need to be multiplied by mass.
+func (b *Body) ApplyForceField(force *math32.Vector3) {
+
+	b.force.Add(force.MultiplyScalar(b.mass))
+}
+
+// Apply force to a world point.
+// This could for example be a point on the Body surface.
+// Applying force this way will add to Body.force and Body.torque.
+// relativePoint: A point relative to the center of mass to apply the force on.
+func (b *Body) ApplyForce(force, relativePoint *math32.Vector3) {
+
+	if b.bodyType != Dynamic { // Needed?
+		return
+	}
+
+	// Add linear force
+	b.force.Add(force) // TODO shouldn't rotational momentum be subtracted from linear momentum?
+
+	// Add rotational force
+	b.torque.Add(math32.NewVec3().CrossVectors(relativePoint, force))
+}
+
+// Apply force to a local point in the body.
+// force: The force vector to apply, defined locally in the body frame.
+// localPoint: A local point in the body to apply the force on.
+func (b *Body) ApplyLocalForce(localForce, localPoint *math32.Vector3) {
+
+	if b.bodyType != Dynamic {
+		return
+	}
+
+	// Transform the force vector to world space
+	worldForce := b.VectorToWorld(localForce)
+	relativePointWorld := b.VectorToWorld(localPoint)
+
+	b.ApplyForce(&worldForce, &relativePointWorld)
+}
+
+// Apply impulse to a world point.
+// This could for example be a point on the Body surface.
+// An impulse is a force added to a body during a short period of time (impulse = force * time).
+// Impulses will be added to Body.velocity and Body.angularVelocity.
+// impulse: The amount of impulse to add.
+// relativePoint: A point relative to the center of mass to apply the force on.
+func (b *Body) ApplyImpulse(impulse, relativePoint *math32.Vector3) {
+
+	if b.bodyType != Dynamic {
+		return
+	}
+
+	// Compute point position relative to the body center
+	r := relativePoint
+
+	// Compute produced central impulse velocity
+	velo := impulse.Clone().MultiplyScalar(b.invMass)
+
+	// Add linear impulse
+	b.velocity.Add(velo)
+
+	// Compute produced rotational impulse velocity
+	rotVelo := math32.NewVec3().CrossVectors(r, impulse)
+	rotVelo.ApplyMatrix3(b.invRotInertiaWorld)
+
+	// Add rotational Impulse
+	b.angularVelocity.Add(rotVelo)
+}
+
+// Apply locally-defined impulse to a local point in the body.
+// force: The force vector to apply, defined locally in the body frame.
+// localPoint: A local point in the body to apply the force on.
+func (b *Body) ApplyLocalImpulse(localImpulse, localPoint *math32.Vector3) {
+
+	if b.bodyType != Dynamic {
+		return
+	}
+
+	// Transform the force vector to world space
+	worldImpulse := b.VectorToWorld(localImpulse)
+	relativePointWorld := b.VectorToWorld(localPoint)
+
+	b.ApplyImpulse(&worldImpulse, &relativePointWorld)
+}
+
+// Get world velocity of a point in the body.
+func (b *Body) GetVelocityAtWorldPoint(worldPoint *math32.Vector3) *math32.Vector3 {
+
+	r := math32.NewVec3().SubVectors(worldPoint, b.position)
+	r.CrossVectors(b.angularVelocity, r)
+	r.Add(b.velocity)
+
+	return r
+}
+
+// Move the body forward in time.
+// dt: Time step
+// quatNormalize: Set to true to normalize the body quaternion
+// quatNormalizeFast: If the quaternion should be normalized using "fast" quaternion normalization
+func (b *Body) Integrate(dt float32, quatNormalize, quatNormalizeFast bool) {
+
+	// Save previous position and rotation
+	b.prevPosition.Copy(b.position)
+	b.prevQuaternion.Copy(b.quaternion)
+
+	// If static or sleeping - skip
+	if !(b.bodyType == Dynamic || b.bodyType == Kinematic) || b.sleepState == Sleeping {
+		return
+	}
+
+	// Integrate force over mass (acceleration) to obtain estimate for instantaneous velocities
+	iMdt := b.invMass * dt
+	b.velocity.X += b.force.X * iMdt * b.linearFactor.X
+	b.velocity.Y += b.force.Y * iMdt * b.linearFactor.Y
+	b.velocity.Z += b.force.Z * iMdt * b.linearFactor.Z
+
+	// Integrate inverse angular mass times torque to obtain estimate for instantaneous angular velocities
+	e := b.invRotInertiaWorld
+	tx := b.torque.X * b.angularFactor.X
+	ty := b.torque.Y * b.angularFactor.Y
+	tz := b.torque.Z * b.angularFactor.Z
+	b.angularVelocity.X += dt * (e[0]*tx + e[3]*ty + e[6]*tz)
+	b.angularVelocity.Y += dt * (e[1]*tx + e[4]*ty + e[7]*tz)
+	b.angularVelocity.Z += dt * (e[2]*tx + e[5]*ty + e[8]*tz)
+
+	// Integrate velocity to obtain estimate for position
+	b.position.X += b.velocity.X * dt
+	b.position.Y += b.velocity.Y * dt
+	b.position.Z += b.velocity.Z * dt
+
+	// Integrate angular velocity to obtain estimate for rotation
+	ax := b.angularVelocity.X * b.angularFactor.X
+	ay := b.angularVelocity.Y * b.angularFactor.Y
+	az := b.angularVelocity.Z * b.angularFactor.Z
+	bx := b.quaternion.X
+	by := b.quaternion.Y
+	bz := b.quaternion.Z
+	bw := b.quaternion.W
+	halfDt := dt * 0.5
+	b.quaternion.X += halfDt * (ax*bw + ay*bz - az*by)
+	b.quaternion.Y += halfDt * (ay*bw + az*bx - ax*bz)
+	b.quaternion.Z += halfDt * (az*bw + ax*by - ay*bx)
+	b.quaternion.W += halfDt * (-ax*bx - ay*by - az*bz)
+
+	// Normalize quaternion
+	b.quaternion.Normalize()
+	//if quatNormalize { // TODO future
+	//	if quatNormalizeFast {
+	//		b.quaternion.NormalizeFast()
+	//	} else {
+	//		b.quaternion.Normalize()
+	//	}
+	//}
+
+	// Update position and rotation of Node (containing visual representation of the body)
+	b.GetNode().SetPositionVec(b.position)
+	b.GetNode().SetRotationQuat(b.quaternion)
+
+	b.aabbNeedsUpdate = true
+
+	// Update world inertia
+	b.UpdateInertiaWorld(false)
+}

+ 31 - 0
experimental/physics/particle.go

@@ -0,0 +1,31 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package physics
+
+//import (
+//	"github.com/g3n/engine/math32"
+//	"github.com/g3n/engine/graphic"
+//)
+//
+//// Particle represents a physics-driven particle.
+//type Particle struct {
+//	Body
+//	mass      float32
+//	radius    float32
+//	position  math32.Vector3
+//	velocity  math32.Vector3
+//	//netForce  math32.Vector3
+//	colliding bool
+//}
+//
+//// NewParticle creates and returns a pointer to a new Particle.
+//func  NewParticle(igraphic graphic.IGraphic) *Particle {
+//
+//	p := new(Particle)
+//	p.Graphic = igraphic.GetGraphic()
+//	p.mass = 1
+//	p.radius = 1
+//	return p
+//}

+ 5 - 0
experimental/physics/shape/box.go

@@ -0,0 +1,5 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package shape

+ 6 - 0
experimental/physics/shape/capsule.go

@@ -0,0 +1,6 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package shape
+

+ 465 - 0
experimental/physics/shape/convexhull.go

@@ -0,0 +1,465 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package shape
+
+import (
+	"github.com/g3n/engine/geometry"
+	"github.com/g3n/engine/math32"
+	"github.com/g3n/engine/experimental/physics/collision"
+)
+
+// ConvexHull is a convex triangle-based geometry used for collision detection and contact resolution.
+type ConvexHull struct {
+	geometry.Geometry
+
+	// Cached geometry properties
+	faces            [][3]math32.Vector3
+	faceNormals      []math32.Vector3
+	worldFaceNormals []math32.Vector3
+	uniqueEdges      []math32.Vector3
+	worldUniqueEdges []math32.Vector3
+
+}
+
+func NewConvexHull(geom *geometry.Geometry) *ConvexHull {
+
+	ch := new(ConvexHull)
+	// // TODO check if geometry is convex, panic if not
+	//if !geom.IsConvex() {
+	//	panic("geometry needs to be convex")
+	//}
+	// // TODO future: create function to break up geometry into convex shapes and add all shapes to body
+
+	ch.Geometry = *geom
+
+	// Perform single-time computations
+	ch.computeFaceNormalsAndUniqueEdges()
+
+	return ch
+}
+
+// Compute and store face normals and unique edges
+func (ch *ConvexHull) computeFaceNormalsAndUniqueEdges() {
+
+	ch.GetGeometry().ReadFaces(func(vA, vB, vC math32.Vector3) bool {
+
+		// Store face vertices
+		var face [3]math32.Vector3
+		face[0] = vA
+		face[1] = vB
+		face[2] = vC
+		ch.faces = append(ch.faces, face)
+
+		// Compute edges
+		edge1 := math32.NewVec3().SubVectors(&vB, &vA)
+		edge2 := math32.NewVec3().SubVectors(&vC, &vB)
+		edge3 := math32.NewVec3().SubVectors(&vA, &vC)
+
+		// Compute and store face normal in b.faceNormals
+		faceNormal := math32.NewVec3().CrossVectors(edge2, edge1)
+		if faceNormal.Length() > 0 {
+			faceNormal.Normalize().Negate()
+		}
+		ch.faceNormals = append(ch.faceNormals, *faceNormal)
+
+		// Compare unique edges recorded so far with the three new face edges and store the unique ones
+		tol := float32(1e-6)
+		for p := 0; p < len(ch.uniqueEdges); p++ {
+			ue := ch.uniqueEdges[p]
+			if !ue.AlmostEquals(edge1, tol) {
+				ch.uniqueEdges = append(ch.uniqueEdges, *edge1)
+			}
+			if !ue.AlmostEquals(edge2, tol) {
+				ch.uniqueEdges = append(ch.uniqueEdges, *edge1)
+			}
+			if !ue.AlmostEquals(edge3, tol) {
+				ch.uniqueEdges = append(ch.uniqueEdges, *edge1)
+			}
+		}
+
+		return false
+	})
+
+	// Allocate space for worldFaceNormals and worldUniqueEdges
+	ch.worldFaceNormals = make([]math32.Vector3, len(ch.faceNormals))
+	ch.worldUniqueEdges = make([]math32.Vector3, len(ch.uniqueEdges))
+}
+
+// ComputeWorldFaceNormalsAndUniqueEdges
+func (ch *ConvexHull) ComputeWorldFaceNormalsAndUniqueEdges(quat *math32.Quaternion) {
+
+	// Re-compute world face normals from local face normals
+	for i := 0; i < len(ch.faceNormals); i++ {
+		ch.worldFaceNormals[i] = ch.faceNormals[i]
+		ch.worldFaceNormals[i].ApplyQuaternion(quat)
+	}
+	// Re-compute world unique edges from local unique edges
+	for i := 0; i < len(ch.uniqueEdges); i++ {
+		ch.worldUniqueEdges[i] = ch.uniqueEdges[i]
+		ch.worldUniqueEdges[i].ApplyQuaternion(quat)
+	}
+}
+
+func (ch *ConvexHull) Faces() [][3]math32.Vector3 {
+
+	return ch.faces
+}
+
+func (ch *ConvexHull) FaceNormals() []math32.Vector3 {
+
+	return ch.faceNormals
+}
+
+func (ch *ConvexHull) WorldFaceNormals() []math32.Vector3 {
+
+	return ch.worldFaceNormals
+}
+
+func (ch *ConvexHull) UniqueEdges() []math32.Vector3 {
+
+	return ch.uniqueEdges
+}
+
+func (ch *ConvexHull) WorldUniqueEdges() []math32.Vector3 {
+
+	return ch.worldUniqueEdges
+}
+
+// FindPenetrationAxis finds the penetration axis between two convex bodies.
+// The normal points from bodyA to bodyB.
+// Returns false if there is no penetration. If there is a penetration - returns true and the penetration axis.
+func (ch *ConvexHull) FindPenetrationAxis(chB *ConvexHull, posA, posB *math32.Vector3, quatA, quatB *math32.Quaternion) (bool, math32.Vector3) {
+
+	// Keep track of the smaller depth found so far
+	// Note that the penetration axis is the one that causes
+	// the smallest penetration depth when the two hulls are squished onto that axis!
+	// (may seem a bit counter-intuitive)
+	depthMin := math32.Inf(1)
+
+	var penetrationAxis math32.Vector3
+	var depth float32
+
+	// Assume the geometries are penetrating.
+	// As soon as (and if) we figure out that they are not, then return false.
+	penetrating := true
+
+	worldFaceNormalsA := ch.WorldFaceNormals()
+	worldFaceNormalsB := ch.WorldFaceNormals()
+
+	// Check world normals of body A
+	for _, worldFaceNormal := range worldFaceNormalsA {
+		// Check whether the face is colliding with geomB
+		penetrating, depth = ch.TestPenetrationAxis(chB, &worldFaceNormal, posA, posB, quatA, quatB)
+		if !penetrating {
+			return false, penetrationAxis // penetrationAxis doesn't matter since not penetrating
+		}
+		if depth < depthMin {
+			depthMin = depth
+			penetrationAxis.Copy(&worldFaceNormal)
+		}
+	}
+
+	// Check world normals of body B
+	for _, worldFaceNormal := range worldFaceNormalsB {
+		// Check whether the face is colliding with geomB
+		penetrating, depth = ch.TestPenetrationAxis(chB, &worldFaceNormal, posA, posB, quatA, quatB)
+		if !penetrating {
+			return false, penetrationAxis // penetrationAxis doesn't matter since not penetrating
+		}
+		if depth < depthMin {
+			depthMin = depth
+			penetrationAxis.Copy(&worldFaceNormal)
+		}
+	}
+
+	worldUniqueEdgesA := ch.WorldUniqueEdges()
+	worldUniqueEdgesB := ch.WorldUniqueEdges()
+
+	// Check all combinations of unique world edges
+	for _, worldUniqueEdgeA := range worldUniqueEdgesA {
+		for _, worldUniqueEdgeB := range worldUniqueEdgesB {
+			// Cross edges
+			edgeCross := math32.NewVec3().CrossVectors(&worldUniqueEdgeA, &worldUniqueEdgeB)
+			// If the edges are not aligned
+			tol := float32(1e-6)
+			if edgeCross.Length() > tol { // Cross product is not close to zero
+				edgeCross.Normalize()
+				penetrating, depth = ch.TestPenetrationAxis(chB, edgeCross, posA, posB, quatA, quatB)
+				if !penetrating {
+					return false, penetrationAxis
+				}
+				if depth < depthMin {
+					depthMin = depth
+					penetrationAxis.Copy(edgeCross)
+				}
+			}
+		}
+	}
+
+	deltaC := math32.NewVec3().SubVectors(posA, posB)
+	if deltaC.Dot(&penetrationAxis) > 0.0 {
+		penetrationAxis.Negate()
+	}
+
+	return true, penetrationAxis
+}
+
+// Both hulls are projected onto the axis and the overlap size (penetration depth) is returned if there is one.
+// return {number} The overlap depth, or FALSE if no penetration.
+func (ch *ConvexHull) TestPenetrationAxis(chB *ConvexHull, worldAxis, posA, posB *math32.Vector3, quatA, quatB *math32.Quaternion) (bool, float32) {
+
+	maxA, minA := ch.ProjectOntoWorldAxis(worldAxis, posA, quatA)
+	maxB, minB := chB.ProjectOntoWorldAxis(worldAxis, posB, quatB)
+
+	if maxA < minB || maxB < minA {
+		return false, 0 // Separated
+	}
+
+	d0 := maxA - minB
+	d1 := maxB - minA
+
+	if d0 < d1 {
+		return true, d0
+	} else {
+		return true, d1
+	}
+}
+
+// ProjectOntoWorldAxis projects the geometry onto the specified world axis.
+func (ch *ConvexHull) ProjectOntoWorldAxis(worldAxis, pos *math32.Vector3, quat *math32.Quaternion) (float32, float32) {
+
+	// Transform the world axis to local
+	quatConj := quat.Conjugate()
+	localAxis := worldAxis.Clone().ApplyQuaternion(quatConj)
+
+	// Project onto the local axis
+	max, min := ch.GetGeometry().ProjectOntoAxis(localAxis)
+
+	// Offset to obtain values relative to world origin
+	localOrigin := math32.NewVec3().Sub(pos).ApplyQuaternion(quatConj)
+	add := localOrigin.Dot(localAxis)
+	min -= add
+	max -= add
+
+	return max, min
+}
+
+// =====================================================================
+
+//{array} result The an array of contact point objects, see clipFaceAgainstHull
+func (ch *ConvexHull) ClipAgainstHull(chB *ConvexHull, posA, posB *math32.Vector3, quatA, quatB *math32.Quaternion, penAxis *math32.Vector3, minDist, maxDist float32) []collision.Contact {
+
+	var contacts []collision.Contact
+
+	// Invert penetration axis so it points from b to a
+	invPenAxis := penAxis.Clone().Negate()
+
+	// Find face of B that is closest (i.e. that is most aligned with the penetration axis)
+	closestFaceBidx := -1
+	dmax := math32.Inf(-1)
+	worldFaceNormalsB := chB.WorldFaceNormals()
+	for i, worldFaceNormal := range worldFaceNormalsB {
+		// Note - normals must be pointing out of the body so that they align with the penetration axis in the line below
+		d := worldFaceNormal.Dot(invPenAxis)
+		if d > dmax {
+			dmax = d
+			closestFaceBidx = i
+		}
+	}
+
+	// If found a closest face (sometimes we don't find one)
+	if closestFaceBidx >= 0 {
+
+		// Copy and transform face vertices to world coordinates
+		faces := chB.Faces()
+		worldClosestFaceB := ch.WorldFace(faces[closestFaceBidx], posB, quatB)
+
+		// Clip the closest world face of B to only the portion that is inside the hull of A
+		contacts = ch.clipFaceAgainstHull(posA, penAxis, quatA, worldClosestFaceB, minDist, maxDist)
+	}
+
+	return contacts
+}
+
+func (ch *ConvexHull) WorldFace(face [3]math32.Vector3, pos *math32.Vector3, quat *math32.Quaternion) [3]math32.Vector3 {
+
+	var result [3]math32.Vector3
+	result[0] = face[0]
+	result[1] = face[1]
+	result[2] = face[2]
+	result[0].ApplyQuaternion(quat).Add(pos)
+	result[1].ApplyQuaternion(quat).Add(pos)
+	result[2].ApplyQuaternion(quat).Add(pos)
+	return result
+}
+
+// Clip a face against a hull.
+//@param {Array} worldVertsB1 An array of Vec3 with vertices in the world frame.
+//@param Array result Array to store resulting contact points in. Will be objects with properties: point, depth, normal. These are represented in world coordinates.
+func (ch *ConvexHull) clipFaceAgainstHull(posA, penAxis *math32.Vector3, quatA *math32.Quaternion, worldClosestFaceB [3]math32.Vector3, minDist, maxDist float32) []collision.Contact {
+
+	contacts := make([]collision.Contact, 0)
+
+	// Find the face of A with normal closest to the separating axis (i.e. that is most aligned with the penetration axis)
+	closestFaceAidx := -1
+	dmax := math32.Inf(-1)
+	worldFaceNormalsA := ch.WorldFaceNormals()
+	for i, worldFaceNormal := range worldFaceNormalsA {
+		// Note - normals must be pointing out of the body so that they align with the penetration axis in the line below
+		d := worldFaceNormal.Dot(penAxis)
+		if d > dmax {
+			dmax = d
+			closestFaceAidx = i
+		}
+	}
+
+	if closestFaceAidx < 0 {
+		// Did not find any closest face...
+		return contacts
+	}
+
+	//console.log("closest A: ",worldClosestFaceA);
+
+	// Get the face and construct connected faces
+	facesA := ch.Faces()
+	//worldClosestFaceA := n.WorldFace(facesA[closestFaceAidx], bodyA)
+	closestFaceA := facesA[closestFaceAidx]
+	connectedFaces := make([]int, 0) // indexes of the connected faces
+	for faceIdx := 0; faceIdx < len(facesA); faceIdx++ {
+		// Skip worldClosestFaceA
+		if faceIdx == closestFaceAidx {
+			continue
+		}
+		// Test that face has not already been added
+		for _, cfidx := range connectedFaces {
+			if cfidx == faceIdx {
+				continue
+			}
+		}
+		face := facesA[faceIdx]
+		// Loop through face vertices and see if any of them are also present in the closest face
+		// If a vertex is shared and this connected face hasn't been recorded yet - record and break inner loop
+		for pConnFaceVidx := 0; pConnFaceVidx < len(face); pConnFaceVidx++ {
+			var goToNextFace bool
+			// Test if face shares a vertex with closetFaceA - add it to connectedFaces if so and break out of both loops
+			for closFaceVidx := 0; closFaceVidx < len(closestFaceA); closFaceVidx++ {
+				if closestFaceA[closFaceVidx].Equals(&face[pConnFaceVidx]) {
+					connectedFaces = append(connectedFaces, faceIdx)
+					goToNextFace = true
+					break
+				}
+			}
+			if goToNextFace {
+				break
+			}
+		}
+	}
+
+
+	worldClosestFaceA := ch.WorldFace(closestFaceA, posA, quatA)
+	// DEBUGGING
+	//if n.debugging {
+	//	//log.Error("CONN-FACES: %v", len(connectedFaces))
+	//	for _, fidx := range connectedFaces {
+	//		wFace := n.WorldFace(facesA[fidx], bodyA)
+	//		ShowWorldFace(n.simulation.Scene(), wFace[:], &math32.Color{0.8, 0.8, 0.8})
+	//	}
+	//	//log.Error("worldClosestFaceA: %v", worldClosestFaceA)
+	//	//log.Error("worldClosestFaceB: %v", worldClosestFaceB)
+	//	ShowWorldFace(n.simulation.Scene(), worldClosestFaceA[:], &math32.Color{2, 0, 0})
+	//	ShowWorldFace(n.simulation.Scene(), worldClosestFaceB[:], &math32.Color{0, 2, 0})
+	//}
+
+	clippedFace := make([]math32.Vector3, len(worldClosestFaceB))
+	for i, v := range worldClosestFaceB {
+		clippedFace[i] = v
+	}
+
+	// TODO port simplified loop to cannon.js once done and verified
+	// https://github.com/schteppe/cannon.js/issues/378
+	// https://github.com/TheRohans/cannon.js/commit/62a1ce47a851b7045e68f7b120b9e4ecb0d91aab#r29106924
+	// Iterate over connected faces and clip the planes associated with their normals
+	for _, cfidx := range connectedFaces {
+		connFace := facesA[cfidx]
+		connFaceNormal := worldFaceNormalsA[cfidx]
+		// Choose a vertex in the connected face and use it to find the plane constant
+		worldFirstVertex := connFace[0].Clone().ApplyQuaternion(quatA).Add(posA)
+		planeDelta := - worldFirstVertex.Dot(&connFaceNormal)
+		clippedFace = ch.clipFaceAgainstPlane(clippedFace, connFaceNormal.Clone(), planeDelta)
+	}
+
+	// Plot clipped face
+	//if n.debugging {
+	//	log.Error("worldClosestFaceBClipped: %v", clippedFace)
+	//	ShowWorldFace(n.simulation.Scene(), clippedFace, &math32.Color{0, 0, 2})
+	//}
+
+	closestFaceAnormal := worldFaceNormalsA[closestFaceAidx]
+	worldFirstVertex := worldClosestFaceA[0].Clone()//.ApplyQuaternion(quatA).Add(&posA)
+	planeDelta := -worldFirstVertex.Dot(&closestFaceAnormal)
+
+	// For each vertex in the clipped face resolve its depth (relative to the closestFaceA) and create a contact
+	for _, vertex := range clippedFace {
+		depth := closestFaceAnormal.Dot(&vertex) + planeDelta
+		// Cap distance
+		if depth <= minDist {
+			depth = minDist
+		}
+		if depth <= maxDist {
+			if depth <= 0 {
+				contacts = append(contacts, collision.Contact{
+					Point: vertex,
+					Normal: closestFaceAnormal,
+					Depth: depth,
+				})
+			}
+		}
+
+	}
+
+	return contacts
+}
+
+
+// clipFaceAgainstPlane clips the specified face against the back of the specified plane.
+// This is used multiple times when finding the portion of a face of one convex hull that is inside another convex hull.
+// planeNormal and planeConstant satisfy the plane equation n*x = p where n is the planeNormal and p is the planeConstant (and x is a point on the plane).
+func (ch *ConvexHull) clipFaceAgainstPlane(face []math32.Vector3, planeNormal *math32.Vector3, planeConstant float32) []math32.Vector3 {
+
+	// inVertices are the verts making up the face of hullB
+
+	clippedFace := make([]math32.Vector3, 0)
+
+	// If not a face (if an edge or a vertex) - don't clip it
+	if len(face) < 2 {
+		return face
+	}
+
+	firstVertex := face[len(face)-1]
+	dotFirst := planeNormal.Dot(&firstVertex) + planeConstant
+
+	for vi := 0; vi < len(face); vi++ {
+		lastVertex := face[vi]
+		dotLast := planeNormal.Dot(&lastVertex) + planeConstant
+		if dotFirst < 0 { // Inside hull
+			if dotLast < 0 { // Start < 0, end < 0, so output lastVertex
+				clippedFace = append(clippedFace, lastVertex)
+			} else { // Start < 0, end >= 0, so output intersection
+				newv := firstVertex.Clone().Lerp(&lastVertex, dotFirst / (dotFirst - dotLast))
+				clippedFace = append(clippedFace, *newv)
+			}
+		} else { // Outside hull
+			if dotLast < 0 { // Start >= 0, end < 0 so output intersection and end
+				newv := firstVertex.Clone().Lerp(&lastVertex, dotFirst / (dotFirst - dotLast))
+				clippedFace = append(clippedFace, *newv)
+				clippedFace = append(clippedFace, lastVertex)
+			}
+		}
+		firstVertex = lastVertex
+		dotFirst = dotLast
+	}
+
+	return clippedFace
+}

+ 6 - 0
experimental/physics/shape/cylinder.go

@@ -0,0 +1,6 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package shape
+

+ 6 - 0
experimental/physics/shape/heightfield.go

@@ -0,0 +1,6 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package shape
+

+ 76 - 0
experimental/physics/shape/plane.go

@@ -0,0 +1,76 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package shape
+
+import "github.com/g3n/engine/math32"
+
+// Plane is an analytical collision Plane.
+// A plane, facing in the +Z direction. The plane has its surface at z=0 and everything below z=0 is assumed to be solid.
+type Plane struct {
+	normal math32.Vector3
+}
+
+// NewPlane creates and returns a pointer to a new analytical collision plane.
+func NewPlane() *Plane {
+
+	p := new(Plane)
+	p.normal = *math32.NewVector3(0,0,1) //*normal
+	return p
+}
+
+// SetRadius sets the radius of the analytical collision sphere.
+//func (p *Plane) SetNormal(normal *math32.Vector3) {
+//
+//	p.normal = *normal
+//}
+
+// Normal returns the normal of the analytical collision plane.
+func (p *Plane) Normal() math32.Vector3 {
+
+	return p.normal
+}
+
+// IShape =============================================================
+
+// BoundingBox computes and returns the bounding box of the analytical collision plane.
+func (p *Plane) BoundingBox() math32.Box3 {
+
+	//return math32.Box3{math32.Vector3{math32.Inf(-1), math32.Inf(-1), math32.Inf(-1)}, math32.Vector3{math32.Inf(1), 0, math32.Inf(1)}}
+	return math32.Box3{math32.Vector3{-1000, -1000, -1000}, math32.Vector3{1000, 1000, 0}}
+}
+
+// BoundingSphere computes and returns the bounding sphere of the analytical collision plane.
+func (p *Plane) BoundingSphere() math32.Sphere {
+
+	return *math32.NewSphere(math32.NewVec3(), math32.Inf(1))
+}
+
+// Area returns the surface area of the analytical collision plane.
+func (p *Plane) Area() float32 {
+
+	return math32.Inf(1)
+}
+
+// Volume returns the volume of the analytical collision sphere.
+func (p *Plane) Volume() float32 {
+
+	return math32.Inf(1)
+}
+
+// RotationalInertia computes and returns the rotational inertia of the analytical collision plane.
+func (p *Plane) RotationalInertia(mass float32) math32.Matrix3 {
+
+	return *math32.NewMatrix3().Zero()
+}
+
+// ProjectOntoAxis returns the minimum and maximum distances of the analytical collision plane projected onto the specified local axis.
+func (p *Plane) ProjectOntoAxis(localAxis *math32.Vector3) (float32, float32) {
+
+	if localAxis.Equals(&p.normal) {
+		return math32.Inf(-1), 0
+	} else {
+		return math32.Inf(-1), math32.Inf(1)
+	}
+}

+ 37 - 0
experimental/physics/shape/shape.go

@@ -0,0 +1,37 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package shape
+
+import "github.com/g3n/engine/math32"
+
+// IShape is the interface for all collision shapes.
+// Shapes in this package satisfy this interface and also geometry.Geometry.
+type IShape interface {
+	BoundingBox() math32.Box3
+	BoundingSphere() math32.Sphere
+	Area() float32
+	Volume() float32
+	RotationalInertia(mass float32) math32.Matrix3
+	ProjectOntoAxis(localAxis *math32.Vector3) (float32, float32)
+}
+
+// Shape is a collision shape.
+// It can be an analytical geometry such as a sphere, plane, etc.. or it can be defined by a polygonal Geometry.
+type Shape struct {
+
+	// TODO
+	//material
+
+	// Collision filtering
+	colFilterGroup int
+	colFilterMask  int
+}
+
+func (s *Shape) initialize() {
+
+	// Collision filtering
+	s.colFilterGroup = 1
+	s.colFilterMask = -1
+}

+ 75 - 0
experimental/physics/shape/sphere.go

@@ -0,0 +1,75 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package shape
+
+import "github.com/g3n/engine/math32"
+
+// Sphere is an analytical collision sphere.
+type Sphere struct {
+	radius float32
+}
+
+// NewSphere creates and returns a pointer to a new analytical collision sphere.
+func NewSphere(radius float32) *Sphere {
+
+	s := new(Sphere)
+	s.radius = radius
+	return s
+}
+
+// SetRadius sets the radius of the analytical collision sphere.
+func (s *Sphere) SetRadius(radius float32) {
+
+	s.radius = radius
+}
+
+// Radius returns the radius of the analytical collision sphere.
+func (s *Sphere) Radius() float32 {
+
+	return s.radius
+}
+
+// IShape =============================================================
+
+// BoundingBox computes and returns the bounding box of the analytical collision sphere.
+func (s *Sphere) BoundingBox() math32.Box3 {
+
+	return math32.Box3{math32.Vector3{-s.radius, -s.radius, -s.radius}, math32.Vector3{s.radius, s.radius, s.radius}}
+}
+
+// BoundingSphere computes and returns the bounding sphere of the analytical collision sphere.
+func (s *Sphere) BoundingSphere() math32.Sphere {
+
+	return *math32.NewSphere(math32.NewVec3(), s.radius)
+}
+
+// Area computes and returns the surface area of the analytical collision sphere.
+func (s *Sphere) Area() float32 {
+
+	return 4 * math32.Pi * s.radius * s.radius
+}
+
+// Volume computes and returns the volume of the analytical collision sphere.
+func (s *Sphere) Volume() float32 {
+
+	return (4/3) * math32.Pi * s.radius * s.radius * s.radius
+}
+
+// RotationalInertia computes and returns the rotational inertia of the analytical collision sphere.
+func (s *Sphere) RotationalInertia(mass float32) math32.Matrix3 {
+
+	v := (2/5) * mass * s.radius * s.radius
+	return *math32.NewMatrix3().Set(
+		v, 0, 0,
+		0, v, 0,
+		0, 0, v,
+	)
+}
+
+// ProjectOntoAxis computes and returns the minimum and maximum distances of the analytical collision sphere projected onto the specified local axis.
+func (s *Sphere) ProjectOntoAxis(localAxis *math32.Vector3) (float32, float32) {
+
+	return -s.radius, s.radius
+}

+ 583 - 0
experimental/physics/simulation.go

@@ -0,0 +1,583 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package physics
+
+import (
+	"github.com/g3n/engine/experimental/physics/equation"
+	"github.com/g3n/engine/experimental/physics/solver"
+	"github.com/g3n/engine/experimental/physics/constraint"
+	"github.com/g3n/engine/experimental/physics/collision"
+	"github.com/g3n/engine/math32"
+	"github.com/g3n/engine/experimental/physics/object"
+	"github.com/g3n/engine/core"
+	"github.com/g3n/engine/experimental/physics/shape"
+)
+
+// Simulation represents a physics simulation.
+type Simulation struct {
+	scene       *core.Node
+	forceFields []ForceField
+
+	// Bodies under simulation
+	bodies      []*object.Body  // Slice of bodies. May contain nil values.
+	nilBodies   []int           // Array keeps track of which indices of the 'bodies' array are nil
+
+	// Collision tracking
+	collisionMatrix     collision.Matrix // Boolean triangular matrix indicating which pairs of bodies are colliding
+	prevCollisionMatrix collision.Matrix // CollisionMatrix from the previous step.
+
+	allowSleep  bool                // Makes bodies go to sleep when they've been inactive
+	paused bool
+
+	quatNormalizeSkip int  // How often to normalize quaternions. Set to 0 for every step, 1 for every second etc..
+	                       // A larger value increases performance.
+	                       // If bodies tend to explode, set to a smaller value (zero to be sure nothing can go wrong).
+	quatNormalizeFast bool // Set to true to use fast quaternion normalization. It is often enough accurate to use. If bodies tend to explode, set to false.
+
+	time float32      // The wall-clock time since simulation start
+	stepnumber int    // Number of timesteps taken since start
+	default_dt float32 // Default and last timestep sizes
+	dt float32      // Currently / last used timestep. Is set to -1 if not available. This value is updated before each internal step, which means that it is "fresh" inside event callbacks.
+
+	accumulator float32 // Time accumulator for interpolation. See http://gafferongames.com/game-physics/fix-your-timestep/
+
+	broadphase  *Broadphase    // The broadphase algorithm to use, default is NaiveBroadphase
+	narrowphase *Narrowphase   // The narrowphase algorithm to use
+	solver      solver.ISolver // The solver algorithm to use, default is Gauss-Seidel
+
+	constraints       []constraint.IConstraint  // All constraints
+
+	materials         []*Material               // All added materials
+	cMaterials        []*ContactMaterial
+
+	//contactMaterialTable map[intPair]*ContactMaterial // Used to look up a ContactMaterial given two instances of Material.
+	//defaultMaterial *Material
+	defaultContactMaterial *ContactMaterial
+
+	doProfiling      bool
+}
+
+// NewSimulation creates and returns a pointer to a new physics simulation.
+func NewSimulation(scene *core.Node) *Simulation {
+
+	s := new(Simulation)
+	s.time = 0
+	s.dt = -1
+	s.default_dt = 1/60
+	s.scene = scene
+
+	// Set up broadphase, narrowphase, and solver
+	s.broadphase = NewBroadphase()
+	s.narrowphase = NewNarrowphase(s)
+	s.solver = solver.NewGaussSeidel()
+
+	s.collisionMatrix = collision.NewMatrix()
+	s.prevCollisionMatrix = collision.NewMatrix()
+
+	//s.contactMaterialTable = make(map[intPair]*ContactMaterial)
+	//s.defaultMaterial = NewMaterial
+	s.defaultContactMaterial = NewContactMaterial()
+
+	return s
+}
+
+func (s *Simulation) Scene() *core.Node {
+
+	return s.scene
+}
+
+// AddForceField adds a force field to the simulation.
+func (s *Simulation) AddForceField(ff ForceField) {
+
+	s.forceFields = append(s.forceFields, ff)
+}
+
+// RemoveForceField removes the specified force field from the simulation.
+// Returns true if found, false otherwise.
+func (s *Simulation) RemoveForceField(ff ForceField) bool {
+
+	for pos, current := range s.forceFields {
+		if current == ff {
+			copy(s.forceFields[pos:], s.forceFields[pos+1:])
+			s.forceFields[len(s.forceFields)-1] = nil
+			s.forceFields = s.forceFields[:len(s.forceFields)-1]
+			return true
+		}
+	}
+	return false
+}
+
+// AddBody adds a body to the simulation.
+func (s *Simulation) AddBody(body *object.Body, name string) {
+
+	// Do nothing if body is already present
+	for _, existingBody := range s.bodies {
+		if existingBody == body {
+			return // Do nothing
+		}
+	}
+
+	// If there are any open/nil spots in the body slice - add the body to one of them
+	// Else, just append to the end of the slice. Either way compute the body's index in the slice.
+	var idx int
+	nilLen := len(s.nilBodies)
+	if nilLen > 0 {
+		idx = s.nilBodies[nilLen]
+		s.nilBodies = s.nilBodies[0:nilLen-1]
+	} else {
+		idx = len(s.bodies)
+		s.bodies = append(s.bodies, body)
+
+		// Initialize collision matrix values up to the current index (and set the colliding flag to false)
+		s.collisionMatrix.Set(idx, idx, false)
+		s.prevCollisionMatrix.Set(idx, idx, false)
+	}
+
+	body.SetIndex(idx)
+	body.SetName(name)
+
+	// TODO dispatch add-body event
+	//s.Dispatch(AddBodyEvent, BodyEvent{body})
+}
+
+// RemoveBody removes the specified body from the simulation.
+// Returns true if found, false otherwise.
+func (s *Simulation) RemoveBody(body *object.Body) bool {
+
+	for idx, current := range s.bodies {
+		if current == body {
+			s.bodies[idx] = nil
+			// TODO dispatch remove-body event
+			//s.Dispatch(AddBodyEvent, BodyEvent{body})
+			return true
+		}
+	}
+	return false
+}
+
+// Clean removes nil bodies from the bodies array, recalculates the body indices and updates the collision matrix.
+//func (s *Simulation) Clean() {
+//
+//	// TODO Remove nil bodies from array
+//	//copy(s.bodies[pos:], s.bodies[pos+1:])
+//	//s.bodies[len(s.bodies)-1] = nil
+//	//s.bodies = s.bodies[:len(s.bodies)-1]
+//
+//	// Recompute body indices (each body has a .index int property)
+//	for i:=0; i<len(s.bodies); i++ {
+//		s.bodies[i].SetIndex(i)
+//	}
+//
+//	// TODO Update collision matrix
+//
+//}
+
+// Bodies returns the slice of bodies under simulation.
+// The slice may contain nil values!
+func (s *Simulation) Bodies() []*object.Body{
+
+	return s.bodies
+}
+
+func (s *Simulation) Step(frameDelta float32) {
+
+	s.StepPlus(frameDelta, 0, 10)
+}
+
+
+// Step steps the simulation.
+// maxSubSteps should be 10 by default
+func (s *Simulation) StepPlus(frameDelta float32, timeSinceLastCalled float32, maxSubSteps int) {
+
+	if s.paused {
+		return
+	}
+
+	dt := frameDelta//float32(frameDelta.Seconds())
+
+    //if timeSinceLastCalled == 0 { // Fixed, simple stepping
+
+        s.internalStep(dt)
+
+        // Increment time
+        //s.time += dt
+
+    //} else {
+	//
+    //    s.accumulator += timeSinceLastCalled
+    //    var substeps = 0
+    //    for s.accumulator >= dt && substeps < maxSubSteps {
+    //        // Do fixed steps to catch up
+    //        s.internalStep(dt)
+    //        s.accumulator -= dt
+    //        substeps++
+    //    }
+	//
+    //    var t = (s.accumulator % dt) / dt
+    //    for j := 0; j < len(s.bodies); j++ {
+    //        var b = s.bodies[j]
+    //        b.previousPosition.lerp(b.position, t, b.interpolatedPosition)
+    //        b.previousQuaternion.slerp(b.quaternion, t, b.interpolatedQuaternion)
+    //        b.previousQuaternion.normalize()
+    //    }
+    //    s.time += timeSinceLastCalled
+    //}
+
+}
+
+// SetPaused sets the paused state of the simulation.
+func (s *Simulation) SetPaused(state bool) {
+
+	s.paused = state
+}
+
+// Paused returns the paused state of the simulation.
+func (s *Simulation) Paused() bool {
+
+	return s.paused
+}
+
+// ClearForces sets all body forces in the world to zero.
+func (s *Simulation) ClearForces() {
+
+	for i:=0; i < len(s.bodies); i++ {
+		s.bodies[i].ClearForces()
+	}
+}
+
+// AddConstraint adds a constraint to the simulation.
+func (s *Simulation) AddConstraint(c constraint.IConstraint) {
+
+	s.constraints = append(s.constraints, c)
+}
+
+func (s *Simulation) RemoveConstraint(c constraint.IConstraint) {
+
+	// TODO
+}
+
+func (s *Simulation) AddMaterial(mat *Material) {
+
+	s.materials = append(s.materials, mat)
+}
+
+func (s *Simulation) RemoveMaterial(mat *Material) {
+
+	// TODO
+}
+
+// Adds a contact material to the simulation
+func (s *Simulation) AddContactMaterial(cmat *ContactMaterial) {
+
+	s.cMaterials = append(s.cMaterials, cmat)
+
+	// TODO add contactMaterial materials to contactMaterialTable
+	// s.contactMaterialTable.set(cmat.materials[0].id, cmat.materials[1].id, cmat)
+}
+
+// GetContactMaterial returns the contact material between the specified bodies.
+func (s *Simulation) GetContactMaterial(bodyA, bodyB *object.Body) *ContactMaterial {
+
+	var cm *ContactMaterial
+	// TODO
+	//if bodyA.material != nil && bodyB.material != nil {
+	//	cm = s.contactMaterialTable.get(bodyA.material.id, bodyB.material.id)
+	//	if cm == nil {
+	//		cm = s.defaultContactMaterial
+	//	}
+	//} else {
+	cm = s.defaultContactMaterial
+	//}
+	return cm
+}
+
+
+// Events =====================
+
+type CollideEvent struct {
+	body      *object.Body
+	contactEq *equation.Contact
+}
+
+// TODO AddBodyEvent, RemoveBodyEvent
+type ContactEvent struct {
+	bodyA *object.Body
+	bodyB *object.Body
+}
+
+const (
+	BeginContactEvent = "physics.BeginContactEvent"
+	EndContactEvent   = "physics.EndContactEvent"
+	CollisionEv       = "physics.Collision"
+)
+
+// ===========================
+
+
+// ApplySolution applies the specified solution to the bodies under simulation.
+// The solution is a set of linear and angular velocity deltas for each body.
+// This method alters the solution arrays.
+func (s *Simulation) ApplySolution(sol *solver.Solution) {
+
+	// Add results to velocity and angular velocity of bodies
+	for i := 0; i < len(s.bodies); i++ {
+		s.bodies[i].ApplyVelocityDeltas(&sol.VelocityDeltas[i], &sol.AngularVelocityDeltas[i])
+	}
+}
+
+// Store old collision state info
+func (s *Simulation) collisionMatrixTick() {
+
+	s.prevCollisionMatrix = s.collisionMatrix
+	s.collisionMatrix = collision.NewMatrix()
+
+	lb := len(s.bodies)
+	s.collisionMatrix.Set(lb, lb, false)
+
+	// TODO verify that the matrices are indeed different
+	//if s.prevCollisionMatrix == s.collisionMatrix {
+	//	log.Error("SAME")
+	//}
+
+	// TODO
+	//s.bodyOverlapKeeper.tick()
+	//s.shapeOverlapKeeper.tick()
+}
+
+func (s *Simulation) uniqueBodiesFromPairs(pairs []CollisionPair) []*object.Body {
+
+	bodiesUndergoingNarrowphase := make([]*object.Body, 0) // array of indices of s.bodies
+	for _, pair := range pairs {
+		alreadyAddedA := false
+		alreadyAddedB := false
+		for _, body := range bodiesUndergoingNarrowphase {
+			if pair.BodyA == body {
+				alreadyAddedA = true
+				if alreadyAddedB {
+					break
+				}
+			}
+			if pair.BodyB == body {
+				alreadyAddedB = true
+				if alreadyAddedA {
+					break
+				}
+			}
+		}
+		if !alreadyAddedA {
+			bodiesUndergoingNarrowphase = append(bodiesUndergoingNarrowphase, pair.BodyA)
+		}
+		if !alreadyAddedB {
+			bodiesUndergoingNarrowphase = append(bodiesUndergoingNarrowphase, pair.BodyB)
+		}
+	}
+
+	return bodiesUndergoingNarrowphase
+}
+
+// TODO read https://gafferongames.com/post/fix_your_timestep/
+func (s *Simulation) internalStep(dt float32) {
+
+	s.dt = dt
+
+	// Apply force fields (only to dynamic bodies
+	for _, b := range s.bodies {
+		if b.BodyType() == object.Dynamic {
+			for _, ff := range s.forceFields {
+				pos := b.Position()
+				force := ff.ForceAt(&pos)
+				b.ApplyForceField(&force)
+			}
+		}
+	}
+
+    // Find pairs of bodies that are potentially colliding (broadphase)
+	pairs := s.broadphase.FindCollisionPairs(s.bodies)
+
+	// Remove some pairs before proceeding to narrowphase based on constraints' colConn property
+	// which specifies if constrained bodies should collide with one another
+    s.prunePairs(pairs) // TODO review/implement
+
+	// Precompute world normals/edges only for convex bodies that will undergo narrowphase
+	for _, body := range s.uniqueBodiesFromPairs(pairs) {
+		if ch, ok := body.Shape().(*shape.ConvexHull); ok{
+			ch.ComputeWorldFaceNormalsAndUniqueEdges(body.Quaternion())
+		}
+	}
+
+	// Switch collision matrices (to keep track of which collisions started/ended)
+    s.collisionMatrixTick()
+
+    // Resolve collisions and generate contact and friction equations
+	contactEqs, frictionEqs := s.narrowphase.GenerateEquations(pairs)
+
+	// Add all friction equations to solver
+	for i := 0; i < len(frictionEqs); i++ {
+		s.solver.AddEquation(frictionEqs[i])
+	}
+
+	// Add all contact equations to solver (and update some things)
+	for i := 0; i < len(contactEqs); i++ {
+		s.solver.AddEquation(contactEqs[i])
+		s.updateSleepAndCollisionMatrix(contactEqs[i])
+	}
+
+    // Add all equations from user-added constraints to the solver
+	userAddedEquations := 0
+    for i := 0; i < len(s.constraints); i++ {
+		s.constraints[i].Update()
+        eqs := s.constraints[i].Equations()
+        for j := 0; j < len(eqs); j++ {
+			userAddedEquations++
+            s.solver.AddEquation(eqs[j])
+        }
+    }
+
+	// Emit events TODO implement
+	s.emitContactEvents()
+	// Wake up bodies
+	// TODO why not wake bodies up inside s.updateSleepAndCollisionMatrix when setting the WakeUpAfterNarrowphase flag?
+	// Maybe there we are only looking at bodies that belong to current contact equations...
+	// and need to wake up all marked bodies
+	for i := 0; i < len(s.bodies); i++ {
+		bi := s.bodies[i]
+		if bi != nil && bi.WakeUpAfterNarrowphase() {
+			bi.WakeUp()
+			bi.SetWakeUpAfterNarrowphase(false)
+		}
+	}
+
+	// If we have any equations to solve
+	if len(frictionEqs) + len(contactEqs) + userAddedEquations > 0 {
+		// Update effective mass for all bodies
+		for i := 0; i < len(s.bodies); i++ {
+			s.bodies[i].UpdateEffectiveMassProperties()
+		}
+		// Solve the constrained system
+		solution := s.solver.Solve(dt, len(s.bodies))
+		// Apply linear and angular velocity deltas to bodies
+		s.ApplySolution(solution)
+		// Clear all equations added to the solver
+		s.solver.ClearEquations()
+	}
+
+    // Apply damping (only to dynamic bodies)
+    // See http://code.google.com/p/bullet/issues/detail?id=74 for details
+    for _, body := range s.bodies {
+        if body != nil && body.BodyType() == object.Dynamic {
+			body.ApplyDamping(dt)
+        }
+    }
+
+    // TODO s.Dispatch(World_step_preStepEvent)
+
+	// Integrate the forces into velocities and the velocities into position deltas for all bodies
+    // TODO future: quatNormalize := s.stepnumber % (s.quatNormalizeSkip + 1) == 0
+    for _, body := range s.bodies {
+		if body != nil {
+			body.Integrate(dt, true, s.quatNormalizeFast)
+		}
+    }
+    s.ClearForces()
+
+    // TODO s.broadphase.dirty = true ?
+
+    // Update world time
+    s.time += dt
+    s.stepnumber += 1
+
+    // TODO s.Dispatch(World_step_postStepEvent)
+
+    // Sleeping update
+    if s.allowSleep {
+        for i := 0; i < len(s.bodies); i++ {
+            s.bodies[i].SleepTick(s.time)
+        }
+    }
+
+}
+
+// TODO - REVIEW THIS
+func (s *Simulation) prunePairs(pairs []CollisionPair) []CollisionPair {
+
+	// TODO There is probably a bug here when the same body can have multiple constraints and appear in multiple pairs
+
+	//// Remove constrained pairs with collideConnected == false
+	//pairIdxsToRemove := []int
+	//for i := 0; i < len(s.constraints); i++ {
+	//	c := s.constraints[i]
+	//	cBodyA := s.bodies[c.BodyA().Index()]
+	//	cBodyB := s.bodies[c.BodyB().Index()]
+	//	if !c.CollideConnected() {
+	//		for i := range pairs {
+	//			if (pairs[i].BodyA == cBodyA && pairs[i].BodyB == cBodyB) ||
+	//				(pairs[i].BodyA == cBodyB && pairs[i].BodyB == cBodyA) {
+	//				pairIdxsToRemove = append(pairIdxsToRemove, i)
+	//
+	//			}
+	//		}
+	//	}
+	//}
+	//
+	//// Remove pairs
+	////var prunedPairs []CollisionPair
+	//for i := range pairs {
+	//	for _, idx := range pairIdxsToRemove {
+	//		copy(pairs[i:], pairs[i+1:])
+	//		//pairs[len(pairs)-1] = nil
+	//		pairs = pairs[:len(pairs)-1]
+	//	}
+	//}
+
+	return pairs
+}
+
+// generateContacts
+func (s *Simulation) updateSleepAndCollisionMatrix(contactEq *equation.Contact) {
+
+	// Get current collision indices
+	bodyA := s.bodies[contactEq.BodyA().Index()]
+	bodyB := s.bodies[contactEq.BodyB().Index()]
+
+	// TODO future: update equations with physical material properties
+
+	if bodyA.AllowSleep() && bodyA.BodyType() == object.Dynamic && bodyA.SleepState() == object.Sleeping && bodyB.SleepState() == object.Awake && bodyB.BodyType() != object.Static {
+		velocityB := bodyB.Velocity()
+		angularVelocityB := bodyB.AngularVelocity()
+		speedSquaredB := velocityB.LengthSq() + angularVelocityB.LengthSq()
+		speedLimitSquaredB := math32.Pow(bodyB.SleepSpeedLimit(), 2)
+		if speedSquaredB >= speedLimitSquaredB*2 {
+			bodyA.SetWakeUpAfterNarrowphase(true)
+		}
+	}
+
+	if bodyB.AllowSleep() && bodyB.BodyType() == object.Dynamic && bodyB.SleepState() == object.Sleeping && bodyA.SleepState() == object.Awake && bodyA.BodyType() != object.Static {
+		velocityA := bodyA.Velocity()
+		angularVelocityA := bodyA.AngularVelocity()
+		speedSquaredA := velocityA.LengthSq() + angularVelocityA.LengthSq()
+		speedLimitSquaredA := math32.Pow(bodyA.SleepSpeedLimit(), 2)
+		if speedSquaredA >= speedLimitSquaredA*2 {
+			bodyB.SetWakeUpAfterNarrowphase(true)
+		}
+	}
+
+	// Now we know that i and j are in contact. Set collision matrix state
+	s.collisionMatrix.Set(bodyA.Index(), bodyB.Index(), true)
+
+	if s.prevCollisionMatrix.Get(bodyA.Index(), bodyB.Index()) == false {
+		// First contact!
+		bodyA.Dispatch(CollisionEv, &CollideEvent{bodyB, contactEq})
+		bodyB.Dispatch(CollisionEv, &CollideEvent{bodyA, contactEq})
+	}
+
+	// TODO this is only for events
+	//s.bodyOverlapKeeper.set(bodyA.id, bodyB.id)
+	//s.shapeOverlapKeeper.set(si.id, sj.id)
+
+}
+
+func (s *Simulation) emitContactEvents() {
+	//TODO
+}

+ 139 - 0
experimental/physics/solver/gs.go

@@ -0,0 +1,139 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+// Package physics implements a basic physics engine.
+package solver
+
+import (
+	"github.com/g3n/engine/math32"
+)
+
+// GaussSeidel equation solver.
+// See https://en.wikipedia.org/wiki/Gauss-Seidel_method.
+// The number of solver iterations determines the quality of the solution.
+// More iterations yield a better solution but require more computation.
+type GaussSeidel struct {
+	Solver
+	maxIter   int     // Number of solver iterations.
+	tolerance float32 // When the error is less than the tolerance, the system is assumed to be converged.
+
+	solveInvCs  []float32
+	solveBs     []float32
+	solveLambda []float32
+}
+
+// NewGaussSeidel creates and returns a pointer to a new GaussSeidel constraint equation solver.
+func NewGaussSeidel() *GaussSeidel {
+
+	gs := new(GaussSeidel)
+	gs.maxIter = 20
+	gs.tolerance = 1e-7
+
+	gs.VelocityDeltas = make([]math32.Vector3, 0)
+	gs.AngularVelocityDeltas = make([]math32.Vector3, 0)
+
+	gs.solveInvCs = make([]float32, 0)
+	gs.solveBs = make([]float32, 0)
+	gs.solveLambda = make([]float32, 0)
+
+	return gs
+}
+
+func (gs *GaussSeidel) Reset(numBodies int) {
+
+	// Reset solution
+	gs.VelocityDeltas = make([]math32.Vector3, numBodies)
+	gs.AngularVelocityDeltas = make([]math32.Vector3, numBodies)
+	gs.Iterations = 0
+
+	// Reset internal arrays
+	gs.solveInvCs = gs.solveInvCs[0:0]
+	gs.solveBs = gs.solveBs[0:0]
+	gs.solveLambda = gs.solveLambda[0:0]
+}
+
+// Solve
+func (gs *GaussSeidel) Solve(dt float32, nBodies int) *Solution {
+
+	gs.Reset(nBodies)
+
+	iter := 0
+	nEquations := len(gs.equations)
+	h := dt
+
+	// Things that do not change during iteration can be computed once
+	for i := 0; i < nEquations; i++ {
+		eq := gs.equations[i]
+		gs.solveInvCs = append(gs.solveInvCs, 1.0 / eq.ComputeC())
+		gs.solveBs = append(gs.solveBs, eq.ComputeB(h))
+		gs.solveLambda = append(gs.solveLambda, 0.0)
+	}
+
+	if nEquations > 0 {
+		tolSquared := gs.tolerance*gs.tolerance
+
+		// Iterate over equations
+		for iter = 0; iter < gs.maxIter; iter++ {
+
+			// Accumulate the total error for each iteration.
+			deltaLambdaTot := float32(0)
+
+			for j := 0; j < nEquations; j++ {
+				eq := gs.equations[j]
+
+				// Compute iteration
+				lambdaJ := gs.solveLambda[j]
+
+				idxBodyA := eq.BodyA().Index()
+				idxBodyB := eq.BodyB().Index()
+
+				vA := gs.VelocityDeltas[idxBodyA]
+				vB := gs.VelocityDeltas[idxBodyB]
+				wA := gs.AngularVelocityDeltas[idxBodyA]
+				wB := gs.AngularVelocityDeltas[idxBodyB]
+				jeA := eq.JeA()
+				jeB := eq.JeB()
+				GWlambda := jeA.MultiplyVectors(&vA, &wA) + jeB.MultiplyVectors(&vB, &wB)
+
+				deltaLambda := gs.solveInvCs[j] * ( gs.solveBs[j]  - GWlambda - eq.Eps() *lambdaJ)
+
+				// Clamp if we are outside the min/max interval
+				if lambdaJ + deltaLambda < eq.MinForce() {
+					deltaLambda = eq.MinForce() - lambdaJ
+				} else if lambdaJ + deltaLambda > eq.MaxForce() {
+					deltaLambda = eq.MaxForce() - lambdaJ
+				}
+				gs.solveLambda[j] += deltaLambda
+				deltaLambdaTot += math32.Abs(deltaLambda)
+
+				// Add to velocity deltas
+				spatA := jeA.Spatial()
+				spatB := jeB.Spatial()
+				gs.VelocityDeltas[idxBodyA].Add(spatA.MultiplyScalar(eq.BodyA().InvMassEff() * deltaLambda))
+				gs.VelocityDeltas[idxBodyB].Add(spatB.MultiplyScalar(eq.BodyB().InvMassEff() * deltaLambda))
+
+				// Add to angular velocity deltas
+				rotA := jeA.Rotational()
+				rotB := jeB.Rotational()
+				gs.AngularVelocityDeltas[idxBodyA].Add(rotA.ApplyMatrix3(eq.BodyA().InvRotInertiaWorldEff()).MultiplyScalar(deltaLambda))
+				gs.AngularVelocityDeltas[idxBodyB].Add(rotB.ApplyMatrix3(eq.BodyB().InvRotInertiaWorldEff()).MultiplyScalar(deltaLambda))
+			}
+
+			// If the total error is small enough - stop iterating
+			if deltaLambdaTot*deltaLambdaTot < tolSquared {
+				break
+			}
+		}
+
+		// Set the .multiplier property of each equation
+		for i := range gs.equations {
+			gs.equations[i].SetMultiplier(gs.solveLambda[i] / h)
+		}
+		iter += 1
+	}
+
+	gs.Iterations = iter
+
+	return &gs.Solution
+}

+ 59 - 0
experimental/physics/solver/solver.go

@@ -0,0 +1,59 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+// Package physics implements a basic physics engine.
+package solver
+
+import (
+	"github.com/g3n/engine/experimental/physics/equation"
+	"github.com/g3n/engine/math32"
+)
+
+// ISolver is the interface type for all constraint solvers.
+type ISolver interface {
+	Solve(dt float32, nBodies int) *Solution // Solve should return the number of iterations performed
+	AddEquation(eq equation.IEquation)
+	RemoveEquation(eq equation.IEquation) bool
+	ClearEquations()
+}
+
+// Solution represents a solver solution
+type Solution struct {
+	VelocityDeltas        []math32.Vector3
+	AngularVelocityDeltas []math32.Vector3
+	Iterations            int
+}
+
+// Constraint equation solver base class.
+type Solver struct {
+	Solution
+	equations []equation.IEquation // All equations to be solved
+}
+
+// AddEquation adds an equation to the solver.
+func (s *Solver) AddEquation(eq equation.IEquation) {
+
+	s.equations = append(s.equations, eq)
+}
+
+// RemoveEquation removes the specified equation from the solver.
+// Returns true if found, false otherwise.
+func (s *Solver) RemoveEquation(eq equation.IEquation) bool {
+
+	for pos, current := range s.equations {
+		if current == eq {
+			copy(s.equations[pos:], s.equations[pos+1:])
+			s.equations[len(s.equations)-1] = nil
+			s.equations = s.equations[:len(s.equations)-1]
+			return true
+		}
+	}
+	return false
+}
+
+// ClearEquations removes all equations from the solver.
+func (s *Solver) ClearEquations() {
+
+	s.equations = s.equations[0:0]
+}

+ 18 - 4
geometry/box.go

@@ -135,12 +135,26 @@ func NewSegmentedBox(width, height, length float32, widthSegments, heightSegment
 	buildPlane("x", "y", -1, -1, box.Width, box.Height, -lHalf, 5) // nz
 
 	box.SetIndices(indices)
-	box.AddVBO(gls.NewVBO().AddAttrib("VertexPosition", 3).SetBuffer(positions))
-	box.AddVBO(gls.NewVBO().AddAttrib("VertexNormal", 3).SetBuffer(normals))
-	box.AddVBO(gls.NewVBO().AddAttrib("VertexTexcoord", 2).SetBuffer(uvs))
+	box.AddVBO(gls.NewVBO(positions).AddAttrib(gls.VertexPosition, 3))
+	box.AddVBO(gls.NewVBO(normals).AddAttrib(gls.VertexNormal, 3))
+	box.AddVBO(gls.NewVBO(uvs).AddAttrib(gls.VertexTexcoord, 2))
 
-	box.boundingBox = math32.Box3{math32.Vector3{-wHalf, -hHalf, -lHalf}, math32.Vector3{wHalf, hHalf, lHalf}}
+	// Update bounding box
+	box.boundingBox.Min = math32.Vector3{-wHalf, -hHalf, -lHalf}
+	box.boundingBox.Max = math32.Vector3{wHalf, hHalf, lHalf}
 	box.boundingBoxValid = true
 
+	// Update bounding sphere
+	box.boundingSphere.Radius = math32.Sqrt(math32.Pow(width/2,2) + math32.Pow(height/2,2) + math32.Pow(length/2,2))
+	box.boundingSphereValid = true
+
+	// Update area
+	box.area = 2*width + 2*height + 2*length
+	box.areaValid = true
+
+	// Update volume
+	box.volume = width * height * length
+	box.volumeValid = true
+
 	return box
 }

+ 6 - 4
geometry/circle.go

@@ -82,11 +82,13 @@ func NewCircleSector(radius float64, segments int, thetaStart, thetaLength float
 	}
 
 	circ.SetIndices(indices)
-	circ.AddVBO(gls.NewVBO().AddAttrib("VertexPosition", 3).SetBuffer(positions))
-	circ.AddVBO(gls.NewVBO().AddAttrib("VertexNormal", 3).SetBuffer(normals))
-	circ.AddVBO(gls.NewVBO().AddAttrib("VertexTexcoord", 2).SetBuffer(uvs))
+	circ.AddVBO(gls.NewVBO(positions).AddAttrib(gls.VertexPosition, 3))
+	circ.AddVBO(gls.NewVBO(normals).AddAttrib(gls.VertexNormal, 3))
+	circ.AddVBO(gls.NewVBO(uvs).AddAttrib(gls.VertexTexcoord, 2))
 
-	//circ.BoundingSphere = math32.NewSphere(math32.NewVector3(0,0,0), float32(radius))
+	// Update volume
+	circ.volume = 0
+	circ.volumeValid = true
 
 	return circ
 }

+ 107 - 107
geometry/cylinder.go

@@ -44,10 +44,10 @@ func NewCylinder(radiusTop, radiusBottom, height float64,
 
 	heightHalf := height / 2
 	vertices := [][]int{}
-	uvs := [][]math32.Vector2{}
+	uvsOrig := [][]math32.Vector2{}
 
 	// Create buffer for vertex positions
-	Positions := math32.NewArrayF32(0, 0)
+	positions := math32.NewArrayF32(0, 0)
 
 	for y := 0; y <= heightSegments; y++ {
 		var verticesRow = []int{}
@@ -60,30 +60,30 @@ func NewCylinder(radiusTop, radiusBottom, height float64,
 			vertex.X = float32(radius * math.Sin(u*thetaLength+thetaStart))
 			vertex.Y = float32(-v*height + heightHalf)
 			vertex.Z = float32(radius * math.Cos(u*thetaLength+thetaStart))
-			Positions.AppendVector3(&vertex)
-			verticesRow = append(verticesRow, Positions.Size()/3-1)
+			positions.AppendVector3(&vertex)
+			verticesRow = append(verticesRow, positions.Size()/3-1)
 			uvsRow = append(uvsRow, math32.Vector2{float32(u), 1.0 - float32(v)})
 		}
 		vertices = append(vertices, verticesRow)
-		uvs = append(uvs, uvsRow)
+		uvsOrig = append(uvsOrig, uvsRow)
 	}
 
 	tanTheta := (radiusBottom - radiusTop) / height
 	var na, nb math32.Vector3
 
 	// Create preallocated buffers for normals and uvs and buffer for indices
-	npos := Positions.Size()
-	Normals := math32.NewArrayF32(npos, npos)
-	Uvs := math32.NewArrayF32(2*npos/3, 2*npos/3)
-	Indices := math32.NewArrayU32(0, 0)
+	npos := positions.Size()
+	normals := math32.NewArrayF32(npos, npos)
+	uvs := math32.NewArrayF32(2*npos/3, 2*npos/3)
+	indices := math32.NewArrayU32(0, 0)
 
 	for x := 0; x < radialSegments; x++ {
 		if radiusTop != 0 {
-			Positions.GetVector3(3*vertices[0][x], &na)
-			Positions.GetVector3(3*vertices[0][x+1], &nb)
+			positions.GetVector3(3*vertices[0][x], &na)
+			positions.GetVector3(3*vertices[0][x+1], &nb)
 		} else {
-			Positions.GetVector3(3*vertices[1][x], &na)
-			Positions.GetVector3(3*vertices[1][x+1], &nb)
+			positions.GetVector3(3*vertices[1][x], &na)
+			positions.GetVector3(3*vertices[1][x+1], &nb)
 		}
 
 		na.SetY(float32(math.Sqrt(float64(na.X*na.X+na.Z*na.Z)) * tanTheta)).Normalize()
@@ -100,162 +100,162 @@ func NewCylinder(radiusTop, radiusBottom, height float64,
 			n3 := nb
 			n4 := nb
 
-			uv1 := uvs[y][x]
-			uv2 := uvs[y+1][x]
-			uv3 := uvs[y+1][x+1]
-			uv4 := uvs[y][x+1]
-
-			Indices.Append(uint32(v1), uint32(v2), uint32(v4))
-			Normals.SetVector3(3*v1, &n1)
-			Normals.SetVector3(3*v2, &n2)
-			Normals.SetVector3(3*v4, &n4)
-
-			Indices.Append(uint32(v2), uint32(v3), uint32(v4))
-			Normals.SetVector3(3*v2, &n2)
-			Normals.SetVector3(3*v3, &n3)
-			Normals.SetVector3(3*v4, &n4)
-
-			Uvs.SetVector2(2*v1, &uv1)
-			Uvs.SetVector2(2*v2, &uv2)
-			Uvs.SetVector2(2*v3, &uv3)
-			Uvs.SetVector2(2*v4, &uv4)
+			uv1 := uvsOrig[y][x]
+			uv2 := uvsOrig[y+1][x]
+			uv3 := uvsOrig[y+1][x+1]
+			uv4 := uvsOrig[y][x+1]
+
+			indices.Append(uint32(v1), uint32(v2), uint32(v4))
+			normals.SetVector3(3*v1, &n1)
+			normals.SetVector3(3*v2, &n2)
+			normals.SetVector3(3*v4, &n4)
+
+			indices.Append(uint32(v2), uint32(v3), uint32(v4))
+			normals.SetVector3(3*v2, &n2)
+			normals.SetVector3(3*v3, &n3)
+			normals.SetVector3(3*v4, &n4)
+
+			uvs.SetVector2(2*v1, &uv1)
+			uvs.SetVector2(2*v2, &uv2)
+			uvs.SetVector2(2*v3, &uv3)
+			uvs.SetVector2(2*v4, &uv4)
 		}
 	}
 	// First group is the body of the cylinder
 	// without the caps
-	c.AddGroup(0, Indices.Size(), 0)
-	nextGroup := Indices.Size()
+	c.AddGroup(0, indices.Size(), 0)
+	nextGroup := indices.Size()
 
 	// Top cap
 	if top && radiusTop > 0 {
 
-		// Array of vertex indices to build used to build the faces.
-		indices := []uint32{}
-		nextidx := Positions.Size() / 3
+		// Array of vertex indicesOrig to build used to build the faces.
+		indicesOrig := []uint32{}
+		nextidx := positions.Size() / 3
 
-		// Appends top segments vertices and builds array of its indices
+		// Appends top segments vertices and builds array of its indicesOrig
 		var uv1, uv2, uv3 math32.Vector2
 		for x := 0; x < radialSegments; x++ {
-			uv1 = uvs[0][x]
-			uv2 = uvs[0][x+1]
+			uv1 = uvsOrig[0][x]
+			uv2 = uvsOrig[0][x+1]
 			uv3 = math32.Vector2{uv2.X, 0}
 			// Appends CENTER with its own UV.
-			Positions.Append(0, float32(heightHalf), 0)
-			Normals.Append(0, 1, 0)
-			Uvs.AppendVector2(&uv3)
-			indices = append(indices, uint32(nextidx))
+			positions.Append(0, float32(heightHalf), 0)
+			normals.Append(0, 1, 0)
+			uvs.AppendVector2(&uv3)
+			indicesOrig = append(indicesOrig, uint32(nextidx))
 			nextidx++
 			// Appends vertex
 			v := math32.Vector3{}
 			vi := vertices[0][x]
-			Positions.GetVector3(3*vi, &v)
-			Positions.AppendVector3(&v)
-			Normals.Append(0, 1, 0)
-			Uvs.AppendVector2(&uv1)
-			indices = append(indices, uint32(nextidx))
+			positions.GetVector3(3*vi, &v)
+			positions.AppendVector3(&v)
+			normals.Append(0, 1, 0)
+			uvs.AppendVector2(&uv1)
+			indicesOrig = append(indicesOrig, uint32(nextidx))
 			nextidx++
 		}
 		// Appends copy of first vertex (center)
 		var vertex, normal math32.Vector3
 		var uv math32.Vector2
-		Positions.GetVector3(3*int(indices[0]), &vertex)
-		Normals.GetVector3(3*int(indices[0]), &normal)
-		Uvs.GetVector2(2*int(indices[0]), &uv)
-		Positions.AppendVector3(&vertex)
-		Normals.AppendVector3(&normal)
-		Uvs.AppendVector2(&uv)
-		indices = append(indices, uint32(nextidx))
+		positions.GetVector3(3*int(indicesOrig[0]), &vertex)
+		normals.GetVector3(3*int(indicesOrig[0]), &normal)
+		uvs.GetVector2(2*int(indicesOrig[0]), &uv)
+		positions.AppendVector3(&vertex)
+		normals.AppendVector3(&normal)
+		uvs.AppendVector2(&uv)
+		indicesOrig = append(indicesOrig, uint32(nextidx))
 		nextidx++
 
 		// Appends copy of second vertex (v1) USING LAST UV2
-		Positions.GetVector3(3*int(indices[1]), &vertex)
-		Normals.GetVector3(3*int(indices[1]), &normal)
-		Positions.AppendVector3(&vertex)
-		Normals.AppendVector3(&normal)
-		Uvs.AppendVector2(&uv2)
-		indices = append(indices, uint32(nextidx))
+		positions.GetVector3(3*int(indicesOrig[1]), &vertex)
+		normals.GetVector3(3*int(indicesOrig[1]), &normal)
+		positions.AppendVector3(&vertex)
+		normals.AppendVector3(&normal)
+		uvs.AppendVector2(&uv2)
+		indicesOrig = append(indicesOrig, uint32(nextidx))
 		nextidx++
 
-		// Append faces indices
+		// Append faces indicesOrig
 		for x := 0; x < radialSegments; x++ {
 			pos := 2 * x
-			i1 := indices[pos]
-			i2 := indices[pos+1]
-			i3 := indices[pos+3]
-			Indices.Append(uint32(i1), uint32(i2), uint32(i3))
+			i1 := indicesOrig[pos]
+			i2 := indicesOrig[pos+1]
+			i3 := indicesOrig[pos+3]
+			indices.Append(uint32(i1), uint32(i2), uint32(i3))
 		}
 		// Second group is optional top cap of the cylinder
-		c.AddGroup(nextGroup, Indices.Size()-nextGroup, 1)
-		nextGroup = Indices.Size()
+		c.AddGroup(nextGroup, indices.Size()-nextGroup, 1)
+		nextGroup = indices.Size()
 	}
 
 	// Bottom cap
 	if bottom && radiusBottom > 0 {
 
-		// Array of vertex indices to build used to build the faces.
-		indices := []uint32{}
-		nextidx := Positions.Size() / 3
+		// Array of vertex indicesOrig to build used to build the faces.
+		indicesOrig := []uint32{}
+		nextidx := positions.Size() / 3
 
-		// Appends top segments vertices and builds array of its indices
+		// Appends top segments vertices and builds array of its indicesOrig
 		var uv1, uv2, uv3 math32.Vector2
 		for x := 0; x < radialSegments; x++ {
-			uv1 = uvs[heightSegments][x]
-			uv2 = uvs[heightSegments][x+1]
+			uv1 = uvsOrig[heightSegments][x]
+			uv2 = uvsOrig[heightSegments][x+1]
 			uv3 = math32.Vector2{uv2.X, 1}
 			// Appends CENTER with its own UV.
-			Positions.Append(0, float32(-heightHalf), 0)
-			Normals.Append(0, -1, 0)
-			Uvs.AppendVector2(&uv3)
-			indices = append(indices, uint32(nextidx))
+			positions.Append(0, float32(-heightHalf), 0)
+			normals.Append(0, -1, 0)
+			uvs.AppendVector2(&uv3)
+			indicesOrig = append(indicesOrig, uint32(nextidx))
 			nextidx++
 			// Appends vertex
 			v := math32.Vector3{}
 			vi := vertices[heightSegments][x]
-			Positions.GetVector3(3*vi, &v)
-			Positions.AppendVector3(&v)
-			Normals.Append(0, -1, 0)
-			Uvs.AppendVector2(&uv1)
-			indices = append(indices, uint32(nextidx))
+			positions.GetVector3(3*vi, &v)
+			positions.AppendVector3(&v)
+			normals.Append(0, -1, 0)
+			uvs.AppendVector2(&uv1)
+			indicesOrig = append(indicesOrig, uint32(nextidx))
 			nextidx++
 		}
 
 		// Appends copy of first vertex (center)
 		var vertex, normal math32.Vector3
 		var uv math32.Vector2
-		Positions.GetVector3(3*int(indices[0]), &vertex)
-		Normals.GetVector3(3*int(indices[0]), &normal)
-		Uvs.GetVector2(2*int(indices[0]), &uv)
-		Positions.AppendVector3(&vertex)
-		Normals.AppendVector3(&normal)
-		Uvs.AppendVector2(&uv)
-		indices = append(indices, uint32(nextidx))
+		positions.GetVector3(3*int(indicesOrig[0]), &vertex)
+		normals.GetVector3(3*int(indicesOrig[0]), &normal)
+		uvs.GetVector2(2*int(indicesOrig[0]), &uv)
+		positions.AppendVector3(&vertex)
+		normals.AppendVector3(&normal)
+		uvs.AppendVector2(&uv)
+		indicesOrig = append(indicesOrig, uint32(nextidx))
 		nextidx++
 
 		// Appends copy of second vertex (v1) USING LAST UV2
-		Positions.GetVector3(3*int(indices[1]), &vertex)
-		Normals.GetVector3(3*int(indices[1]), &normal)
-		Positions.AppendVector3(&vertex)
-		Normals.AppendVector3(&normal)
-		Uvs.AppendVector2(&uv2)
-		indices = append(indices, uint32(nextidx))
+		positions.GetVector3(3*int(indicesOrig[1]), &vertex)
+		normals.GetVector3(3*int(indicesOrig[1]), &normal)
+		positions.AppendVector3(&vertex)
+		normals.AppendVector3(&normal)
+		uvs.AppendVector2(&uv2)
+		indicesOrig = append(indicesOrig, uint32(nextidx))
 		nextidx++
 
-		// Appends faces indices
+		// Appends faces indicesOrig
 		for x := 0; x < radialSegments; x++ {
 			pos := 2 * x
-			i1 := indices[pos]
-			i2 := indices[pos+3]
-			i3 := indices[pos+1]
-			Indices.Append(uint32(i1), uint32(i2), uint32(i3))
+			i1 := indicesOrig[pos]
+			i2 := indicesOrig[pos+3]
+			i3 := indicesOrig[pos+1]
+			indices.Append(uint32(i1), uint32(i2), uint32(i3))
 		}
 		// Third group is optional bottom cap of the cylinder
-		c.AddGroup(nextGroup, Indices.Size()-nextGroup, 2)
+		c.AddGroup(nextGroup, indices.Size()-nextGroup, 2)
 	}
 
-	c.SetIndices(Indices)
-	c.AddVBO(gls.NewVBO().AddAttrib("VertexPosition", 3).SetBuffer(Positions))
-	c.AddVBO(gls.NewVBO().AddAttrib("VertexNormal", 3).SetBuffer(Normals))
-	c.AddVBO(gls.NewVBO().AddAttrib("VertexTexcoord", 2).SetBuffer(Uvs))
+	c.SetIndices(indices)
+	c.AddVBO(gls.NewVBO(positions).AddAttrib(gls.VertexPosition, 3))
+	c.AddVBO(gls.NewVBO(normals).AddAttrib(gls.VertexNormal, 3))
+	c.AddVBO(gls.NewVBO(uvs).AddAttrib(gls.VertexTexcoord, 2))
 
 	return c
 }

+ 277 - 91
geometry/geometry.go

@@ -16,20 +16,31 @@ type IGeometry interface {
 	Dispose()
 }
 
-// Geometry is a vertex based geometry.
+// Geometry encapsulates a three-dimensional vertex-based geometry.
 type Geometry struct {
-	refcount            int             // Current number of references
-	vbos                []*gls.VBO      // Array of VBOs
-	groups              []Group         // Array geometry groups
-	indices             math32.ArrayU32 // Buffer with indices
-	gs                  *gls.GLS        // Pointer to gl context. Valid after first render setup
-	handleVAO           uint32          // Handle to OpenGL VAO
-	handleIndices       uint32          // Handle to OpenGL buffer for indices
-	updateIndices       bool            // Flag to indicate that indices must be transferred
-	boundingBox         math32.Box3     // Last calculated bounding box
-	boundingBoxValid    bool            // Indicates if last calculated bounding box is valid
-	boundingSphere      math32.Sphere   // Last calculated bounding sphere
-	boundingSphereValid bool            // Indicates if last calculated bounding sphere is valid
+	refcount      int               // Current number of references
+	vbos          []*gls.VBO        // Array of VBOs
+	groups        []Group           // Array geometry groups
+	indices       math32.ArrayU32   // Buffer with indices
+	gs            *gls.GLS          // Pointer to gl context. Valid after first render setup
+	ShaderDefines gls.ShaderDefines // Geometry-specific shader defines
+	handleVAO     uint32            // Handle to OpenGL VAO
+	handleIndices uint32            // Handle to OpenGL buffer for indices
+	updateIndices bool              // Flag to indicate that indices must be transferred
+
+	// Geometric properties
+	boundingBox    math32.Box3    // Last calculated bounding box
+	boundingSphere math32.Sphere  // Last calculated bounding sphere
+	area           float32        // Last calculated area
+	volume         float32        // Last calculated volume
+	rotInertia     math32.Matrix3 // Last calculated rotational inertia matrix
+
+	// Flags indicating whether geometric properties are valid
+	boundingBoxValid    bool // Indicates if last calculated bounding box is valid
+	boundingSphereValid bool // Indicates if last calculated bounding sphere is valid
+	areaValid           bool // Indicates if last calculated area is valid
+	volumeValid         bool // Indicates if last calculated volume is valid
+	rotInertiaValid     bool // Indicates if last calculated rotational inertia matrix is valid
 }
 
 // Group is a geometry group object.
@@ -58,6 +69,7 @@ func (g *Geometry) Init() {
 	g.handleVAO = 0
 	g.handleIndices = 0
 	g.updateIndices = true
+	g.ShaderDefines = *gls.NewShaderDefines()
 }
 
 // Incref increments the reference count for this geometry
@@ -71,7 +83,7 @@ func (g *Geometry) Incref() *Geometry {
 }
 
 // Dispose decrements this geometry reference count and
-// if necessary releases OpenGL resources, C memory
+// if possible releases OpenGL resources, C memory
 // and VBOs associated with this geometry.
 func (g *Geometry) Dispose() {
 
@@ -146,8 +158,8 @@ func (g *Geometry) AddVBO(vbo *gls.VBO) {
 	// Check that the provided VBO doesn't have conflicting attributes with existing VBOs
 	for _, existingVbo := range g.vbos {
 		for _, attrib := range vbo.Attributes() {
-			if existingVbo.Attrib(attrib.Name) != nil {
-				panic("Geometry.AddVBO: geometry already has a VBO with attribute " + attrib.Name)
+			if existingVbo.AttribName(attrib.Name) != nil {
+				panic("Geometry.AddVBO: geometry already has a VBO with attribute named:" + attrib.Name)
 			}
 		}
 	}
@@ -157,16 +169,22 @@ func (g *Geometry) AddVBO(vbo *gls.VBO) {
 
 // VBO returns a pointer to this geometry's VBO which contain the specified attribute.
 // Returns nil if the VBO is not found.
-func (g *Geometry) VBO(attrib string) *gls.VBO {
+func (g *Geometry) VBO(atype gls.AttribType) *gls.VBO {
 
 	for _, vbo := range g.vbos {
-		if vbo.Attrib(attrib) != nil {
+		if vbo.Attrib(atype) != nil {
 			return vbo
 		}
 	}
 	return nil
 }
 
+// VBOs returns all of this geometry's VBOs.
+func (g *Geometry) VBOs() []*gls.VBO {
+
+	return g.vbos
+}
+
 // Items returns the number of items in the first VBO.
 // (The number of items should be same for all VBOs)
 // An item is a complete group of attributes in the VBO buffer.
@@ -182,32 +200,135 @@ func (g *Geometry) Items() int {
 	return vbo.Buffer().Bytes() / vbo.StrideSize()
 }
 
+// SetAttributeName sets the name of the VBO attribute associated with the provided attribute type.
+func (g *Geometry) SetAttributeName(atype gls.AttribType, attribName string) {
+
+	vbo := g.VBO(atype)
+	if vbo != nil {
+		vbo.Attrib(atype).Name = attribName
+	}
+}
+
+// AttributeName returns the name of the VBO attribute associated with the provided attribute type.
+func (g *Geometry) AttributeName(atype gls.AttribType) string {
+
+	return g.VBO(atype).Attrib(atype).Name
+}
+
+// OperateOnVertices iterates over all the vertices and calls
+// the specified callback function with a pointer to each vertex.
+// The vertex pointers can be modified inside the callback and
+// the modifications will be applied to the buffer at each iteration.
+// The callback function returns false to continue or true to break.
+func (g *Geometry) OperateOnVertices(cb func(vertex *math32.Vector3) bool) {
+
+	// Get buffer with position vertices
+	vbo := g.VBO(gls.VertexPosition)
+	if vbo == nil {
+		return
+	}
+	vbo.OperateOnVectors3(gls.VertexPosition, cb)
+}
+
+// ReadVertices iterates over all the vertices and calls
+// the specified callback function with the value of each vertex.
+// The callback function returns false to continue or true to break.
+func (g *Geometry) ReadVertices(cb func(vertex math32.Vector3) bool) {
+
+	// Get buffer with position vertices
+	vbo := g.VBO(gls.VertexPosition)
+	if vbo == nil {
+		return
+	}
+	vbo.ReadVectors3(gls.VertexPosition, cb)
+}
+
+// OperateOnVertexNormals iterates over all the vertex normals
+// and calls the specified callback function with a pointer to each normal.
+// The vertex pointers can be modified inside the callback and
+// the modifications will be applied to the buffer at each iteration.
+// The callback function returns false to continue or true to break.
+func (g *Geometry) OperateOnVertexNormals(cb func(normal *math32.Vector3) bool) {
+
+	// Get buffer with position vertices
+	vbo := g.VBO(gls.VertexNormal)
+	if vbo == nil {
+		return
+	}
+	vbo.OperateOnVectors3(gls.VertexNormal, cb)
+}
+
+// ReadVertexNormals iterates over all the vertex normals and calls
+// the specified callback function with the value of each normal.
+// The callback function returns false to continue or true to break.
+func (g *Geometry) ReadVertexNormals(cb func(vertex math32.Vector3) bool) {
+
+	// Get buffer with position vertices
+	vbo := g.VBO(gls.VertexNormal)
+	if vbo == nil {
+		return
+	}
+	vbo.ReadVectors3(gls.VertexNormal, cb)
+}
+
+// ReadFaces iterates over all the vertices and calls
+// the specified callback function with face-forming vertex triples.
+// The callback function returns false to continue or true to break.
+func (g *Geometry) ReadFaces(cb func(vA, vB, vC math32.Vector3) bool) {
+
+	// Get buffer with position vertices
+	vbo := g.VBO(gls.VertexPosition)
+	if vbo == nil {
+		return
+	}
+
+	// If geometry has indexed vertices need to loop over indexes
+	if g.Indexed() {
+		var vA, vB, vC math32.Vector3
+		positions := vbo.Buffer()
+		for i := 0; i < g.indices.Size(); i += 3 {
+			// Get face vertices
+			positions.GetVector3(int(3*g.indices[i]), &vA)
+			positions.GetVector3(int(3*g.indices[i+1]), &vB)
+			positions.GetVector3(int(3*g.indices[i+2]), &vC)
+			// Call callback with face vertices
+			brk := cb(vA, vB, vC)
+			if brk {
+				break
+			}
+		}
+	} else {
+		// Geometry does NOT have indexed vertices - can read vertices in sequence
+		vbo.ReadTripleVectors3(gls.VertexPosition, cb)
+	}
+}
+
+// TODO Read and Operate on Texcoords, Faces, Edges, FaceNormals, etc...
+
+// Indexed returns whether the geometry is indexed or not.
+func (g *Geometry) Indexed() bool {
+
+	return g.indices.Size() > 0
+}
+
 // BoundingBox computes the bounding box of the geometry if necessary
 // and returns is value.
 func (g *Geometry) BoundingBox() math32.Box3 {
 
-	// If valid, returns its value
+	// If valid, return its value
 	if g.boundingBoxValid {
 		return g.boundingBox
 	}
 
-	// Get buffer with position vertices
-	vboPos := g.VBO("VertexPosition")
-	if vboPos == nil {
-		return g.boundingBox
-	}
-	stride := vboPos.Stride()
-	offset := vboPos.AttribOffset("VertexPosition")
-	positions := vboPos.Buffer()
-
-	// Calculates bounding box
-	var vertex math32.Vector3
+	// Reset bounding box
 	g.boundingBox.Min.Set(0, 0, 0)
 	g.boundingBox.Max.Set(0, 0, 0)
-	for i := offset; i < positions.Size(); i += stride {
-		positions.GetVector3(i, &vertex)
+
+	// Expand bounding box by each vertex
+	g.ReadVertices(func(vertex math32.Vector3) bool {
 		g.boundingBox.ExpandByPoint(&vertex)
-	}
+		return false
+	})
 	g.boundingBoxValid = true
 	return g.boundingBox
 }
@@ -216,84 +337,149 @@ func (g *Geometry) BoundingBox() math32.Box3 {
 // if necessary and returns its value.
 func (g *Geometry) BoundingSphere() math32.Sphere {
 
-	// if valid, returns its value
+	// If valid, return its value
 	if g.boundingSphereValid {
 		return g.boundingSphere
 	}
 
-	// Get buffer with position vertices
-	vboPos := g.VBO("VertexPosition")
-	if vboPos == nil {
-		return g.boundingSphere
-	}
-	stride := vboPos.Stride()
-	offset := vboPos.AttribOffset("VertexPosition")
-	positions := vboPos.Buffer()
-
-	// Get/calculates the bounding box
+	// Reset radius, calculate bounding box and copy center
+	g.boundingSphere.Radius = float32(0)
 	box := g.BoundingBox()
-
-	// Sets the center of the bounding sphere the same as the center of the bounding box.
 	box.Center(&g.boundingSphere.Center)
-	center := g.boundingSphere.Center
 
 	// Find the radius of the bounding sphere
-	maxRadiusSq := float32(0.0)
-	for i := offset; i < positions.Size(); i += stride {
-		var vertex math32.Vector3
-		positions.GetVector3(i, &vertex)
-		maxRadiusSq = math32.Max(maxRadiusSq, center.DistanceToSquared(&vertex))
-	}
-	radius := math32.Sqrt(maxRadiusSq)
-	if math32.IsNaN(radius) {
-		panic("geometry.BoundingSphere: computed radius is NaN")
-	}
-	g.boundingSphere.Radius = float32(radius)
+	maxRadiusSq := float32(0)
+	g.ReadVertices(func(vertex math32.Vector3) bool {
+		maxRadiusSq = math32.Max(maxRadiusSq, g.boundingSphere.Center.DistanceToSquared(&vertex))
+		return false
+	})
+	g.boundingSphere.Radius = float32(math32.Sqrt(maxRadiusSq))
 	g.boundingSphereValid = true
 	return g.boundingSphere
 }
 
+// Area returns the surface area.
+// NOTE: This only works for triangle-based meshes.
+func (g *Geometry) Area() float32 {
+
+	// If valid, return its value
+	if g.areaValid {
+		return g.area
+	}
+
+	// Reset area
+	g.area = 0
+
+	// Sum area of all triangles
+	g.ReadFaces(func(vA, vB, vC math32.Vector3) bool {
+		vA.Sub(&vC)
+		vB.Sub(&vC)
+		vC.CrossVectors(&vA, &vB)
+		g.area += vC.Length() / 2.0
+		return false
+	})
+	g.areaValid = true
+	return g.area
+}
+
+// Volume returns the volume.
+// NOTE: This only works for closed triangle-based meshes.
+func (g *Geometry) Volume() float32 {
+
+	// If valid, return its value
+	if g.volumeValid {
+		return g.volume
+	}
+
+	// Reset volume
+	g.volume = 0
+
+	// Calculate volume of all tetrahedrons
+	g.ReadFaces(func(vA, vB, vC math32.Vector3) bool {
+		vA.Sub(&vC)
+		vB.Sub(&vC)
+		g.volume += vC.Dot(vA.Cross(&vB)) / 6.0
+		return false
+	})
+	g.volumeValid = true
+	return g.volume
+}
+
+// RotationalInertia returns the rotational inertia tensor, also known as the moment of inertia.
+// This assumes constant density of 1 (kg/m^2).
+// To adjust for a different constant density simply scale the returning matrix by the density.
+func (g *Geometry) RotationalInertia(mass float32) math32.Matrix3 {
+
+	// If valid, return its value
+	if g.rotInertiaValid {
+		return g.rotInertia
+	}
+
+	// Reset rotational inertia
+	g.rotInertia.Zero()
+
+	// For now approximate result based on bounding box
+	b := math32.NewVec3()
+	box := g.BoundingBox()
+	box.Size(b)
+	multiplier := mass / 12.0
+
+	x := (b.Y*b.Y + b.Z*b.Z) * multiplier
+	y := (b.X*b.X + b.Z*b.Z) * multiplier
+	z := (b.Y*b.Y + b.X*b.X) * multiplier
+
+	g.rotInertia.Set(
+		x, 0, 0,
+		0, y, 0,
+		0, 0, z,
+	)
+	return g.rotInertia
+}
+
+// ProjectOntoAxis projects the geometry onto the specified axis,
+// effectively squashing it into a line passing through the local origin.
+// Returns the maximum and the minimum values on that line (i.e. signed distances from the local origin).
+func (g *Geometry) ProjectOntoAxis(localAxis *math32.Vector3) (float32, float32) {
+
+	var max, min float32
+	g.ReadVertices(func(vertex math32.Vector3) bool {
+		val := vertex.Dot(localAxis)
+		if val > max {
+			max = val
+		}
+		if val < min {
+			min = val
+		}
+		return false
+	})
+	return max, min
+}
+
+// TODO:
+// https://stackoverflow.com/questions/21640545/how-to-check-for-convexity-of-a-3d-mesh
+// func (g *Geometry) IsConvex() bool {
+//
+// {
+
 // ApplyMatrix multiplies each of the geometry position vertices
 // by the specified matrix and apply the correspondent normal
 // transform matrix to the geometry normal vectors.
 // The geometry's bounding box and sphere are recomputed if needed.
 func (g *Geometry) ApplyMatrix(m *math32.Matrix4) {
 
-	// Get positions buffer
-	vboPos := g.VBO("VertexPosition")
-	if vboPos == nil {
-		return
-	}
-	stride := vboPos.Stride()
-	offset := vboPos.AttribOffset("VertexPosition")
-	positions := vboPos.Buffer()
-	// Apply matrix to all position vertices
-	for i := offset; i < positions.Size(); i += stride {
-		var vertex math32.Vector3
-		positions.GetVector3(i, &vertex)
+	// Apply matrix to all vertices
+	g.OperateOnVertices(func(vertex *math32.Vector3) bool {
 		vertex.ApplyMatrix4(m)
-		positions.SetVector3(i, &vertex)
-	}
-	vboPos.Update()
+		return false
+	})
 
-	// Get normals buffer
-	vboNormals := g.VBO("VertexNormal")
-	if vboNormals == nil {
-		return
-	}
-	stride = vboNormals.Stride()
-	offset = vboNormals.AttribOffset("VertexNormal")
-	normals := vboNormals.Buffer()
 	// Apply normal matrix to all normal vectors
 	var normalMatrix math32.Matrix3
 	normalMatrix.GetNormalMatrix(m)
-	for i := offset; i < normals.Size(); i += stride {
-		var vertex math32.Vector3
-		normals.GetVector3(i, &vertex)
-		vertex.ApplyMatrix3(&normalMatrix).Normalize()
-		normals.SetVector3(i, &vertex)
-	}
-	vboNormals.Update()
+	g.OperateOnVertexNormals(func(normal *math32.Vector3) bool {
+		normal.ApplyMatrix3(&normalMatrix).Normalize()
+		return false
+	})
 }
 
 // RenderSetup is called by the renderer before drawing the geometry.
@@ -301,12 +487,12 @@ func (g *Geometry) RenderSetup(gs *gls.GLS) {
 
 	// First time initialization
 	if g.gs == nil {
-		// Generates VAO and binds it
+		// Generate VAO and binds it
 		g.handleVAO = gs.GenVertexArray()
 		gs.BindVertexArray(g.handleVAO)
-		// Generates VBO for indices
+		// Generate VBO for indices
 		g.handleIndices = gs.GenBuffer()
-		// Saves pointer to gl indicating initialization was done.
+		// Saves pointer to gs indicating initialization was done.
 		g.gs = gs
 	}
 

+ 144 - 0
geometry/morph.go

@@ -0,0 +1,144 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package geometry
+
+import (
+	"github.com/g3n/engine/gls"
+	"github.com/g3n/engine/math32"
+	"strconv"
+	"sort"
+)
+
+// MorphGeometry represents a base geometry and its morph targets.
+type MorphGeometry struct {
+	baseGeometry  *Geometry   // The base geometry
+	targets       []*Geometry // The morph target geometries
+	activeTargets []*Geometry // The morph target geometries
+	weights       []float32   // The weights for each morph target
+	uniWeights    gls.Uniform // Texture unit uniform location cache
+	morphGeom     *Geometry   // Cache of the last CPU-morphed geometry
+}
+
+// NumMorphInfluencers is the maximum number of active morph targets.
+const NumMorphTargets = 8
+
+// NewMorphGeometry creates and returns a pointer to a new MorphGeometry.
+func NewMorphGeometry(baseGeometry *Geometry) *MorphGeometry {
+
+	mg := new(MorphGeometry)
+	mg.baseGeometry = baseGeometry
+
+	mg.targets = make([]*Geometry, 0)
+	mg.activeTargets = make([]*Geometry, 0)
+	mg.weights = make([]float32, NumMorphTargets)
+
+	mg.baseGeometry.ShaderDefines.Set("MORPHTARGETS", strconv.Itoa(NumMorphTargets))
+	mg.uniWeights.Init("morphTargetInfluences")
+	return mg
+}
+
+// GetGeometry satisfies the IGeometry interface.
+func (mg *MorphGeometry) GetGeometry() *Geometry {
+
+	return mg.baseGeometry
+}
+
+// SetWeights sets the morph target weights.
+func (mg *MorphGeometry) SetWeights(weights []float32) {
+
+	mg.weights = weights
+}
+
+// Weights returns the morph target weights.
+func (mg *MorphGeometry) Weights() []float32 {
+
+	return mg.weights
+}
+
+// Weights returns the morph target weights.
+func (mg *MorphGeometry) AddMorphTargets(morphTargets ...*Geometry) {
+
+	log.Error("ADD morph targets")
+	mg.targets = append(mg.targets, morphTargets...)
+}
+
+// ActiveMorphTargets sorts the morph targets by weight and returns the top n morph targets with largest weight.
+func (mg *MorphGeometry) ActiveMorphTargets() []*Geometry {
+
+	numTargets := len(mg.targets)
+	if numTargets == 0 {
+		return nil
+	}
+
+	sortedMorphTargets := make([]*Geometry, numTargets)
+	copy(sortedMorphTargets, mg.targets)
+	sort.Slice(sortedMorphTargets, func(i, j int) bool {
+		return mg.weights[i] > mg.weights[j]
+	})
+
+	// TODO check current 0 weights
+
+	//if len(mg.targets) < NumMorphTargets-1 {
+		return sortedMorphTargets
+	//} else {
+	//	return sortedMorphTargets[:NumMorphTargets-1]
+	//}
+
+}
+
+// SetIndices sets the indices array for this geometry.
+func (mg *MorphGeometry) SetIndices(indices math32.ArrayU32) {
+
+	mg.baseGeometry.SetIndices(indices)
+	for i := range mg.targets {
+		mg.targets[i].SetIndices(indices)
+	}
+}
+
+// ComputeMorphed computes a morphed geometry from the provided morph target weights.
+// Note that morphing is usually computed by the GPU in shaders.
+// This CPU implementation allows users to obtain an instance of a morphed geometry
+// if so desired (loosing morphing ability).
+func (mg *MorphGeometry) ComputeMorphed(weights []float32) *Geometry {
+
+	morphed := NewGeometry()
+	// TODO
+	return morphed
+}
+
+// Dispose releases, if possible, OpenGL resources, C memory
+// and VBOs associated with the base geometry and morph targets.
+func (mg *MorphGeometry) Dispose() {
+
+	mg.baseGeometry.Dispose()
+	for i := range mg.targets {
+		mg.targets[i].Dispose()
+	}
+}
+
+// RenderSetup is called by the renderer before drawing the geometry.
+func (mg *MorphGeometry) RenderSetup(gs *gls.GLS) {
+
+	mg.baseGeometry.RenderSetup(gs)
+
+	// Sort weights and find top 8 morph targets with largest current weight (8 is the max sent to shader)
+	activeMorphTargets := mg.ActiveMorphTargets()
+
+	for i, mt := range activeMorphTargets {
+
+		mt.SetAttributeName(gls.VertexPosition, "MorphPosition"+strconv.Itoa(i))
+		mt.SetAttributeName(gls.VertexNormal, "MorphNormal"+strconv.Itoa(i))
+		//mt.SetAttributeName(vTangent, fmt.Sprintf("MorphTangent[%d]", i))
+
+		// Transfer morphed geometry VBOs
+		for _, vbo := range mt.VBOs() {
+			vbo.Transfer(gs)
+		}
+	}
+
+	// Transfer texture info combined uniform
+	location := mg.uniWeights.Location(gs)
+	gs.Uniform1fv(location, int32(len(activeMorphTargets)), mg.weights)
+}

+ 11 - 3
geometry/plane.go

@@ -71,9 +71,17 @@ func NewPlane(width, height float32, widthSegments, heightSegments int) *Plane {
 	}
 
 	plane.SetIndices(indices)
-	plane.AddVBO(gls.NewVBO().AddAttrib("VertexPosition", 3).SetBuffer(positions))
-	plane.AddVBO(gls.NewVBO().AddAttrib("VertexNormal", 3).SetBuffer(normals))
-	plane.AddVBO(gls.NewVBO().AddAttrib("VertexTexcoord", 2).SetBuffer(uvs))
+	plane.AddVBO(gls.NewVBO(positions).AddAttrib(gls.VertexPosition, 3))
+	plane.AddVBO(gls.NewVBO(normals).AddAttrib(gls.VertexNormal, 3))
+	plane.AddVBO(gls.NewVBO(uvs).AddAttrib(gls.VertexTexcoord, 2))
+
+	// Update area
+	plane.area = width*height
+	plane.areaValid = true
+
+	// Update volume
+	plane.volume = 0
+	plane.volumeValid = true
 
 	return plane
 }

+ 9 - 5
geometry/sphere.go

@@ -83,13 +83,17 @@ func NewSphere(radius float64, widthSegments, heightSegments int, phiStart, phiL
 	}
 
 	s.SetIndices(indices)
-	s.AddVBO(gls.NewVBO().AddAttrib("VertexPosition", 3).SetBuffer(positions))
-	s.AddVBO(gls.NewVBO().AddAttrib("VertexNormal", 3).SetBuffer(normals))
-	s.AddVBO(gls.NewVBO().AddAttrib("VertexTexcoord", 2).SetBuffer(uvs))
+	s.AddVBO(gls.NewVBO(positions).AddAttrib(gls.VertexPosition, 3))
+	s.AddVBO(gls.NewVBO(normals).AddAttrib(gls.VertexNormal, 3))
+	s.AddVBO(gls.NewVBO(uvs).AddAttrib(gls.VertexTexcoord, 2))
 
-	r := float32(s.Radius)
-	s.boundingSphere = math32.Sphere{math32.Vector3{0, 0, 0}, r}
+	r := float32(radius)
+
+	// Update bounding sphere
+	s.boundingSphere.Radius = 3
 	s.boundingSphereValid = true
+
+	// Update bounding box
 	s.boundingBox = math32.Box3{math32.Vector3{-r, -r, -r}, math32.Vector3{r, r, r}}
 	s.boundingBoxValid = true
 

+ 3 - 3
geometry/torus.go

@@ -69,9 +69,9 @@ func NewTorus(radius, tube float64, radialSegments, tubularSegments int, arc flo
 	}
 
 	t.SetIndices(indices)
-	t.AddVBO(gls.NewVBO().AddAttrib("VertexPosition", 3).SetBuffer(positions))
-	t.AddVBO(gls.NewVBO().AddAttrib("VertexNormal", 3).SetBuffer(normals))
-	t.AddVBO(gls.NewVBO().AddAttrib("VertexTexcoord", 2).SetBuffer(uvs))
+	t.AddVBO(gls.NewVBO(positions).AddAttrib(gls.VertexPosition, 3))
+	t.AddVBO(gls.NewVBO(normals).AddAttrib(gls.VertexNormal, 3))
+	t.AddVBO(gls.NewVBO(uvs).AddAttrib(gls.VertexTexcoord, 2))
 
 	return t
 }

+ 60 - 71
gls/program.go

@@ -13,31 +13,32 @@ import (
 	"strings"
 )
 
-// Program represents a shader program.
+// Program represents an OpenGL program.
+// It must have Vertex and Fragment shaders.
+// It can also have a Geometry shader.
 type Program struct {
-	// Shows source code in error messages
-	ShowSource bool
-	gs         *GLS
-	handle     uint32
-	shaders    []shaderInfo
-	uniforms   map[string]int32
-	Specs      interface{}
+	gs         *GLS             // OpenGL state
+	ShowSource bool             // Show source code in error messages
+	handle     uint32           // OpenGL program handle
+	shaders    []shaderInfo     // List of shaders for this program
+	uniforms   map[string]int32 // List of uniforms
 }
 
+// shaderInfo contains OpenGL-related shader information.
 type shaderInfo struct {
-	stype   uint32
-	source  string
-	defines map[string]interface{}
-	handle  uint32
+	stype  uint32 // OpenGL shader type (VERTEX_SHADER, FRAGMENT_SHADER, or GEOMETRY_SHADER)
+	source string // Shader source code
+	handle uint32 // OpenGL shader handle
 }
 
-// Map shader types to names
+// Map from shader types to names.
 var shaderNames = map[uint32]string{
 	VERTEX_SHADER:   "Vertex Shader",
 	FRAGMENT_SHADER: "Fragment Shader",
+	GEOMETRY_SHADER: "Geometry Shader",
 }
 
-// NewProgram creates a new empty shader program object.
+// NewProgram creates and returns a new empty shader program object.
 // Use this type methods to add shaders and build the final program.
 func (gs *GLS) NewProgram() *Program {
 
@@ -50,74 +51,65 @@ func (gs *GLS) NewProgram() *Program {
 	return prog
 }
 
+// Handle returns the OpenGL handle of this program.
+func (prog *Program) Handle() uint32 {
+
+	return prog.handle
+}
+
 // AddShader adds a shader to this program.
 // This must be done before the program is built.
-func (prog *Program) AddShader(stype uint32, source string, defines map[string]interface{}) {
+func (prog *Program) AddShader(stype uint32, source string) {
 
+	// Check if program already built
 	if prog.handle != 0 {
 		log.Fatal("Program already built")
 	}
-	prog.shaders = append(prog.shaders, shaderInfo{stype, source, defines, 0})
+	prog.shaders = append(prog.shaders, shaderInfo{stype, source, 0})
 }
 
-// Build builds the program compiling and linking the previously supplied shaders.
+// DeleteShaders deletes all of this program's shaders from OpenGL.
+func (prog *Program) DeleteShaders() {
+
+	for _, shaderInfo := range prog.shaders {
+		if shaderInfo.handle != 0 {
+			prog.gs.DeleteShader(shaderInfo.handle)
+			shaderInfo.handle = 0
+		}
+	}
+}
+
+// Build builds the program, compiling and linking the previously supplied shaders.
 func (prog *Program) Build() error {
 
+	// Check if program already built
 	if prog.handle != 0 {
-		return fmt.Errorf("Program already built")
+		return fmt.Errorf("program already built")
 	}
 
-	// Checks if shaders were provided
+	// Check if shaders were provided
 	if len(prog.shaders) == 0 {
-		return fmt.Errorf("No shaders supplied")
+		return fmt.Errorf("no shaders supplied")
 	}
 
 	// Create program
 	prog.handle = prog.gs.CreateProgram()
 	if prog.handle == 0 {
-		return fmt.Errorf("Error creating program")
+		return fmt.Errorf("error creating program")
 	}
 
 	// Clean unused GL allocated resources
-	defer func() {
-		for _, sinfo := range prog.shaders {
-			if sinfo.handle != 0 {
-				prog.gs.DeleteShader(sinfo.handle)
-				sinfo.handle = 0
-			}
-		}
-	}()
+	defer prog.DeleteShaders()
 
-	// Compiles and attach each shader
+	// Compile and attach shaders
 	for _, sinfo := range prog.shaders {
-		// Creates string with defines from specified parameters
-		deflines := make([]string, 0)
-		if sinfo.defines != nil {
-			for pname, pval := range sinfo.defines {
-				line := "#define " + pname + " "
-				switch val := pval.(type) {
-				case bool:
-					if val {
-						deflines = append(deflines, line)
-					}
-				case float32:
-					line += strconv.FormatFloat(float64(val), 'f', -1, 32)
-					deflines = append(deflines, line)
-				default:
-					panic("Parameter type not supported")
-				}
-			}
-		}
-		deftext := strings.Join(deflines, "\n")
-		// Compile shader
-		shader, err := prog.CompileShader(sinfo.stype, sinfo.source+deftext)
+		shader, err := prog.CompileShader(sinfo.stype, sinfo.source)
 		if err != nil {
 			prog.gs.DeleteProgram(prog.handle)
 			prog.handle = 0
-			msg := fmt.Sprintf("Error compiling %s: %s", shaderNames[sinfo.stype], err)
+			msg := fmt.Sprintf("error compiling %s: %s", shaderNames[sinfo.stype], err)
 			if prog.ShowSource {
-				source := FormatSource(sinfo.source + deftext)
-				msg += source
+				msg += FormatSource(sinfo.source)
 			}
 			return errors.New(msg)
 		}
@@ -125,25 +117,19 @@ func (prog *Program) Build() error {
 		prog.gs.AttachShader(prog.handle, shader)
 	}
 
-	// Link program and checks for errors
+	// Link program and check for errors
 	prog.gs.LinkProgram(prog.handle)
 	var status int32
 	prog.gs.GetProgramiv(prog.handle, LINK_STATUS, &status)
 	if status == FALSE {
 		log := prog.gs.GetProgramInfoLog(prog.handle)
 		prog.handle = 0
-		return fmt.Errorf("Error linking program: %v", log)
+		return fmt.Errorf("error linking program: %v", log)
 	}
 
 	return nil
 }
 
-// Handle returns the handle of this program
-func (prog *Program) Handle() uint32 {
-
-	return prog.handle
-}
-
 // GetAttribLocation returns the location of the specified attribute
 // in this program. This location is internally cached.
 func (prog *Program) GetAttribLocation(name string) int32 {
@@ -161,26 +147,28 @@ func (prog *Program) GetUniformLocation(name string) int32 {
 		prog.gs.stats.UnilocHits++
 		return loc
 	}
-	// Get location from GL
+
+	// Get location from OpenGL
 	loc = prog.gs.GetUniformLocation(prog.handle, name)
+	prog.gs.stats.UnilocMiss++
+
 	// Cache result
 	prog.uniforms[name] = loc
 	if loc < 0 {
-		log.Warn("GetUniformLocation(%s) NOT FOUND", name)
+		log.Warn("Program.GetUniformLocation(%s): NOT FOUND", name)
 	}
-	prog.gs.stats.UnilocMiss++
+
 	return loc
 }
 
-// CompileShader creates and compiles a shader of the specified type and with
-// the specified source code and returns a non-zero value by which
-// it can be referenced.
+// CompileShader creates and compiles an OpenGL shader of the specified type, with
+// the specified source code, and returns a non-zero value by which it can be referenced.
 func (prog *Program) CompileShader(stype uint32, source string) (uint32, error) {
 
-	// Creates shader object
+	// Create shader object
 	shader := prog.gs.CreateShader(stype)
 	if shader == 0 {
-		return 0, fmt.Errorf("Error creating shader")
+		return 0, fmt.Errorf("error creating shader")
 	}
 
 	// Set shader source and compile it
@@ -198,10 +186,11 @@ func (prog *Program) CompileShader(stype uint32, source string) (uint32, error)
 	}
 
 	// If the shader compiled OK but the log has data,
-	// logs this data instead of returning error
+	// log this data instead of returning error
 	if len(slog) > 2 {
 		log.Warn("%s", slog)
 	}
+
 	return shader, nil
 }
 

+ 58 - 0
gls/shaderdefines.go

@@ -0,0 +1,58 @@
+// Copyright 2016 The G3N Authors. All rights reserved.
+// Use of this source code is governed by a BSD-style
+// license that can be found in the LICENSE file.
+
+package gls
+
+// ShaderDefines is a store of shader defines ("#define <key> <value>").
+type ShaderDefines map[string]string
+
+// NewShaderDefines creates and returns a pointer to a ShaderDefines object.
+func NewShaderDefines() *ShaderDefines {
+
+	sd := ShaderDefines(make(map[string]string))
+	return &sd
+}
+
+// Set sets a shader define with the specified value.
+func (sd *ShaderDefines) Set(name, value string) {
+
+	(*sd)[name] = value
+}
+
+// Unset removes the specified name from the shader defines.
+func (sd *ShaderDefines) Unset(name string) {
+
+	delete(*sd, name)
+}
+
+// Add adds to this ShaderDefines all the key-value pairs in the specified ShaderDefines.
+func (sd *ShaderDefines) Add(other *ShaderDefines) {
+
+	for k, v := range map[string]string(*other){
+		(*sd)[k] = v
+	}
+}
+
+// Equals compares two ShaderDefines and return true if they contain the same key-value pairs.
+func (sd *ShaderDefines) Equals(other *ShaderDefines) bool {
+
+	if sd == nil && other == nil {
+		return true
+	}
+	if sd != nil && other != nil {
+		if len(*sd) != len(*other) {
+			return false
+		}
+		for k := range map[string]string(*sd) {
+			v1, ok1 := (*sd)[k]
+			v2, ok2 := (*other)[k]
+			if v1 != v2 || ok1 != ok2 {
+				return false
+			}
+		}
+		return true
+	}
+	// One is nil and the other is not nil
+	return false
+}

+ 140 - 52
gls/vbo.go

@@ -21,15 +21,36 @@ type VBO struct {
 
 // VBOattrib describes one attribute of an OpenGL Vertex Buffer Object.
 type VBOattrib struct {
-	Name     string // Name of of the attribute
-	ItemSize int32  // Number of elements
+	Type     AttribType // Type of the attribute
+	Name     string     // Name of the attribute
+	ItemSize int32      // Number of elements
+}
+
+// AttribType is the functional type of a vbo attribute.
+type AttribType int
+
+const (
+	Undefined = AttribType(iota)
+	VertexPosition
+	VertexNormal
+	VertexColor
+	VertexTexcoord
+)
+
+// Map from attribute type to default attribute name.
+var attribTypeMap = map[AttribType]string{
+	VertexPosition: "VertexPosition",
+	VertexNormal:   "VertexNormal",
+	VertexColor:    "VertexColor",
+	VertexTexcoord: "VertexTexcoord",
 }
 
 // NewVBO creates and returns a pointer to a new OpenGL Vertex Buffer Object.
-func NewVBO() *VBO {
+func NewVBO(buffer math32.ArrayF32) *VBO {
 
 	vbo := new(VBO)
 	vbo.init()
+	vbo.SetBuffer(buffer)
 	return vbo
 }
 
@@ -43,23 +64,47 @@ func (vbo *VBO) init() {
 	vbo.attribs = make([]VBOattrib, 0)
 }
 
-// AddAttrib adds a new attribute to the VBO.
-func (vbo *VBO) AddAttrib(name string, itemSize int32) *VBO {
+// AddAttrib adds a new attribute to the VBO by attribute type.
+func (vbo *VBO) AddAttrib(atype AttribType, itemSize int32) *VBO {
 
 	vbo.attribs = append(vbo.attribs, VBOattrib{
+		Type:     atype,
+		Name:     attribTypeMap[atype],
+		ItemSize: itemSize,
+	})
+	return vbo
+}
+
+// AddAttribName adds a new attribute to the VBO by name.
+func (vbo *VBO) AddAttribName(name string, itemSize int32) *VBO {
+
+	vbo.attribs = append(vbo.attribs, VBOattrib{
+		Type:     Undefined,
 		Name:     name,
 		ItemSize: itemSize,
 	})
 	return vbo
 }
 
-// Attrib finds and returns a pointer to the VBO attribute with the specified name.
+// Attrib finds and returns a pointer to the VBO attribute with the specified type.
 // Returns nil if not found.
-func (vbo *VBO) Attrib(name string) *VBOattrib {
+func (vbo *VBO) Attrib(atype AttribType) *VBOattrib {
 
-	for _, attr := range vbo.attribs {
-		if attr.Name == name {
-			return &attr
+	for i := range vbo.attribs {
+		if vbo.attribs[i].Type == atype {
+			return &vbo.attribs[i]
+		}
+	}
+	return nil
+}
+
+// AttribName finds and returns a pointer to the VBO attribute with the specified name.
+// Returns nil if not found.
+func (vbo *VBO) AttribName(name string) *VBOattrib {
+
+	for i := range vbo.attribs {
+		if vbo.attribs[i].Name == name {
+			return &vbo.attribs[i]
 		}
 	}
 	return nil
@@ -122,8 +167,22 @@ func (vbo *VBO) Update() {
 }
 
 // AttribOffset returns the total number of elements from
-// all attributes preceding the specified attribute.
-func (vbo *VBO) AttribOffset(name string) int {
+// all attributes preceding the attribute specified by type.
+func (vbo *VBO) AttribOffset(attribType AttribType) int {
+
+	elementCount := 0
+	for _, attr := range vbo.attribs {
+		if attr.Type == attribType {
+			return elementCount
+		}
+		elementCount += int(attr.ItemSize)
+	}
+	return elementCount
+}
+
+// AttribOffsetName returns the total number of elements from
+// all attributes preceding the attribute specified by name.
+func (vbo *VBO) AttribOffsetName(name string) int {
 
 	elementCount := 0
 	for _, attr := range vbo.attribs {
@@ -182,6 +241,7 @@ func (vbo *VBO) Transfer(gs *GLS) {
 			// Get attribute location in the current program
 			loc := gs.prog.GetAttribLocation(attrib.Name)
 			if loc < 0 {
+				log.Warn("Attribute not found: %v", attrib.Name)
 				continue
 			}
 			// Enables attribute and sets its stride and offset in the buffer
@@ -204,43 +264,71 @@ func (vbo *VBO) Transfer(gs *GLS) {
 	vbo.update = false
 }
 
-//// Transfer is called internally and transfer the data in the VBO buffer to OpenGL if necessary
-//func (vbo *VBO) Transfer(gs *GLS) {
-//
-//	// If the VBO buffer is empty, ignore
-//	if vbo.buffer.Bytes() == 0 {
-//		return
-//	}
-//
-//	// First time initialization
-//	if vbo.gs == nil {
-//		vbo.handle = gs.GenBuffer()
-//		gs.BindBuffer(ARRAY_BUFFER, vbo.handle)
-//		// Calculates stride
-//		stride := vbo.Stride()
-//		// For each attribute
-//		var items uint32 = 0
-//		var offset uint32 = 0
-//		elsize := int32(unsafe.Sizeof(float32(0)))
-//		for _, attrib := range vbo.attribs {
-//			// Get attribute location in the current program
-//			loc := gs.prog.GetAttribLocation(attrib.Name)
-//			if loc < 0 {
-//				continue
-//			}
-//			// Enables attribute and sets its stride and offset in the buffer
-//			gs.EnableVertexAttribArray(uint32(loc))
-//			gs.VertexAttribPointer(uint32(loc), attrib.ItemSize, FLOAT, false, int32(stride), offset)
-//			items += uint32(attrib.ItemSize)
-//			offset = uint32(elsize) * items
-//		}
-//		vbo.gs = gs // this indicates that the vbo was initialized
-//	}
-//	if !vbo.update {
-//		return
-//	}
-//	// Transfer the VBO data to OpenGL
-//	gs.BindBuffer(ARRAY_BUFFER, vbo.handle)
-//	gs.BufferData(ARRAY_BUFFER, vbo.buffer.Bytes(), &vbo.buffer[0], vbo.usage)
-//	vbo.update = false
-//}
+// OperateOnVectors3 iterates over all 3-float32 items for the specified attribute
+// and calls the specified callback function with a pointer to each item as a Vector3.
+// The vector pointers can be modified inside the callback and the modifications will be applied to the buffer at each iteration.
+// The callback function returns false to continue or true to break.
+func (vbo *VBO) OperateOnVectors3(attribType AttribType, cb func(vec *math32.Vector3) bool) {
+
+	stride := vbo.Stride()
+	offset := vbo.AttribOffset(attribType)
+	buffer := vbo.Buffer()
+
+	// Call callback for each vector3, updating the buffer afterward
+	var vec math32.Vector3
+	for i := offset; i < vbo.buffer.Size(); i += stride {
+		buffer.GetVector3(i, &vec)
+		brk := cb(&vec)
+		buffer.SetVector3(i, &vec)
+		if brk {
+			break
+		}
+	}
+	vbo.Update()
+}
+
+// ReadVectors3 iterates over all 3-float32 items for the specified attribute
+// and calls the specified callback function with the value of each item as a Vector3.
+// The callback function returns false to continue or true to break.
+func (vbo *VBO) ReadVectors3(attribType AttribType, cb func(vec math32.Vector3) bool) {
+
+	stride := vbo.Stride()
+	offset := vbo.AttribOffset(attribType)
+	positions := vbo.Buffer()
+
+	// Call callback for each vector3
+	var vec math32.Vector3
+	for i := offset; i < positions.Size(); i += stride {
+		positions.GetVector3(i, &vec)
+		brk := cb(vec)
+		if brk {
+			break
+		}
+	}
+}
+
+
+// Read3Vectors3 iterates over all 3-float32 items (3 items at a time) for the specified attribute
+// and calls the specified callback function with the value of each of the 3 items as Vector3.
+// The callback function returns false to continue or true to break.
+func (vbo *VBO) ReadTripleVectors3(attribType AttribType, cb func(vec1, vec2, vec3 math32.Vector3) bool) {
+
+	stride := vbo.Stride()
+	offset := vbo.AttribOffset(attribType)
+	positions := vbo.Buffer()
+
+	doubleStride := 2*stride
+	loopStride := 3*stride
+
+	// Call callback for each vector3 triple
+	var vec1, vec2, vec3 math32.Vector3
+	for i := offset; i < positions.Size(); i += loopStride {
+		positions.GetVector3(i, &vec1)
+		positions.GetVector3(i + stride, &vec2)
+		positions.GetVector3(i + doubleStride, &vec3)
+		brk := cb(vec1, vec2, vec3)
+		if brk {
+			break
+		}
+	}
+}

+ 2 - 2
graphic/axis_helper.go

@@ -36,8 +36,8 @@ func NewAxisHelper(size float32) *AxisHelper {
 		0, 1, 0, 0.6, 1, 0,
 		0, 0, 1, 0, 0.6, 1,
 	)
-	geom.AddVBO(gls.NewVBO().AddAttrib("VertexPosition", 3).SetBuffer(positions))
-	geom.AddVBO(gls.NewVBO().AddAttrib("VertexColor", 3).SetBuffer(colors))
+	geom.AddVBO(gls.NewVBO(positions).AddAttrib(gls.VertexPosition, 3))
+	geom.AddVBO(gls.NewVBO(colors).AddAttrib(gls.VertexColor, 3))
 
 	// Creates line material
 	mat := material.NewBasic()

+ 3 - 4
graphic/grid_helper.go

@@ -36,10 +36,9 @@ func NewGridHelper(size, step float32, color *math32.Color) *GridHelper {
 	// Creates geometry
 	geom := geometry.NewGeometry()
 	geom.AddVBO(
-		gls.NewVBO().
-			AddAttrib("VertexPosition", 3).
-			AddAttrib("VertexColor", 3).
-			SetBuffer(positions),
+		gls.NewVBO(positions).
+			AddAttrib(gls.VertexPosition, 3).
+			AddAttrib(gls.VertexColor, 3),
 	)
 
 	// Creates material

+ 1 - 1
graphic/lines.go

@@ -81,7 +81,7 @@ func lineRaycast(igr IGraphic, rc *core.Raycaster, intersects *[]core.Intersect,
 	var interRay math32.Vector3
 
 	// Get geometry positions and indices buffers
-	vboPos := geom.VBO("VertexPosition")
+	vboPos := geom.VBO(gls.VertexPosition)
 	if vboPos == nil {
 		return
 	}

+ 12 - 52
graphic/mesh.go

@@ -144,57 +144,17 @@ func (m *Mesh) Raycast(rc *core.Raycaster, intersects *[]core.Intersect) {
 		}
 	}
 
-	// Get buffer with position vertices
-	vboPos := geom.VBO("VertexPosition")
-	if vboPos == nil {
-		panic("mesh.Raycast(): VertexPosition VBO not found")
-	}
-	positions := vboPos.Buffer()
-	indices := geom.Indices()
-
-	var vA, vB, vC math32.Vector3
-
-	// Geometry has indexed vertices
-	if indices.Size() > 0 {
-		for i := 0; i < indices.Size(); i += 3 {
-			// Get face indices
-			a := indices[i]
-			b := indices[i+1]
-			c := indices[i+2]
-			// Get face position vectors
-			positions.GetVector3(int(3*a), &vA)
-			positions.GetVector3(int(3*b), &vB)
-			positions.GetVector3(int(3*c), &vC)
-			// Checks intersection of the ray with this face
-			mat := m.GetMaterial(i).GetMaterial()
-			var point math32.Vector3
-			intersect := checkIntersection(mat, &vA, &vB, &vC, &point)
-			if intersect != nil {
-				intersect.Index = uint32(i)
-				*intersects = append(*intersects, *intersect)
-			}
-		}
-		// Geometry has NO indexed vertices
-	} else {
-		stride := vboPos.Stride()
-		offset := vboPos.AttribOffset("VertexPosition")
-		for i := offset; i < positions.Size(); i += stride {
-			// Get face indices
-			a := i / 3
-			b := a + 1
-			c := a + 2
-			// Set face position vectors
-			positions.GetVector3(int(3*a), &vA)
-			positions.GetVector3(int(3*b), &vB)
-			positions.GetVector3(int(3*c), &vC)
-			// Checks intersection of the ray with this face
-			mat := m.GetMaterial(i).GetMaterial()
-			var point math32.Vector3
-			intersect := checkIntersection(mat, &vA, &vB, &vC, &point)
-			if intersect != nil {
-				intersect.Index = uint32(a)
-				*intersects = append(*intersects, *intersect)
-			}
+	i := 0
+	geom.ReadFaces(func(vA, vB, vC math32.Vector3) bool {
+		// Checks intersection of the ray with this face
+		mat := m.GetMaterial(i).GetMaterial()
+		var point math32.Vector3
+		intersect := checkIntersection(mat, &vA, &vB, &vC, &point)
+		if intersect != nil {
+			intersect.Index = uint32(i)
+			*intersects = append(*intersects, *intersect)
 		}
-	}
+		i++
+		return false
+	})
 }

+ 5 - 5
graphic/normals_helper.go

@@ -35,13 +35,13 @@ func NewNormalsHelper(ig IGraphic, size float32, color *math32.Color, lineWidth
 	nh.targetGeometry = ig.GetGeometry()
 
 	// Get the number of target vertex positions
-	vertices := nh.targetGeometry.VBO("VertexPosition")
+	vertices := nh.targetGeometry.VBO(gls.VertexPosition)
 	n := vertices.Buffer().Size() * 2
 
 	// Creates this helper geometry
 	geom := geometry.NewGeometry()
 	positions := math32.NewArrayF32(n, n)
-	geom.AddVBO(gls.NewVBO().AddAttrib("VertexPosition", 3).SetBuffer(positions))
+	geom.AddVBO(gls.NewVBO(positions).AddAttrib(gls.VertexPosition, 3))
 
 	// Creates this helper material
 	mat := material.NewStandard(color)
@@ -67,14 +67,14 @@ func (nh *NormalsHelper) Update() {
 	normalMatrix.GetNormalMatrix(&matrixWorld)
 
 	// Get the target positions and normals buffers
-	tPosVBO := nh.targetGeometry.VBO("VertexPosition")
+	tPosVBO := nh.targetGeometry.VBO(gls.VertexPosition)
 	tPositions := tPosVBO.Buffer()
-	tNormVBO := nh.targetGeometry.VBO("VertexNormal")
+	tNormVBO := nh.targetGeometry.VBO(gls.VertexNormal)
 	tNormals := tNormVBO.Buffer()
 
 	// Get this object positions buffer
 	geom := nh.GetGeometry()
-	posVBO := geom.VBO("VertexPosition")
+	posVBO := geom.VBO(gls.VertexPosition)
 	positions := posVBO.Buffer()
 
 	// For each target object vertex position:

+ 6 - 24
graphic/points.go

@@ -90,28 +90,10 @@ func (p *Points) Raycast(rc *core.Raycaster, intersects *[]core.Intersect) {
 		})
 	}
 
-	// Get buffer with position vertices
-	vboPos := geom.VBO("VertexPosition")
-	if vboPos == nil {
-		panic("points.Raycast(): VertexPosition VBO not found")
-	}
-	positions := vboPos.Buffer()
-
-	var point math32.Vector3
-	indices := geom.Indices()
-	// Geometry has indexed vertices
-	if indices.Size() > 0 {
-		for i := 0; i < indices.Size(); i++ {
-			a := indices[i]
-			positions.GetVector3(int(a*3), &point)
-			testPoint(&point, i)
-		}
-	} else {
-		stride := vboPos.Stride()
-		offset := vboPos.AttribOffset("VertexPosition")
-		for i := offset; i < positions.Size(); i += stride {
-			positions.GetVector3(i, &point)
-			testPoint(&point, i)
-		}
-	}
+	i := 0
+	geom.ReadVertices(func(vertex math32.Vector3) bool {
+		testPoint(&vertex, i)
+		i++
+		return false
+	})
 }

+ 4 - 5
graphic/sprite.go

@@ -43,10 +43,9 @@ func NewSprite(width, height float32, imat material.IMaterial) *Sprite {
 	// Set geometry buffers
 	geom.SetIndices(indices)
 	geom.AddVBO(
-		gls.NewVBO().
-			AddAttrib("VertexPosition", 3).
-			AddAttrib("VertexTexcoord", 2).
-			SetBuffer(positions),
+		gls.NewVBO(positions).
+			AddAttrib(gls.VertexPosition, 3).
+			AddAttrib(gls.VertexTexcoord, 2),
 	)
 
 	s.Graphic.Init(geom, gls.TRIANGLES)
@@ -114,7 +113,7 @@ func (s *Sprite) Raycast(rc *core.Raycaster, intersects *[]core.Intersect) {
 
 	// Get buffer with vertices and uvs
 	geom := s.GetGeometry()
-	vboPos := geom.VBO("VertexPosition")
+	vboPos := geom.VBO(gls.VertexPosition)
 	if vboPos == nil {
 		panic("sprite.Raycast(): VertexPosition VBO not found")
 	}

+ 3 - 4
gui/chart.go

@@ -476,7 +476,7 @@ func newChartScaleX(chart *Chart, lines int, color *math32.Color) *chartScaleX {
 
 	// Creates geometry and adds VBO
 	geom := geometry.NewGeometry()
-	geom.AddVBO(gls.NewVBO().AddAttrib("VertexPosition", 3).SetBuffer(positions))
+	geom.AddVBO(gls.NewVBO(positions).AddAttrib(gls.VertexPosition, 3))
 
 	// Initializes the panel graphic
 	gr := graphic.NewGraphic(geom, gls.LINES)
@@ -561,7 +561,7 @@ func newChartScaleY(chart *Chart, lines int, color *math32.Color) *chartScaleY {
 
 	// Creates geometry and adds VBO
 	geom := geometry.NewGeometry()
-	geom.AddVBO(gls.NewVBO().AddAttrib("VertexPosition", 3).SetBuffer(positions))
+	geom.AddVBO(gls.NewVBO(positions).AddAttrib(gls.VertexPosition, 3))
 
 	// Initializes the panel with this graphic
 	gr := graphic.NewGraphic(geom, gls.LINES)
@@ -629,9 +629,8 @@ func newGraph(chart *Chart, color *math32.Color, data []float32) *Graph {
 
 	// Creates geometry and adds VBO with positions
 	geom := geometry.NewGeometry()
-	lg.vbo = gls.NewVBO().AddAttrib("VertexPosition", 3)
 	lg.positions = math32.NewArrayF32(0, 0)
-	lg.vbo.SetBuffer(lg.positions)
+	lg.vbo = gls.NewVBO(lg.positions).AddAttrib(gls.VertexPosition, 3)
 	geom.AddVBO(lg.vbo)
 
 	// Initializes the panel with this graphic

+ 3 - 4
gui/panel.go

@@ -152,10 +152,9 @@ func (p *Panel) Initialize(width, height float32) {
 		// Creates geometry
 		geom := geometry.NewGeometry()
 		geom.SetIndices(indices)
-		geom.AddVBO(gls.NewVBO().
-			AddAttrib("VertexPosition", 3).
-			AddAttrib("VertexTexcoord", 2).
-			SetBuffer(positions),
+		geom.AddVBO(gls.NewVBO(positions).
+			AddAttrib(gls.VertexPosition, 3).
+			AddAttrib(gls.VertexTexcoord, 2),
 		)
 		panelQuadGeometry = geom
 	}

+ 5 - 13
loader/collada/geometry.go

@@ -285,22 +285,16 @@ func newMeshPolylist(m *Mesh, pels []interface{}) (*geometry.Geometry, uint32, e
 	geom := geometry.NewGeometry()
 
 	// Creates VBO with vertex positions
-	vboPositions := gls.NewVBO()
-	vboPositions.AddAttrib("VertexPosition", 3).SetBuffer(positions)
-	geom.AddVBO(vboPositions)
+	geom.AddVBO(gls.NewVBO(positions).AddAttrib(gls.VertexPosition, 3))
 
 	// Creates VBO with vertex normals
 	if normals.Size() > 0 {
-		vboNormals := gls.NewVBO()
-		vboNormals.AddAttrib("VertexNormal", 3).SetBuffer(normals)
-		geom.AddVBO(vboNormals)
+		geom.AddVBO(gls.NewVBO(normals).AddAttrib(gls.VertexNormal, 3))
 	}
 
 	// Creates VBO with uv coordinates
 	if uvs.Size() > 0 {
-		vboUvs := gls.NewVBO()
-		vboUvs.AddAttrib("VertexTexcoord", 2).SetBuffer(uvs)
-		geom.AddVBO(vboUvs)
+		geom.AddVBO(gls.NewVBO(uvs).AddAttrib(gls.VertexTexcoord, 2))
 	}
 
 	// Sets the geometry indices buffer
@@ -389,9 +383,7 @@ func newMeshLines(m *Mesh, ln *Lines) (*geometry.Geometry, uint32, error) {
 	geom := geometry.NewGeometry()
 
 	// Creates VBO with vertex positions
-	vboPositions := gls.NewVBO()
-	vboPositions.AddAttrib("VertexPosition", 3).SetBuffer(positions)
-	geom.AddVBO(vboPositions)
+	geom.AddVBO(gls.NewVBO(positions).AddAttrib(gls.VertexPosition, 3))
 
 	// Sets the geometry indices buffer
 	geom.SetIndices(indices)
@@ -444,7 +436,7 @@ func newMeshPoints(m *Mesh) (*geometry.Geometry, uint32, error) {
 
 	// Creates geometry and add VBO with vertex positions
 	geom := geometry.NewGeometry()
-	geom.AddVBO(gls.NewVBO().AddAttrib("VertexPosition", 3).SetBuffer(positions))
+	geom.AddVBO(gls.NewVBO(positions).AddAttrib(gls.VertexPosition, 3))
 	return geom, gls.POINTS, nil
 }
 

+ 3 - 3
loader/obj/obj.go

@@ -260,9 +260,9 @@ func (dec *Decoder) NewGeometry(obj *Object) (*geometry.Geometry, error) {
 	}
 
 	geom.SetIndices(indices)
-	geom.AddVBO(gls.NewVBO().AddAttrib("VertexPosition", 3).SetBuffer(positions))
-	geom.AddVBO(gls.NewVBO().AddAttrib("VertexNormal", 3).SetBuffer(normals))
-	geom.AddVBO(gls.NewVBO().AddAttrib("VertexTexcoord", 2).SetBuffer(uvs))
+	geom.AddVBO(gls.NewVBO(positions).AddAttrib(gls.VertexPosition, 3))
+	geom.AddVBO(gls.NewVBO(normals).AddAttrib(gls.VertexNormal, 3))
+	geom.AddVBO(gls.NewVBO(uvs).AddAttrib(gls.VertexTexcoord, 2))
 
 	return geom, nil
 }

+ 50 - 58
material/material.go

@@ -46,48 +46,54 @@ const (
 	UseLightAll         UseLights = 0xFF
 )
 
-// Interface for all materials
+// IMaterial is the interface for all materials.
 type IMaterial interface {
 	GetMaterial() *Material
 	RenderSetup(gs *gls.GLS)
 	Dispose()
 }
 
-//
-// Base Material
-//
+// Material is the base material.
 type Material struct {
-	refcount         int                  // Current number of references
-	shader           string               // Shader name
-	shaderUnique     bool                 // shader has only one instance (does not depend on lights or textures)
-	uselights        UseLights            // consider lights for shader selection
-	sidevis          Side                 // sides visible
-	transparent      bool                 // whether at all transparent
-	wireframe        bool                 // show as wirefrme
-	depthMask        bool                 // Enable writing into the depth buffer
-	depthTest        bool                 // Enable depth buffer test
-	depthFunc        uint32               // Active depth test function
-	blending         Blending             // blending mode
-	blendRGB         uint32               // separate blend equation for RGB
-	blendAlpha       uint32               // separate blend equation for Alpha
-	blendSrcRGB      uint32               // separate blend func source RGB
-	blendDstRGB      uint32               // separate blend func dest RGB
-	blendSrcAlpha    uint32               // separate blend func source Alpha
-	blendDstAlpha    uint32               // separate blend func dest Alpha
-	lineWidth        float32              // line width for lines and mesh wireframe
-	polyOffsetFactor float32              // polygon offset factor
-	polyOffsetUnits  float32              // polygon offset units
-	defines          map[string]string    // shader defines
-	textures         []*texture.Texture2D // List of textures
+	refcount         int                    // Current number of references
+
+	// Shader specification // TODO Move ShaderSpecs into Material ?
+	shader           string                 // Shader name
+	shaderUnique     bool                   // shader has only one instance (does not depend on lights or textures)
+	ShaderDefines    gls.ShaderDefines      // shader defines
+
+	uselights        UseLights              // Which light types to consider
+	sidevis          Side                   // Face side(s) visibility
+	blending         Blending               // Blending mode
+	transparent      bool                   // Whether at all transparent
+	wireframe        bool                   // Whether to render only the wireframe
+	lineWidth        float32                // Line width for lines and mesh wireframe
+	textures         []*texture.Texture2D   // List of textures
+
+	polyOffsetFactor float32                // polygon offset factor
+	polyOffsetUnits  float32                // polygon offset units
+
+	depthMask        bool                   // Enable writing into the depth buffer
+	depthTest        bool                   // Enable depth buffer test
+	depthFunc        uint32                 // Active depth test function
+
+	// Equations used for custom blending (when blending=BlendingCustom) // TODO implement methods
+	blendRGB         uint32                 // separate blend equation for RGB
+	blendAlpha       uint32                 // separate blend equation for Alpha
+	blendSrcRGB      uint32                 // separate blend func source RGB
+	blendDstRGB      uint32                 // separate blend func dest RGB
+	blendSrcAlpha    uint32                 // separate blend func source Alpha
+	blendDstAlpha    uint32                 // separate blend func dest Alpha
 }
 
-// NewMaterial returns a pointer to a new material
+// NewMaterial creates and returns a pointer to a new Material.
 func NewMaterial() *Material {
 
 	mat := new(Material)
 	return mat.Init()
 }
 
+// Init initializes the material.
 func (mat *Material) Init() *Material {
 
 	mat.refcount = 1
@@ -104,10 +110,14 @@ func (mat *Material) Init() *Material {
 	mat.polyOffsetUnits = 0
 	mat.textures = make([]*texture.Texture2D, 0)
 
+	// Setup shader defines and add default values
+	mat.ShaderDefines = *gls.NewShaderDefines()
+
+
 	return mat
 }
 
-// GetMaterial satisfies the IMaterial interface
+// GetMaterial satisfies the IMaterial interface.
 func (mat *Material) GetMaterial() *Material {
 
 	return mat
@@ -178,7 +188,7 @@ func (mat *Material) UseLights() UseLights {
 	return mat.uselights
 }
 
-// Sets the visible side(s) (SideFront | SideBack | SideDouble)
+// SetSide sets the visible side(s) (SideFront | SideBack | SideDouble)
 func (mat *Material) SetSide(side Side) {
 
 	mat.sidevis = side
@@ -190,23 +200,30 @@ func (mat *Material) Side() Side {
 	return mat.sidevis
 }
 
-// SetTransparent sets whether this material is transparent
+// SetTransparent sets whether this material is transparent.
 func (mat *Material) SetTransparent(state bool) {
 
 	mat.transparent = state
 }
 
-// Transparent returns whether this material is transparent
+// Transparent returns whether this material is transparent.
 func (mat *Material) Transparent() bool {
 
 	return mat.transparent
 }
 
+// SetWireframe sets whether only the wireframe is rendered.
 func (mat *Material) SetWireframe(state bool) {
 
 	mat.wireframe = state
 }
 
+// Wireframe returns whether only the wireframe is rendered.
+func (mat *Material) Wireframe() bool {
+
+	return mat.wireframe
+}
+
 func (mat *Material) SetDepthMask(state bool) {
 
 	mat.depthMask = state
@@ -233,32 +250,7 @@ func (mat *Material) SetPolygonOffset(factor, units float32) {
 	mat.polyOffsetUnits = units
 }
 
-// SetShaderDefine defines a name with the specified value which are
-// passed to this material shader.
-func (mat *Material) SetShaderDefine(name, value string) {
-
-	if mat.defines == nil {
-		mat.defines = make(map[string]string)
-	}
-	mat.defines[name] = value
-}
-
-// UnsetShaderDefines removes the specified name from the defines which
-// are passed to this material shader.
-func (mat *Material) UnsetShaderDefine(name string) {
-
-	if mat.defines == nil {
-		return
-	}
-	delete(mat.defines, name)
-}
-
-// ShaderDefines returns this material map of shader defines.
-func (mat *Material) ShaderDefines() map[string]string {
-
-	return mat.defines
-}
-
+// RenderSetup is called by the renderer before drawing objects with this material.
 func (mat *Material) RenderSetup(gs *gls.GLS) {
 
 	// Sets triangle side view mode
@@ -300,7 +292,7 @@ func (mat *Material) RenderSetup(gs *gls.GLS) {
 		gs.Disable(gls.BLEND)
 	case BlendingNormal:
 		gs.Enable(gls.BLEND)
-		gs.BlendEquationSeparate(gls.FUNC_ADD, gls.FUNC_ADD)
+		gs.BlendEquation(gls.FUNC_ADD)
 		gs.BlendFunc(gls.SRC_ALPHA, gls.ONE_MINUS_SRC_ALPHA)
 	case BlendingAdditive:
 		gs.Enable(gls.BLEND)

+ 1 - 2
material/phong.go

@@ -9,8 +9,7 @@ import (
 )
 
 // Phong material is identical to the Standard material but
-// the calculation of the lighting model is done in the
-// fragment shader.
+// the calculation of the lighting model is done in the fragment shader.
 type Phong struct {
 	Standard // Embedded standard material
 }

+ 10 - 10
material/physical.go

@@ -93,10 +93,10 @@ func (m *Physical) SetBaseColorMap(tex *texture.Texture2D) *Physical {
 	m.baseColorTex = tex
 	if m.baseColorTex != nil {
 		m.baseColorTex.SetUniformNames("uBaseColorSampler", "uBaseColorTexParams")
-		m.SetShaderDefine("HAS_BASECOLORMAP", "")
+		m.ShaderDefines.Set("HAS_BASECOLORMAP", "")
 		m.AddTexture(m.baseColorTex)
 	} else {
-		m.UnsetShaderDefine("HAS_BASECOLORMAP")
+		m.ShaderDefines.Unset("HAS_BASECOLORMAP")
 		m.RemoveTexture(m.baseColorTex)
 	}
 	return m
@@ -109,10 +109,10 @@ func (m *Physical) SetMetallicRoughnessMap(tex *texture.Texture2D) *Physical {
 	m.metallicRoughnessTex = tex
 	if m.metallicRoughnessTex != nil {
 		m.metallicRoughnessTex.SetUniformNames("uMetallicRoughnessSampler", "uMetallicRoughnessTexParams")
-		m.SetShaderDefine("HAS_METALROUGHNESSMAP", "")
+		m.ShaderDefines.Set("HAS_METALROUGHNESSMAP", "")
 		m.AddTexture(m.metallicRoughnessTex)
 	} else {
-		m.UnsetShaderDefine("HAS_METALROUGHNESSMAP")
+		m.ShaderDefines.Unset("HAS_METALROUGHNESSMAP")
 		m.RemoveTexture(m.metallicRoughnessTex)
 	}
 	return m
@@ -126,10 +126,10 @@ func (m *Physical) SetNormalMap(tex *texture.Texture2D) *Physical {
 	m.normalTex = tex
 	if m.normalTex != nil {
 		m.normalTex.SetUniformNames("uNormalSampler", "uNormalTexParams")
-		m.SetShaderDefine("HAS_NORMALMAP", "")
+		m.ShaderDefines.Set("HAS_NORMALMAP", "")
 		m.AddTexture(m.normalTex)
 	} else {
-		m.UnsetShaderDefine("HAS_NORMALMAP")
+		m.ShaderDefines.Unset("HAS_NORMALMAP")
 		m.RemoveTexture(m.normalTex)
 	}
 	return m
@@ -142,10 +142,10 @@ func (m *Physical) SetOcclusionMap(tex *texture.Texture2D) *Physical {
 	m.occlusionTex = tex
 	if m.occlusionTex != nil {
 		m.occlusionTex.SetUniformNames("uOcclusionSampler", "uOcclusionTexParams")
-		m.SetShaderDefine("HAS_OCCLUSIONMAP", "")
+		m.ShaderDefines.Set("HAS_OCCLUSIONMAP", "")
 		m.AddTexture(m.occlusionTex)
 	} else {
-		m.UnsetShaderDefine("HAS_OCCLUSIONMAP")
+		m.ShaderDefines.Unset("HAS_OCCLUSIONMAP")
 		m.RemoveTexture(m.occlusionTex)
 	}
 	return m
@@ -158,10 +158,10 @@ func (m *Physical) SetEmissiveMap(tex *texture.Texture2D) *Physical {
 	m.emissiveTex = tex
 	if m.emissiveTex != nil {
 		m.emissiveTex.SetUniformNames("uEmissiveSampler", "uEmissiveTexParams")
-		m.SetShaderDefine("HAS_EMISSIVEMAP", "")
+		m.ShaderDefines.Set("HAS_EMISSIVEMAP", "")
 		m.AddTexture(m.emissiveTex)
 	} else {
-		m.UnsetShaderDefine("HAS_EMISSIVEMAP")
+		m.ShaderDefines.Unset("HAS_EMISSIVEMAP")
 		m.RemoveTexture(m.emissiveTex)
 	}
 	return m

+ 154 - 14
math32/matrix3.go

@@ -35,6 +35,17 @@ func (m *Matrix3) Set(n11, n12, n13, n21, n22, n23, n31, n32, n33 float32) *Matr
 	return m
 }
 
+// SetFromMatrix4 sets the matrix elements based on a Matrix4.
+func (m *Matrix3) SetFromMatrix4(src *Matrix4) *Matrix3 {
+
+	m.Set(
+		src[0], src[4], src[8],
+		src[1], src[5], src[9],
+		src[2], src[6], src[10],
+	)
+	return m
+}
+
 // Identity sets this matrix as the identity matrix.
 // Returns the pointer to this updated matrix.
 func (m *Matrix3) Identity() *Matrix3 {
@@ -47,6 +58,18 @@ func (m *Matrix3) Identity() *Matrix3 {
 	return m
 }
 
+// Zero sets this matrix as the zero matrix.
+// Returns the pointer to this updated matrix.
+func (m *Matrix3) Zero() *Matrix3 {
+
+	m.Set(
+		0, 0, 0,
+		0, 0, 0,
+		0, 0, 0,
+	)
+	return m
+}
+
 // Copy copies src matrix into this one.
 // Returns the pointer to this updated matrix.
 func (m *Matrix3) Copy(src *Matrix3) *Matrix3 {
@@ -55,6 +78,43 @@ func (m *Matrix3) Copy(src *Matrix3) *Matrix3 {
 	return m
 }
 
+// MakeRotationFromQuaternion sets this matrix as a rotation matrix from the specified quaternion.
+// Returns pointer to this updated matrix.
+func (m *Matrix3) MakeRotationFromQuaternion(q *Quaternion) *Matrix3 {
+
+	x := q.X
+	y := q.Y
+	z := q.Z
+	w := q.W
+	x2 := x + x
+	y2 := y + y
+	z2 := z + z
+	xx := x * x2
+	xy := x * y2
+	xz := x * z2
+	yy := y * y2
+	yz := y * z2
+	zz := z * z2
+	wx := w * x2
+	wy := w * y2
+	wz := w * z2
+
+	m[0] = 1 - (yy + zz)
+	m[3] = xy - wz
+	m[6] = xz + wy
+
+	m[1] = xy + wz
+	m[4] = 1 - (xx + zz)
+	m[7] = yz - wx
+
+	m[2] = xz - wy
+	m[5] = yz + wx
+	m[8] = 1 - (xx + yy)
+
+	return m
+
+}
+
 // ApplyToVector3Array multiplies length vectors in the array starting at offset by this matrix.
 // Returns pointer to the updated array.
 // This matrix is unchanged.
@@ -74,6 +134,52 @@ func (m *Matrix3) ApplyToVector3Array(array []float32, offset int, length int) [
 	return array
 }
 
+// Multiply multiply this matrix by the other matrix
+// Returns pointer to this updated matrix.
+func (m *Matrix3) Multiply(other *Matrix3) *Matrix3 {
+
+	return m.MultiplyMatrices(m, other)
+}
+
+// MultiplyMatrices multiply matrix a by b storing the result in this matrix.
+// Returns pointer to this updated matrix.
+func (m *Matrix3) MultiplyMatrices(a, b *Matrix3) *Matrix3 {
+
+	a11 := a[0]
+	a12 := a[3]
+	a13 := a[6]
+	a21 := a[1]
+	a22 := a[4]
+	a23 := a[7]
+	a31 := a[2]
+	a32 := a[5]
+	a33 := a[8]
+
+	b11 := b[0]
+	b12 := b[3]
+	b13 := b[6]
+	b21 := b[1]
+	b22 := b[4]
+	b23 := b[7]
+	b31 := b[2]
+	b32 := b[5]
+	b33 := b[8]
+
+	m[0] = a11*b11 + a12*b21 + a13*b31
+	m[3] = a11*b12 + a12*b22 + a13*b32
+	m[6] = a11*b13 + a12*b23 + a13*b33
+
+	m[1] = a21*b11 + a22*b21 + a23*b31
+	m[4] = a21*b12 + a22*b22 + a23*b32
+	m[7] = a21*b13 + a22*b23 + a23*b33
+
+	m[2] = a31*b11 + a32*b21 + a33*b31
+	m[5] = a31*b12 + a32*b22 + a33*b32
+	m[8] = a31*b13 + a32*b23 + a33*b33
+
+	return m
+}
+
 // MultiplyScalar multiplies each of this matrix's components by the specified scalar.
 // Returns pointer to this updated matrix.
 func (m *Matrix3) MultiplyScalar(s float32) *Matrix3 {
@@ -90,6 +196,23 @@ func (m *Matrix3) MultiplyScalar(s float32) *Matrix3 {
 	return m
 }
 
+// ScaleColumns multiplies the matrix columns by the vector components.
+// This can be used when multiplying this matrix by a diagonal matrix if we store the diagonal components as a vector.
+// Returns pointer to this updated matrix.
+func (m *Matrix3) ScaleColumns(v *Vector3) *Matrix3 {
+
+	m[0] *= v.X
+	m[1] *= v.X
+	m[2] *= v.X
+	m[3] *= v.Y
+	m[4] *= v.Y
+	m[5] *= v.Y
+	m[6] *= v.Z
+	m[7] *= v.Z
+	m[8] *= v.Z
+	return m
+}
+
 // Determinant calculates and returns the determinant of this matrix.
 func (m *Matrix3) Determinant() float32 {
 
@@ -104,26 +227,42 @@ func (m *Matrix3) Determinant() float32 {
 // GetInverse sets this matrix to the inverse of the src matrix.
 // If the src matrix cannot be inverted returns error and
 // sets this matrix to the identity matrix.
-func (m *Matrix3) GetInverse(src *Matrix4) error {
+func (m *Matrix3) GetInverse(src *Matrix3) error {
+
+	n11 := src[0]
+	n21 := src[1]
+	n31 := src[2]
+	n12 := src[3]
+	n22 := src[4]
+	n32 := src[5]
+	n13 := src[6]
+	n23 := src[7]
+	n33 := src[8]
 
-	m[0] = src[10]*src[5] - src[6]*src[9]
-	m[1] = -src[10]*src[1] + src[2]*src[9]
-	m[2] = src[6]*src[1] - src[2]*src[5]
-	m[3] = -src[10]*src[4] + src[6]*src[8]
-	m[4] = src[10]*src[0] - src[2]*src[8]
-	m[5] = -src[6]*src[0] + src[2]*src[4]
-	m[6] = src[9]*src[4] - src[5]*src[8]
-	m[7] = -src[9]*src[0] + src[1]*src[8]
-	m[8] = src[5]*src[0] - src[1]*src[4]
+	t11 := n33*n22 - n32*n23
+	t12 := n32*n13 - n33*n12
+	t13 := n23*n12 - n22*n13
 
-	det := src[0]*m[0] + src[1]*m[3] + src[2]*m[6]
+	det := n11*t11 + n21*t12 + n31*t13
 
 	// no inverse
 	if det == 0 {
 		m.Identity()
-		return errors.New("Cannot inverse matrix")
+		return errors.New("cannot invert matrix")
 	}
-	m.MultiplyScalar(1.0 / det)
+
+	detInv := 1 / det
+
+	m[0] = t11 * detInv
+	m[1] = ( n31 * n23 - n33 * n21 ) * detInv
+	m[2] = ( n32 * n21 - n31 * n22 ) * detInv
+	m[3] = t12 * detInv
+	m[4] = ( n33 * n11 - n31 * n13 ) * detInv
+	m[5] = ( n31 * n12 - n32 * n11 ) * detInv
+	m[6] = t13 * detInv
+	m[7] = ( n21 * n13 - n23 * n11 ) * detInv
+	m[8] = ( n22 * n11 - n21 * n12 ) * detInv
+
 	return nil
 }
 
@@ -149,7 +288,8 @@ func (m *Matrix3) Transpose() *Matrix3 {
 // If the src matrix cannot be inverted returns error.
 func (m *Matrix3) GetNormalMatrix(src *Matrix4) error {
 
-	err := m.GetInverse(src)
+	m.SetFromMatrix4(src)
+	err := m.GetInverse(m)
 	m.Transpose()
 	return err
 }

+ 44 - 21
math32/matrix4.go

@@ -46,12 +46,25 @@ func (m *Matrix4) Set(n11, n12, n13, n14, n21, n22, n23, n24, n31, n32, n33, n34
 // Returns pointer to this updated matrix.
 func (m *Matrix4) Identity() *Matrix4 {
 
-	*m = Matrix4{
+	m.Set(
 		1, 0, 0, 0,
 		0, 1, 0, 0,
 		0, 0, 1, 0,
 		0, 0, 0, 1,
-	}
+	)
+	return m
+}
+
+// Zero sets this matrix as the zero matrix.
+// Returns the pointer to this updated matrix.
+func (m *Matrix4) Zero() *Matrix4 {
+
+	m.Set(
+		0, 0, 0, 0,
+		0, 0, 0, 0,
+		0, 0, 0, 0,
+		0, 0, 0, 0,
+	)
 	return m
 }
 
@@ -449,30 +462,40 @@ func (m *Matrix4) GetInverse(src *Matrix4) error {
 	n43 := src[11]
 	n44 := src[15]
 
-	m[0] = n23*n34*n42 - n24*n33*n42 + n24*n32*n43 - n22*n34*n43 - n23*n32*n44 + n22*n33*n44
-	m[4] = n14*n33*n42 - n13*n34*n42 - n14*n32*n43 + n12*n34*n43 + n13*n32*n44 - n12*n33*n44
-	m[8] = n13*n24*n42 - n14*n23*n42 + n14*n22*n43 - n12*n24*n43 - n13*n22*n44 + n12*n23*n44
-	m[12] = n14*n23*n32 - n13*n24*n32 - n14*n22*n33 + n12*n24*n33 + n13*n22*n34 - n12*n23*n34
-	m[1] = n24*n33*n41 - n23*n34*n41 - n24*n31*n43 + n21*n34*n43 + n23*n31*n44 - n21*n33*n44
-	m[5] = n13*n34*n41 - n14*n33*n41 + n14*n31*n43 - n11*n34*n43 - n13*n31*n44 + n11*n33*n44
-	m[9] = n14*n23*n41 - n13*n24*n41 - n14*n21*n43 + n11*n24*n43 + n13*n21*n44 - n11*n23*n44
-	m[13] = n13*n24*n31 - n14*n23*n31 + n14*n21*n33 - n11*n24*n33 - n13*n21*n34 + n11*n23*n34
-	m[2] = n22*n34*n41 - n24*n32*n41 + n24*n31*n42 - n21*n34*n42 - n22*n31*n44 + n21*n32*n44
-	m[6] = n14*n32*n41 - n12*n34*n41 - n14*n31*n42 + n11*n34*n42 + n12*n31*n44 - n11*n32*n44
-	m[10] = n12*n24*n41 - n14*n22*n41 + n14*n21*n42 - n11*n24*n42 - n12*n21*n44 + n11*n22*n44
-	m[14] = n14*n22*n31 - n12*n24*n31 - n14*n21*n32 + n11*n24*n32 + n12*n21*n34 - n11*n22*n34
-	m[3] = n23*n32*n41 - n22*n33*n41 - n23*n31*n42 + n21*n33*n42 + n22*n31*n43 - n21*n32*n43
-	m[7] = n12*n33*n41 - n13*n32*n41 + n13*n31*n42 - n11*n33*n42 - n12*n31*n43 + n11*n32*n43
-	m[11] = n13*n22*n41 - n12*n23*n41 - n13*n21*n42 + n11*n23*n42 + n12*n21*n43 - n11*n22*n43
-	m[15] = n12*n23*n31 - n13*n22*n31 + n13*n21*n32 - n11*n23*n32 - n12*n21*n33 + n11*n22*n33
-
-	det := n11*m[0] + n21*m[4] + n31*m[8] + n41*m[12]
+	t11 := n23*n34*n42 - n24*n33*n42 + n24*n32*n43 - n22*n34*n43 - n23*n32*n44 + n22*n33*n44
+	t12 := n14*n33*n42 - n13*n34*n42 - n14*n32*n43 + n12*n34*n43 + n13*n32*n44 - n12*n33*n44
+	t13 := n13*n24*n42 - n14*n23*n42 + n14*n22*n43 - n12*n24*n43 - n13*n22*n44 + n12*n23*n44
+	t14 := n14*n23*n32 - n13*n24*n32 - n14*n22*n33 + n12*n24*n33 + n13*n22*n34 - n12*n23*n34
+
+	det := n11 * t11 + n21 * t12 + n31 * t13 + n41 * t14
 
 	if det == 0 {
 		m.Identity()
 		return errors.New("Cannot inverse matrix")
 	}
-	m.MultiplyScalar(1.0 / det)
+
+	detInv := 1 / det
+
+	m[0] = t11 * detInv
+	m[1] = ( n24*n33*n41 - n23*n34*n41 - n24*n31*n43 + n21*n34*n43 + n23*n31*n44 - n21*n33*n44 ) * detInv
+	m[2] = ( n22*n34*n41 - n24*n32*n41 + n24*n31*n42 - n21*n34*n42 - n22*n31*n44 + n21*n32*n44 ) * detInv
+	m[3] = ( n23*n32*n41 - n22*n33*n41 - n23*n31*n42 + n21*n33*n42 + n22*n31*n43 - n21*n32*n43 ) * detInv
+
+	m[4] = t12 * detInv
+	m[5] = ( n13*n34*n41 - n14*n33*n41 + n14*n31*n43 - n11*n34*n43 - n13*n31*n44 + n11*n33*n44 ) * detInv
+	m[6] = ( n14*n32*n41 - n12*n34*n41 - n14*n31*n42 + n11*n34*n42 + n12*n31*n44 - n11*n32*n44 ) * detInv
+	m[7] = ( n12*n33*n41 - n13*n32*n41 + n13*n31*n42 - n11*n33*n42 - n12*n31*n43 + n11*n32*n43 ) * detInv
+
+	m[8] = t13 * detInv
+	m[9] = ( n14*n23*n41 - n13*n24*n41 - n14*n21*n43 + n11*n24*n43 + n13*n21*n44 - n11*n23*n44 ) * detInv
+	m[10] = ( n12*n24*n41 - n14*n22*n41 + n14*n21*n42 - n11*n24*n42 - n12*n21*n44 + n11*n22*n44 ) * detInv
+	m[11] = ( n13*n22*n41 - n12*n23*n41 - n13*n21*n42 + n11*n23*n42 + n12*n21*n43 - n11*n22*n43 ) * detInv
+
+	m[12] = t14 * detInv
+	m[13] = ( n13*n24*n31 - n14*n23*n31 + n14*n21*n33 - n11*n24*n33 - n13*n21*n34 + n11*n23*n34 ) * detInv
+	m[14] = ( n14*n22*n31 - n12*n24*n31 - n14*n21*n32 + n11*n24*n32 + n12*n21*n34 - n11*n22*n34 ) * detInv
+	m[15] = ( n12*n23*n31 - n13*n22*n31 + n13*n21*n32 - n11*n23*n32 - n12*n21*n33 + n11*n22*n33 ) * detInv
+
 	return nil
 }
 

+ 28 - 8
math32/quaternion.go

@@ -245,23 +245,37 @@ func (q *Quaternion) Length() float32 {
 func (q *Quaternion) Normalize() *Quaternion {
 
 	l := q.Length()
-
 	if l == 0 {
-
 		q.X = 0
 		q.Y = 0
 		q.Z = 0
 		q.W = 1
-
 	} else {
-
 		l = 1 / l
+		q.X *= l
+		q.Y *= l
+		q.Z *= l
+		q.W *= l
+	}
+	return q
+}
 
-		q.X = q.X * l
-		q.Y = q.Y * l
-		q.Z = q.Z * l
-		q.W = q.W * l
+// NormalizeFast approximates normalizing this quaternion.
+// Works best when the quaternion is already almost-normalized.
+// Returns pointer to this updated quaternion.
+func (q *Quaternion) NormalizeFast() *Quaternion {
 
+	f := (3.0-(q.X*q.X + q.Y*q.Y + q.Z*q.Z + q.W*q.W))/2.0
+	if f == 0 {
+		q.X = 0
+		q.Y = 0
+		q.Z = 0
+		q.W = 1
+	} else {
+		q.X *= f
+		q.Y *= f
+		q.Z *= f
+		q.W *= f
 	}
 	return q
 }
@@ -391,3 +405,9 @@ func (q *Quaternion) ToArray(array []float32, offset int) []float32 {
 
 	return array
 }
+
+// Clone returns a copy of this quaternion
+func (q *Quaternion) Clone() *Quaternion {
+
+	return NewQuaternion(q.X, q.Y, q.Z, q.W)
+}

+ 28 - 0
math32/vector2.go

@@ -17,6 +17,12 @@ func NewVector2(x, y float32) *Vector2 {
 	return &Vector2{X: x, Y: y}
 }
 
+// NewVec2 creates and returns a pointer to a new zero-ed Vector2.
+func NewVec2() *Vector2 {
+
+	return &Vector2{X: 0, Y: 0}
+}
+
 // Set sets this vector X and Y components.
 // Returns the pointer to this updated vector.
 func (v *Vector2) Set(x, y float32) *Vector2 {
@@ -70,6 +76,28 @@ func (v *Vector2) Component(index int) float32 {
 	}
 }
 
+// SetByName sets this vector component value by its case insensitive name: "x" or "y".
+func (v *Vector2) SetByName(name string, value float32) {
+
+	switch name {
+	case "x", "X":
+		v.X = value
+	case "y", "Y":
+		v.Y = value
+	default:
+		panic("Invalid Vector2 component name: " + name)
+	}
+}
+
+// Zero sets this vector X and Y components to be zero.
+// Returns the pointer to this updated vector.
+func (v *Vector2) Zero() *Vector2 {
+
+	v.X = 0
+	v.Y = 0
+	return v
+}
+
 // Copy copies other vector to this one.
 // It is equivalent to: *v = *other.
 // Returns the pointer to this updated vector.

+ 56 - 0
math32/vector3.go

@@ -18,6 +18,12 @@ func NewVector3(x, y, z float32) *Vector3 {
 	return &Vector3{X: x, Y: y, Z: z}
 }
 
+// NewVec3 creates and returns a pointer to a new zero-ed Vector3.
+func NewVec3() *Vector3 {
+
+	return &Vector3{X: 0, Y: 0, Z: 0}
+}
+
 // Set sets this vector X, Y and Z components.
 // Returns the pointer to this updated vector.
 func (v *Vector3) Set(x, y, z float32) *Vector3 {
@@ -98,6 +104,16 @@ func (v *Vector3) SetByName(name string, value float32) {
 	}
 }
 
+// Zero sets this vector X, Y and Z components to be zero.
+// Returns the pointer to this updated vector.
+func (v *Vector3) Zero() *Vector3 {
+
+	v.X = 0
+	v.Y = 0
+	v.Z = 0
+	return v
+}
+
 // Copy copies other vector to this one.
 // It is equivalent to: *v = *other.
 // Returns the pointer to this updated vector.
@@ -622,3 +638,43 @@ func (v *Vector3) SetFromQuaternion(q *Quaternion) *Vector3 {
 	v.SetFromRotationMatrix(matrix)
 	return v
 }
+
+// RandomTangents computes and returns two arbitrary tangents to the vector.
+func (v *Vector3) RandomTangents() (*Vector3, *Vector3) {
+
+	t1 := NewVector3(0,0,0)
+	t2 := NewVector3(0,0,0)
+	length := v.Length()
+	if length > 0 {
+		n := NewVector3(v.X/length, v.Y/length, v.Z/length)
+		randVec := NewVector3(0,0,0)
+		if Abs(n.X) < 0.9 {
+			randVec.SetX(1)
+			t1.CrossVectors(n, randVec)
+		} else if Abs(n.Y) < 0.9 {
+			randVec.SetY(1)
+			t1.CrossVectors(n, randVec)
+		} else {
+			randVec.SetZ(1)
+			t1.CrossVectors(n, randVec)
+		}
+		t2.CrossVectors(n, t1)
+	} else {
+		t1.SetX(1)
+		t2.SetY(1)
+	}
+
+	return t1, t2
+}
+
+// TODO: implement similar methods for Vector2 and Vector4
+// AlmostEquals returns whether the vector is almost equal to another vector within the specified tolerance.
+func (v *Vector3) AlmostEquals(other *Vector3, tolerance float32) bool {
+
+	if (v.X - other.X < tolerance) &&
+		(v.Y - other.Y < tolerance) &&
+		(v.Z - other.Z < tolerance) {
+			return true
+	}
+	return false
+}

+ 17 - 0
math32/vector4.go

@@ -18,6 +18,12 @@ func NewVector4(x, y, z, w float32) *Vector4 {
 	return &Vector4{X: x, Y: y, Z: z, W: w}
 }
 
+// NewVec4 creates and returns a pointer to a new zero-ed Vector4 (with W=1).
+func NewVec4() *Vector4 {
+
+	return &Vector4{X: 0, Y: 0, Z: 0, W: 1}
+}
+
 // Set sets this vector X, Y, Z and W components.
 // Returns the pointer to this updated vector.
 func (v *Vector4) Set(x, y, z, w float32) *Vector4 {
@@ -124,6 +130,17 @@ func (v *Vector4) SetByName(name string, value float32) {
 	}
 }
 
+// Zero sets this vector X, Y and Z components to be zero and W to be one.
+// Returns the pointer to this updated vector.
+func (v *Vector4) Zero() *Vector4 {
+
+	v.X = 0
+	v.Y = 0
+	v.Z = 0
+	v.W = 1
+	return v
+}
+
 // Copy copies other vector to this one.
 // Returns the pointer to this updated vector.
 func (v *Vector4) Copy(other *Vector4) *Vector4 {

+ 11 - 4
renderer/renderer.go

@@ -358,19 +358,26 @@ func (r *Renderer) renderScene(iscene core.INode, icam camera.ICamera) error {
 		// For each *GraphicMaterial
 		for _, grmat := range grmats {
 			mat := grmat.GetMaterial().GetMaterial()
+			geom := grmat.GetGraphic().GetGeometry()
+
+			// Add defines from material and geometry
+			r.specs.Defines = *gls.NewShaderDefines()
+			r.specs.Defines.Add(&mat.ShaderDefines)
+			r.specs.Defines.Add(&geom.ShaderDefines)
 
 			// Sets the shader specs for this material and sets shader program
 			r.specs.Name = mat.Shader()
 			r.specs.ShaderUnique = mat.ShaderUnique()
 			r.specs.UseLights = mat.UseLights()
 			r.specs.MatTexturesMax = mat.TextureCount()
-			r.specs.Defines = mat.ShaderDefines()
+
+			// Set active program and apply shader specs
 			_, err = r.shaman.SetProgram(&r.specs)
 			if err != nil {
 				return
 			}
 
-			// Setup lights (transfer lights uniforms)
+			// Setup lights (transfer lights' uniforms)
 			for idx, l := range r.ambLights {
 				l.RenderSetup(r.gs, &r.rinfo, idx)
 				r.stats.Lights++
@@ -394,8 +401,8 @@ func (r *Renderer) renderScene(iscene core.INode, icam camera.ICamera) error {
 		}
 	}
 
-	renderGraphicMaterials(r.grmatsOpaque) // Render opaque objects front to back
-	renderGraphicMaterials(r.grmatsTransp) // Render transparent objects back to front
+	renderGraphicMaterials(r.grmatsOpaque) // Render opaque objects (front to back)
+	renderGraphicMaterials(r.grmatsTransp) // Render transparent objects (back to front)
 
 	return err
 }

+ 3 - 4
renderer/shaders/include/lights.glsl

@@ -2,21 +2,21 @@
 // Lights uniforms
 //
 
-// Ambient lights uniforms
 #if AMB_LIGHTS>0
+    // Ambient lights color uniform
     uniform vec3 AmbientLightColor[AMB_LIGHTS];
 #endif
 
-// Directional lights uniform array. Each directional light uses 2 elements
 #if DIR_LIGHTS>0
+    // Directional lights uniform array. Each directional light uses 2 elements
     uniform vec3 DirLight[2*DIR_LIGHTS];
     // Macros to access elements inside the DirectionalLight uniform array
     #define DirLightColor(a)		DirLight[2*a]
     #define DirLightPosition(a)		DirLight[2*a+1]
 #endif
 
-// Point lights uniform array. Each point light uses 3 elements
 #if POINT_LIGHTS>0
+    // Point lights uniform array. Each point light uses 3 elements
     uniform vec3 PointLight[3*POINT_LIGHTS];
     // Macros to access elements inside the PointLight uniform array
     #define PointLightColor(a)			PointLight[3*a]
@@ -28,7 +28,6 @@
 #if SPOT_LIGHTS>0
     // Spot lights uniforms. Each spot light uses 5 elements
     uniform vec3  SpotLight[5*SPOT_LIGHTS];
-    
     // Macros to access elements inside the PointLight uniform array
     #define SpotLightColor(a)			SpotLight[5*a]
     #define SpotLightPosition(a)		SpotLight[5*a+1]

+ 6 - 0
renderer/shaders/include/morphtarget_vertex.glsl

@@ -0,0 +1,6 @@
+#ifdef MORPHTARGETS
+	vPosition += (MorphPosition{i} - VertexPosition) * morphTargetInfluences[{i}];
+  #ifdef MORPHTARGETS_NORMAL
+	vNormal += (MorphNormal{i} - VertexNormal) * morphTargetInfluences[{i}];
+  #endif
+#endif

+ 4 - 0
renderer/shaders/include/morphtarget_vertex_declaration.glsl

@@ -0,0 +1,4 @@
+#ifdef MORPHTARGETS
+	uniform float morphTargetInfluences[MORPHTARGETS];
+	#include <morphtarget_vertex_declaration2> [MORPHTARGETS]
+#endif

+ 4 - 0
renderer/shaders/include/morphtarget_vertex_declaration2.glsl

@@ -0,0 +1,4 @@
+	in vec3 MorphPosition{i};
+  #ifdef MORPHTARGETS_NORMAL
+	in vec3 MorphNormal{i};
+  #endif

+ 0 - 2
renderer/shaders/include/phong_model.glsl

@@ -112,5 +112,3 @@ void phongModel(vec4 position, vec3 normal, vec3 camDir, vec3 matAmbient, vec3 m
     ambdiff = ambientTotal + MatEmissiveColor + diffuseTotal;
     spec = specularTotal;
 }
-
-

+ 4 - 1
renderer/shaders/phong_vertex.glsl

@@ -9,6 +9,7 @@ uniform mat3 NormalMatrix;
 uniform mat4 MVP;
 
 #include <material>
+#include <morphtarget_vertex_declaration>
 
 // Output variables for Fragment shader
 out vec4 Position;
@@ -36,7 +37,9 @@ void main() {
     }
 #endif
     FragTexcoord = texcoord;
+    vec3 vPosition = VertexPosition;
+    #include <morphtarget_vertex> [MORPHTARGETS]
 
-    gl_Position = MVP * vec4(VertexPosition, 1.0);
+    gl_Position = MVP * vec4(vPosition, 1.0);
 }
 

+ 6 - 1
renderer/shaders/physical_vertex.glsl

@@ -9,6 +9,8 @@ uniform mat4 ModelViewMatrix;
 uniform mat3 NormalMatrix;
 uniform mat4 MVP;
 
+#include <morphtarget_vertex_declaration>
+
 // Output variables for Fragment shader
 out vec3 Position;
 out vec3 Normal;
@@ -36,7 +38,10 @@ void main() {
     // #endif
     FragTexcoord = texcoord;
 
-    gl_Position = MVP * vec4(VertexPosition, 1.0);
+    vec3 vPosition = VertexPosition;
+    #include <morphtarget_vertex> [MORPHTARGETS]
+
+    gl_Position = MVP * vec4(vPosition, 1.0);
 }
 
 

+ 1 - 1
renderer/shaders/shaders.go

@@ -12,7 +12,7 @@ package shaders
 type ProgramInfo struct {
 	Vertex   string // Vertex shader name
 	Fragment string // Fragment shader name
-	Geometry string // Geometry shader name (maybe an empty string)
+	Geometry string // Geometry shader name (optional)
 }
 
 // AddInclude adds a chunk of shader code to the default shaders registry

+ 50 - 19
renderer/shaders/sources.go

@@ -21,21 +21,21 @@ const include_lights_source = `//
 // Lights uniforms
 //
 
-// Ambient lights uniforms
 #if AMB_LIGHTS>0
+    // Ambient lights color uniform
     uniform vec3 AmbientLightColor[AMB_LIGHTS];
 #endif
 
-// Directional lights uniform array. Each directional light uses 2 elements
 #if DIR_LIGHTS>0
+    // Directional lights uniform array. Each directional light uses 2 elements
     uniform vec3 DirLight[2*DIR_LIGHTS];
     // Macros to access elements inside the DirectionalLight uniform array
     #define DirLightColor(a)		DirLight[2*a]
     #define DirLightPosition(a)		DirLight[2*a+1]
 #endif
 
-// Point lights uniform array. Each point light uses 3 elements
 #if POINT_LIGHTS>0
+    // Point lights uniform array. Each point light uses 3 elements
     uniform vec3 PointLight[3*POINT_LIGHTS];
     // Macros to access elements inside the PointLight uniform array
     #define PointLightColor(a)			PointLight[3*a]
@@ -47,7 +47,6 @@ const include_lights_source = `//
 #if SPOT_LIGHTS>0
     // Spot lights uniforms. Each spot light uses 5 elements
     uniform vec3  SpotLight[5*SPOT_LIGHTS];
-    
     // Macros to access elements inside the PointLight uniform array
     #define SpotLightColor(a)			SpotLight[5*a]
     #define SpotLightPosition(a)		SpotLight[5*a+1]
@@ -112,6 +111,27 @@ uniform vec3 Material[6];
             //texMixed.rgb /= texMixed.a;                                                      \
 `
 
+const include_morphtarget_vertex_source = `#ifdef MORPHTARGETS
+	vPosition += (MorphPosition{i} - VertexPosition) * morphTargetInfluences[{i}];
+//    vPosition = MorphPosition1;
+  #ifdef MORPHTARGETS_NORMAL
+	vNormal += (MorphNormal{i} - VertexNormal) * morphTargetInfluences[{i}];
+  #endif
+#endif
+`
+
+const include_morphtarget_vertex_declaration_source = `#ifdef MORPHTARGETS
+	uniform float morphTargetInfluences[MORPHTARGETS];
+	#include <morphtarget_vertex_declaration2> [MORPHTARGETS]
+#endif
+`
+
+const include_morphtarget_vertex_declaration2_source = `	in vec3 MorphPosition{i};
+  #ifdef MORPHTARGETS_NORMAL
+	in vec3 MorphNormal{i};
+  #endif
+`
+
 const include_phong_model_source = `/***
  phong lighting model
  Parameters:
@@ -226,8 +246,6 @@ void phongModel(vec4 position, vec3 normal, vec3 camDir, vec3 matAmbient, vec3 m
     ambdiff = ambientTotal + MatEmissiveColor + diffuseTotal;
     spec = specularTotal;
 }
-
-
 `
 
 const basic_fragment_source = `//
@@ -481,6 +499,7 @@ uniform mat3 NormalMatrix;
 uniform mat4 MVP;
 
 #include <material>
+#include <morphtarget_vertex_declaration>
 
 // Output variables for Fragment shader
 out vec4 Position;
@@ -508,8 +527,10 @@ void main() {
     }
 #endif
     FragTexcoord = texcoord;
+    vec3 vPosition = VertexPosition;
+    #include <morphtarget_vertex> [MORPHTARGETS]
 
-    gl_Position = MVP * vec4(VertexPosition, 1.0);
+    gl_Position = MVP * vec4(vPosition, 1.0);
 }
 
 `
@@ -942,6 +963,8 @@ uniform mat4 ModelViewMatrix;
 uniform mat3 NormalMatrix;
 uniform mat4 MVP;
 
+#include <morphtarget_vertex_declaration>
+
 // Output variables for Fragment shader
 out vec3 Position;
 out vec3 Normal;
@@ -969,7 +992,10 @@ void main() {
     // #endif
     FragTexcoord = texcoord;
 
-    gl_Position = MVP * vec4(VertexPosition, 1.0);
+    vec3 vPosition = VertexPosition;
+    #include <morphtarget_vertex> [MORPHTARGETS]
+
+    gl_Position = MVP * vec4(vPosition, 1.0);
 }
 
 
@@ -1179,7 +1205,7 @@ uniform mat4 MVP;
 #include <lights>
 #include <material>
 #include <phong_model>
-
+#include <morphtarget_vertex_declaration>
 
 // Outputs for the fragment shader.
 out vec3 ColorFrontAmbdiff;
@@ -1191,19 +1217,19 @@ out vec2 FragTexcoord;
 void main() {
 
     // Transform this vertex normal to camera coordinates.
-    vec3 normal = normalize(NormalMatrix * VertexNormal);
+    vec3 Normal = normalize(NormalMatrix * VertexNormal);
 
     // Calculate this vertex position in camera coordinates
-    vec4 position = ModelViewMatrix * vec4(VertexPosition, 1.0);
+    vec4 Position = ModelViewMatrix * vec4(VertexPosition, 1.0);
 
     // Calculate the direction vector from the vertex to the camera
     // The camera is at 0,0,0
-    vec3 camDir = normalize(-position.xyz);
+    vec3 camDir = normalize(-Position.xyz);
 
     // Calculates the vertex Ambient+Diffuse and Specular colors using the Phong model
     // for the front and back
-    phongModel(position,  normal, camDir, MatAmbientColor, MatDiffuseColor, ColorFrontAmbdiff, ColorFrontSpec);
-    phongModel(position, -normal, camDir, MatAmbientColor, MatDiffuseColor, ColorBackAmbdiff, ColorBackSpec);
+    phongModel(Position,  Normal, camDir, MatAmbientColor, MatDiffuseColor, ColorFrontAmbdiff, ColorFrontSpec);
+    phongModel(Position, -Normal, camDir, MatAmbientColor, MatDiffuseColor, ColorBackAmbdiff, ColorBackSpec);
 
     vec2 texcoord = VertexTexcoord;
 #if MAT_TEXTURES > 0
@@ -1213,8 +1239,10 @@ void main() {
     }
 #endif
     FragTexcoord = texcoord;
+    vec3 vPosition = VertexPosition;
+    #include <morphtarget_vertex> [MORPHTARGETS]
 
-    gl_Position = MVP * vec4(VertexPosition, 1.0);
+    gl_Position = MVP * vec4(vPosition, 1.0);
 }
 
 `
@@ -1222,10 +1250,13 @@ void main() {
 // Maps include name with its source code
 var includeMap = map[string]string{
 
-	"attributes":  include_attributes_source,
-	"lights":      include_lights_source,
-	"material":    include_material_source,
-	"phong_model": include_phong_model_source,
+	"attributes":                      include_attributes_source,
+	"lights":                          include_lights_source,
+	"material":                        include_material_source,
+	"morphtarget_vertex":              include_morphtarget_vertex_source,
+	"morphtarget_vertex_declaration":  include_morphtarget_vertex_declaration_source,
+	"morphtarget_vertex_declaration2": include_morphtarget_vertex_declaration2_source,
+	"phong_model":                     include_phong_model_source,
 }
 
 // Maps shader name with its source code

+ 9 - 7
renderer/shaders/standard_vertex.glsl

@@ -11,7 +11,7 @@ uniform mat4 MVP;
 #include <lights>
 #include <material>
 #include <phong_model>
-
+#include <morphtarget_vertex_declaration>
 
 // Outputs for the fragment shader.
 out vec3 ColorFrontAmbdiff;
@@ -23,19 +23,19 @@ out vec2 FragTexcoord;
 void main() {
 
     // Transform this vertex normal to camera coordinates.
-    vec3 normal = normalize(NormalMatrix * VertexNormal);
+    vec3 Normal = normalize(NormalMatrix * VertexNormal);
 
     // Calculate this vertex position in camera coordinates
-    vec4 position = ModelViewMatrix * vec4(VertexPosition, 1.0);
+    vec4 Position = ModelViewMatrix * vec4(VertexPosition, 1.0);
 
     // Calculate the direction vector from the vertex to the camera
     // The camera is at 0,0,0
-    vec3 camDir = normalize(-position.xyz);
+    vec3 camDir = normalize(-Position.xyz);
 
     // Calculates the vertex Ambient+Diffuse and Specular colors using the Phong model
     // for the front and back
-    phongModel(position,  normal, camDir, MatAmbientColor, MatDiffuseColor, ColorFrontAmbdiff, ColorFrontSpec);
-    phongModel(position, -normal, camDir, MatAmbientColor, MatDiffuseColor, ColorBackAmbdiff, ColorBackSpec);
+    phongModel(Position,  Normal, camDir, MatAmbientColor, MatDiffuseColor, ColorFrontAmbdiff, ColorFrontSpec);
+    phongModel(Position, -Normal, camDir, MatAmbientColor, MatDiffuseColor, ColorBackAmbdiff, ColorBackSpec);
 
     vec2 texcoord = VertexTexcoord;
 #if MAT_TEXTURES > 0
@@ -45,7 +45,9 @@ void main() {
     }
 #endif
     FragTexcoord = texcoord;
+    vec3 vPosition = VertexPosition;
+    #include <morphtarget_vertex> [MORPHTARGETS]
 
-    gl_Position = MVP * vec4(VertexPosition, 1.0);
+    gl_Position = MVP * vec4(vPosition, 1.0);
 }
 

+ 81 - 68
renderer/shaman.go

@@ -7,20 +7,23 @@ package renderer
 import (
 	"fmt"
 	"regexp"
-	"strconv"
 	"strings"
 
 	"github.com/g3n/engine/gls"
 	"github.com/g3n/engine/material"
 	"github.com/g3n/engine/renderer/shaders"
+	"strconv"
 )
 
-// Regular expression to parse #include <name> directive
+const GLSL_VERSION = "330 core"
+
+// Regular expression to parse #include <name> [quantity] directive
 var rexInclude *regexp.Regexp
+const indexParameter = "{i}"
 
 func init() {
 
-	rexInclude = regexp.MustCompile(`#include\s+<(.*)>`)
+	rexInclude = regexp.MustCompile(`#include\s+<(.*)>\s*(?:\[(.*)]|)`)
 }
 
 // ShaderSpecs describes the specification of a compiled shader program
@@ -34,7 +37,7 @@ type ShaderSpecs struct {
 	PointLightsMax   int                // Current Number of point lights
 	SpotLightsMax    int                // Current Number of spot lights
 	MatTexturesMax   int                // Current Number of material textures
-	Defines          map[string]string  // Additional shader defines
+	Defines          gls.ShaderDefines  // Additional shader defines
 }
 
 // ProgSpecs represents a compiled shader program along with its specs
@@ -115,7 +118,7 @@ func (sm *Shaman) AddProgram(name, vertexName, fragName string, others ...string
 	}
 }
 
-// SetProgram set the shader program to satisfy the specified specs.
+// SetProgram sets the shader program to satisfy the specified specs.
 // Returns an indication if the current shader has changed and a possible error
 // when creating a new shader program.
 // Receives a copy of the specs because it changes the fields which specify the
@@ -139,13 +142,13 @@ func (sm *Shaman) SetProgram(s *ShaderSpecs) (bool, error) {
 	}
 
 	// If current shader specs are the same as the specified specs, nothing to do.
-	if sm.specs.compare(&specs) {
+	if sm.specs.equals(&specs) {
 		return false, nil
 	}
 
 	// Search for compiled program with the specified specs
 	for _, pinfo := range sm.programs {
-		if pinfo.specs.compare(&specs) {
+		if pinfo.specs.equals(&specs) {
 			sm.gs.UseProgram(pinfo.program)
 			sm.specs = specs
 			return true, nil
@@ -177,13 +180,13 @@ func (sm *Shaman) GenProgram(specs *ShaderSpecs) (*gls.Program, error) {
 
 	// Sets the defines map
 	defines := map[string]string{}
-	defines["GLSL_VERSION"] = "330 core"
-	defines["AMB_LIGHTS"] = strconv.FormatUint(uint64(specs.AmbientLightsMax), 10)
-	defines["DIR_LIGHTS"] = strconv.FormatUint(uint64(specs.DirLightsMax), 10)
-	defines["POINT_LIGHTS"] = strconv.FormatUint(uint64(specs.PointLightsMax), 10)
-	defines["SPOT_LIGHTS"] = strconv.FormatUint(uint64(specs.SpotLightsMax), 10)
-	defines["MAT_TEXTURES"] = strconv.FormatUint(uint64(specs.MatTexturesMax), 10)
-	// Adds additional material defines from the specs parameter
+	defines["AMB_LIGHTS"] = strconv.Itoa(specs.AmbientLightsMax)
+	defines["DIR_LIGHTS"] = strconv.Itoa(specs.DirLightsMax)
+	defines["POINT_LIGHTS"] = strconv.Itoa(specs.PointLightsMax)
+	defines["SPOT_LIGHTS"] = strconv.Itoa(specs.SpotLightsMax)
+	defines["MAT_TEXTURES"] = strconv.Itoa(specs.MatTexturesMax)
+
+	// Adds additional material and geometry defines from the specs parameter
 	for name, value := range specs.Defines {
 		defines[name] = value
 	}
@@ -193,7 +196,7 @@ func (sm *Shaman) GenProgram(specs *ShaderSpecs) (*gls.Program, error) {
 	if !ok {
 		return nil, fmt.Errorf("Vertex shader:%s not found", progInfo.Vertex)
 	}
-	// Preprocess vertex shader source
+	// Pre-process vertex shader source
 	vertexSource, err := sm.preprocess(vertexSource, defines)
 	if err != nil {
 		return nil, err
@@ -205,7 +208,7 @@ func (sm *Shaman) GenProgram(specs *ShaderSpecs) (*gls.Program, error) {
 	if err != nil {
 		return nil, fmt.Errorf("Fragment shader:%s not found", progInfo.Fragment)
 	}
-	// Preprocess fragment shader source
+	// Pre-process fragment shader source
 	fragSource, err = sm.preprocess(fragSource, defines)
 	if err != nil {
 		return nil, err
@@ -220,7 +223,7 @@ func (sm *Shaman) GenProgram(specs *ShaderSpecs) (*gls.Program, error) {
 		if !ok {
 			return nil, fmt.Errorf("Geometry shader:%s not found", progInfo.Geometry)
 		}
-		// Preprocess geometry shader source
+		// Pre-process geometry shader source
 		geomSource, err = sm.preprocess(geomSource, defines)
 		if err != nil {
 			return nil, err
@@ -229,10 +232,10 @@ func (sm *Shaman) GenProgram(specs *ShaderSpecs) (*gls.Program, error) {
 
 	// Creates shader program
 	prog := sm.gs.NewProgram()
-	prog.AddShader(gls.VERTEX_SHADER, vertexSource, nil)
-	prog.AddShader(gls.FRAGMENT_SHADER, fragSource, nil)
+	prog.AddShader(gls.VERTEX_SHADER, vertexSource)
+	prog.AddShader(gls.FRAGMENT_SHADER, fragSource)
 	if progInfo.Geometry != "" {
-		prog.AddShader(gls.GEOMETRY_SHADER, geomSource, nil)
+		prog.AddShader(gls.GEOMETRY_SHADER, geomSource)
 	}
 	err = prog.Build()
 	if err != nil {
@@ -242,48 +245,83 @@ func (sm *Shaman) GenProgram(specs *ShaderSpecs) (*gls.Program, error) {
 	return prog, nil
 }
 
-// preprocess preprocesses the specified source prefixing it with optional defines directives
-// contained in "defines" parameter and replaces '#include <name>' directives
-// by the respective source code of include chunk of the specified name.
-// The included "files" are also processed recursively.
+
 func (sm *Shaman) preprocess(source string, defines map[string]string) (string, error) {
 
-	// If defines map supplied, generates prefix with glsl version directive first,
-	// followed by "#define directives"
+	// If defines map supplied, generate prefix with glsl version directive first,
+	// followed by "#define" directives
 	var prefix = ""
-	if defines != nil {
-		prefix = fmt.Sprintf("#version %s\n", defines["GLSL_VERSION"])
+	if defines != nil { // This is only true for the outer call
+		prefix = fmt.Sprintf("#version %s\n", GLSL_VERSION)
 		for name, value := range defines {
-			if name == "GLSL_VERSION" {
-				continue
-			}
 			prefix = prefix + fmt.Sprintf("#define %s %s\n", name, value)
 		}
 	}
 
+	return sm.processIncludes(prefix + source, defines)
+}
+
+
+// preprocess preprocesses the specified source prefixing it with optional defines directives
+// contained in "defines" parameter and replaces '#include <name>' directives
+// by the respective source code of include chunk of the specified name.
+// The included "files" are also processed recursively.
+func (sm *Shaman) processIncludes(source string, defines map[string]string) (string, error) {
+
 	// Find all string submatches for the "#include <name>" directive
 	matches := rexInclude.FindAllStringSubmatch(source, 100)
 	if len(matches) == 0 {
-		return prefix + source, nil
+		return source, nil
 	}
 
 	// For each directive found, replace the name by the respective include chunk source code
-	var newSource = source
+	//var newSource = source
 	for _, m := range matches {
+		incFullMatch := m[0]
+		incName := m[1]
+		incQuantityVariable := m[2]
+
 		// Get the source of the include chunk with the match <name>
-		incSource := sm.includes[m[1]]
+		incSource := sm.includes[incName]
 		if len(incSource) == 0 {
-			return "", fmt.Errorf("Include:[%s] not found", m[1])
+			return "", fmt.Errorf("Include:[%s] not found", incName)
 		}
+
 		// Preprocess the include chunk source code
-		incSource, err := sm.preprocess(incSource, nil)
+		incSource, err := sm.processIncludes(incSource, defines)
 		if err != nil {
 			return "", err
 		}
+
+		// Skip line
+		incSource = "\n" + incSource
+
+		// Process include quantity variable if provided
+		if incQuantityVariable != "" {
+			incQuantityString, defined := defines[incQuantityVariable]
+			if defined { // Only process #include if quantity variable is defined
+				incQuantity, err := strconv.Atoi(incQuantityString)
+				if err != nil {
+					return "", err
+				}
+				// Check for iterated includes and populate index parameter
+				if incQuantity > 0 {
+					repeatedIncludeSource := ""
+					for i := 0; i < incQuantity; i++ {
+						// Replace all occurrences of the index parameter with the current index i.
+						repeatedIncludeSource += strings.Replace(incSource, indexParameter, strconv.Itoa(i), -1)
+					}
+					incSource = repeatedIncludeSource
+				}
+			} else {
+				incSource = ""
+			}
+		}
+
 		// Replace all occurrences of the include directive with its processed source code
-		newSource = strings.Replace(newSource, m[0], incSource, -1)
+		source = strings.Replace(source, incFullMatch, incSource, -1)
 	}
-	return prefix + newSource, nil
+	return source, nil
 }
 
 // copy copies other spec into this
@@ -291,15 +329,13 @@ func (ss *ShaderSpecs) copy(other *ShaderSpecs) {
 
 	*ss = *other
 	if other.Defines != nil {
-		ss.Defines = make(map[string]string)
-		for k, v := range other.Defines {
-			ss.Defines[k] = v
-		}
+		ss.Defines = *gls.NewShaderDefines()
+		ss.Defines.Add(&other.Defines)
 	}
 }
 
-// Compare compares two shaders specifications structures
-func (ss *ShaderSpecs) compare(other *ShaderSpecs) bool {
+// equals compares two ShaderSpecs and returns true if they are effectively equal.
+func (ss *ShaderSpecs) equals(other *ShaderSpecs) bool {
 
 	if ss.Name != other.Name {
 		return false
@@ -312,31 +348,8 @@ func (ss *ShaderSpecs) compare(other *ShaderSpecs) bool {
 		ss.PointLightsMax == other.PointLightsMax &&
 		ss.SpotLightsMax == other.SpotLightsMax &&
 		ss.MatTexturesMax == other.MatTexturesMax &&
-		ss.compareDefines(other) {
-		return true
-	}
-	return false
-}
-
-// compareDefines compares two shaders specification define maps.
-func (ss *ShaderSpecs) compareDefines(other *ShaderSpecs) bool {
-
-	if ss.Defines == nil && other.Defines == nil {
-		return true
-	}
-	if ss.Defines != nil && other.Defines != nil {
-		if len(ss.Defines) != len(other.Defines) {
-			return false
-		}
-		for k := range ss.Defines {
-			v1, ok1 := ss.Defines[k]
-			v2, ok2 := other.Defines[k]
-			if v1 != v2 || ok1 != ok2 {
-				return false
-			}
-		}
+		ss.Defines.Equals(&other.Defines) {
 		return true
 	}
-	// One is nil and the other is not nil
 	return false
 }

+ 3 - 3
window/glfw.go

@@ -64,9 +64,9 @@ func Glfw() (IWindowManager, error) {
 	glfw.WindowHint(glfw.OpenGLProfile, glfw.OpenGLCoreProfile)
 	glfw.WindowHint(glfw.Samples, 8)
 	// Sets OpenGL forward compatible context only for OSX because it is required for OSX.
-	// When this is set glLineWidth(width) only accepts width=1.0 and generates error
-	// for any other values although the spec says it should ignore non supported widths
-	// and generate error only when width <= 0.
+	// When this is set, glLineWidth(width) only accepts width=1.0 and generates an  error
+	// for any other values although the spec says it should ignore unsupported widths
+	// and generate an error only when width <= 0.
 	if runtime.GOOS == "darwin" {
 		glfw.WindowHint(glfw.OpenGLForwardCompatible, glfw.True)
 	}