From 92e7a93d8c1475bdc802d10a1722bcf8a295449d Mon Sep 17 00:00:00 2001
From: 3gg <3gg@shellblade.net>
Date: Tue, 24 Dec 2024 12:07:05 -0800
Subject: New physics module.

---
 Demos/Pong/Pong.hs          | 101 +++++++++++++++++++++--------------
 Spear.cabal                 |   2 +
 Spear/Math/Physics/Rigid.hs | 125 --------------------------------------------
 Spear/Math/Physics/Types.hs |  11 ----
 Spear/Physics/Collision.hs  |  63 ++++++++++++++++++++++
 Spear/Physics/RigidBody.hs  |  77 +++++++++++++++++++++++++++
 6 files changed, 203 insertions(+), 176 deletions(-)
 delete mode 100644 Spear/Math/Physics/Rigid.hs
 delete mode 100644 Spear/Math/Physics/Types.hs
 create mode 100644 Spear/Physics/Collision.hs
 create mode 100644 Spear/Physics/RigidBody.hs

diff --git a/Demos/Pong/Pong.hs b/Demos/Pong/Pong.hs
index b9661ee..b12f792 100644
--- a/Demos/Pong/Pong.hs
+++ b/Demos/Pong/Pong.hs
@@ -16,10 +16,11 @@ import           Spear.Math.Algebra
 import           Spear.Math.Spatial
 import           Spear.Math.Spatial2
 import           Spear.Math.Vector
+import           Spear.Physics.Collision
 import           Spear.Prelude
 import           Spear.Step
 
-import           Data.Monoid         (mconcat)
+import           Data.Monoid             (mconcat)
 
 
 -- Configuration
@@ -41,14 +42,22 @@ initialBallPos      = vec2 0.5 0.5
 data GameEvent
   = MoveLeft
   | MoveRight
-  deriving (Eq, Ord, Show)
+  | Collision GameObjectId GameObjectId
+  deriving (Eq, Show)
 
 -- Game objects
 
+data GameObjectId
+  = Ball
+  | Enemy
+  | Player
+  deriving (Eq, Show)
+
 data GameObject = GameObject
-  { aabb   :: AABB2,
-    basis  :: Transform2,
-    gostep :: Step [GameObject] [GameEvent] GameObject GameObject
+  { gameObjectId :: !GameObjectId
+  , aabb         :: {-# UNPACK #-} !AABB2
+  , basis        :: {-# UNPACK #-} !Transform2
+  , gostep       :: Step [GameObject] [GameEvent] GameObject GameObject
   }
 
 
@@ -78,46 +87,68 @@ instance Spatial GameObject Vector2 Angle Transform2 where
   transform = basis
 
 
+instance Bounded2 GameObject where
+  boundingVolume obj = aabb2Volume $ translate (position obj) (aabb obj)
+
+
 ballBox, padBox :: AABB2
 ballBox = AABB2 (vec2 (-s) (-s)) (vec2 s s) where s = ballSize
 padBox  = AABB2 (-padSize) padSize
 
 newWorld =
-  [ GameObject ballBox (makeAt initialBallPos) $ stepBall initialBallVelocity,
-    GameObject padBox  (makeAt initialEnemyPos)  stepEnemy,
-    GameObject padBox  (makeAt initialPlayerPos) stepPlayer
+  [ GameObject Ball   ballBox (makeAt initialBallPos) $ stepBall initialBallVelocity,
+    GameObject Enemy  padBox  (makeAt initialEnemyPos)  stepEnemy,
+    GameObject Player padBox  (makeAt initialPlayerPos) stepPlayer
   ]
   where makeAt = newTransform2 unitx2 unity2
 
 
+-- Step the game world:
+--   1. Simulate physics.
+--   2. Collide objects and clip -> produce collision events.
+--   3. Update game objects      <- input collision events.
 stepWorld :: Elapsed -> Dt -> [GameEvent] -> [GameObject] -> [GameObject]
-stepWorld elapsed dt evts gos = map (update elapsed dt evts gos) gos
+stepWorld elapsed dt events gos@[ball, enemy, player] =
+  let
+    collisions = collide [ball] [enemy, player]
+    collisionEvents = (\(x,y) -> Collision (gameObjectId x) (gameObjectId y)) <$> collisions
+    events' = events ++ collisionEvents
+    gos' = map (update elapsed dt events' gos) gos
+  in
+    gos'
 
 update :: Elapsed -> Dt -> [GameEvent] -> [GameObject] -> GameObject -> GameObject
-update elapsed dt evts gos go =
-  let (go', s') = runStep (gostep go) elapsed dt gos evts go
-   in go' {gostep = s'}
+update elapsed dt events gos go =
+  let (go', s') = runStep (gostep go) elapsed dt gos events go
+   in go' { gostep = s' }
+
 
 -- Ball steppers
 
-stepBall vel = collideBall vel .> moveBall
+stepBall vel = bounceBall vel .> moveBall
 
-collideBall :: Vector2 -> Step [GameObject] e GameObject (Vector2, GameObject)
-collideBall vel = step $ \_ dt gos _ ball ->
+bounceBall :: Vector2 -> Step [GameObject] [GameEvent] GameObject (Vector2, GameObject)
+bounceBall vel = step $ \_ dt gos events ball ->
   let (AABB2 pmin pmax) = translate (position ball) (aabb ball)
       sideCollision = x pmin < 0 || x pmax > 1
       backCollision = y pmin < 0 || y pmax > 1
       flipX v@(Vector2 x y) = if sideCollision then vec2 (-x) y else v
       flipY v@(Vector2 x y) = if backCollision then vec2 x (-y) else v
-      vel' = normalise . (\v -> foldl (paddleBounce ball) v (tail gos)) . flipX . flipY $ vel
+      collideWithPaddles vel = foldl (paddleBounce ball events) vel (tail gos)
+      vel' = normalise
+           . collideWithPaddles
+           . flipX
+           . flipY
+           $ vel
       collision = vel' /= vel
       -- Apply offset when collision occurs to avoid sticky collisions.
       delta = (1::Float) + if collision then (3::Float)*dt else (0::Float)
-   in ((ballSpeed * delta * vel', ball), collideBall vel')
+   in ((ballSpeed * delta * vel', ball), bounceBall vel')
 
-paddleBounce :: GameObject -> Vector2 -> GameObject -> Vector2
-paddleBounce ball v paddle =
-  if collide ball paddle
+paddleBounce :: GameObject -> [GameEvent] -> Vector2 -> GameObject -> Vector2
+paddleBounce ball events vel paddle =
+  let collision = Collision Ball (gameObjectId paddle) `elem` events
+  in if collision
   then
     let (AABB2 pmin pmax) = translate (position paddle) (aabb paddle)
         center = (x pmin + x pmax) / (2::Float)
@@ -126,25 +157,14 @@ paddleBounce ball v paddle =
         offset = (x (position ball) - center) / ((x pmax - x pmin) / (2::Float))
         angle  = offset * maxBounceAngle
         -- When it bounces off of a paddle, y vel is flipped.
-        ysign = -(signum (y v))
+        ysign = -(signum (y vel))
     in vec2 (sin angle) (ysign * cos angle)
-  else v
-
-collide :: GameObject -> GameObject -> Bool
-collide go1 go2 =
-  let (AABB2 (Vector2 xmin1 ymin1) (Vector2 xmax1 ymax1)) =
-        translate (position go1) (aabb go1)
-      (AABB2 (Vector2 xmin2 ymin2) (Vector2 xmax2 ymax2)) =
-        translate (position go2) (aabb go2)
-   in not $
-       xmax1 < xmin2 ||
-       xmin1 > xmax2 ||
-       ymax1 < ymin2 ||
-       ymin1 > ymax2
+  else vel
 
 moveBall :: Step s e (Vector2, GameObject) GameObject
 moveBall = step $ \_ dt _ _ (vel, ball) -> (translate (vel * dt) ball, moveBall)
 
+
 -- Enemy stepper
 
 stepEnemy = movePad 0 .> clamp
@@ -161,17 +181,18 @@ movePad previousMomentumVector = step $ \_ dt gos _ pad ->
 sign :: Float -> Float
 sign x = if x >= 0 then 1 else -1
 
+
 -- Player stepper
 
-stepPlayer = sfold moveGO .> clamp
+stepPlayer = sfold movePlayer .> clamp
 
-moveGO = mconcat
-  [ swhen MoveLeft  $ moveGO' (vec2 (-playerSpeed) 0)
-  , swhen MoveRight $ moveGO' (vec2   playerSpeed  0)
+movePlayer = mconcat
+  [ swhen MoveLeft  $ movePlayer' (vec2 (-playerSpeed) 0)
+  , swhen MoveRight $ movePlayer' (vec2   playerSpeed  0)
   ]
 
-moveGO' :: Vector2 -> Step s e GameObject GameObject
-moveGO' dir = step $ \_ dt _ _ go -> (translate (dir * dt) go, moveGO' dir)
+movePlayer' :: Vector2 -> Step s e GameObject GameObject
+movePlayer' dir = step $ \_ dt _ _ go -> (translate (dir * dt) go, movePlayer' dir)
 
 clamp :: Step s e GameObject GameObject
 clamp = spure $ \go ->
diff --git a/Spear.cabal b/Spear.cabal
index 8ccc628..306ef6a 100644
--- a/Spear.cabal
+++ b/Spear.cabal
@@ -62,6 +62,8 @@ library
       Spear.Math.Vector.Vector2
       Spear.Math.Vector.Vector3
       Spear.Math.Vector.Vector4
+      Spear.Physics.Collision
+      Spear.Physics.RigidBody
       Spear.Prelude
       Spear.Render.AnimatedModel
       Spear.Render.Core
diff --git a/Spear/Math/Physics/Rigid.hs b/Spear/Math/Physics/Rigid.hs
deleted file mode 100644
index 28995bd..0000000
--- a/Spear/Math/Physics/Rigid.hs
+++ /dev/null
@@ -1,125 +0,0 @@
-module Spear.Math.Physics.Rigid
-(
-    module Spear.Math.Physics.Types
-,   RigidBody(..)
-,   rigidBody
-,   update
-,   setVelocity
-,   setAcceleration
-)
-where
-
-import qualified Spear.Math.Matrix3 as M3
-import Spear.Math.Spatial2
-import Spear.Math.Vector
-import Spear.Physics.Types
-
-import Data.List (foldl')
-import Control.Monad.State
-
-data RigidBody = RigidBody
-    { mass         :: {-# UNPACK #-} !Float
-    , position     :: {-# UNPACK #-} !Position
-    , velocity     :: {-# UNPACK #-} !Velocity
-    , acceleration :: {-# UNPACK #-} !Acceleration
-    }
-
-instance Spatial2 RigidBody where
-
-    move v body = body { position = v + position body }
-
-    moveFwd     speed body = body { position = position body + scale speed unity2 }
-
-    moveBack    speed body = body { position = position body + scale (-speed) unity2 }
-
-    strafeLeft  speed body = body { position = position body + scale (-speed) unitx2 }
-
-    strafeRight speed body = body { position = position body + scale speed unitx2 }
-
-    rotate angle = id
-
-    setRotation angle = id
-
-    pos = position
-
-    fwd _ = unity2
-
-    up _ = unity2
-
-    right _ = unitx2
-
-    transform body = M3.transform unitx2 unity2 $ position body
-
-    setTransform transf body = body { position = M3.position transf }
-
-    setPos p body = body { position = p }
-
--- | Build a 'RigidBody'.
-rigidBody :: Mass -> Position -> RigidBody
-rigidBody m x = RigidBody m x zero2 zero2
-
--- | Update the given 'RigidBody'.
-update :: [Force] -> Dt -> RigidBody -> RigidBody
-update forces dt body =
-    let netforce = foldl' (+) zero2 forces
-        m  = mass body
-        r1 = position body
-        v1 = velocity body
-        a1 = acceleration body
-        r2 = r1 + scale dt v1 + scale (0.5*dt*dt) a1
-        v' = v1 + scale (0.5*dt) a1
-        a2 = a1 + scale (1/m) netforce
-        v2 = v1 + scale (dt/2) (a2+a1) + scale (0.5*dt) a2
-    in
-        RigidBody m r2 v2 a2
-
--- | Set the body's velocity.
-setVelocity :: Velocity -> RigidBody -> RigidBody
-setVelocity v body = body { velocity = v }
-
--- | Set the body's acceleration.
-setAcceleration :: Acceleration -> RigidBody -> RigidBody
-setAcceleration a body = body { acceleration = a }
-
-
--- test
-{-gravity = vec2 0 (-10)
-b0 = rigidBody 50 $ vec2 0 1000
-
-
-debug :: IO ()
-debug = evalStateT debug' b0
-
-
-
-debug' :: StateT RigidBody IO ()
-debug' = do
-    lift . putStrLn $ "Initial body:"
-    lift . putStrLn . show' $ b0
-    lift . putStrLn $ "Falling..."
-    step $ update [gravity*50] 1
-    step $ update [gravity*50] 1
-    step $ update [gravity*50] 1
-    lift . putStrLn $ "Jumping"
-    step $ update [gravity*50, vec2 0 9000] 1
-    lift . putStrLn $ "Falling..."
-    step $ update [gravity*50] 1
-    step $ update [gravity*50] 1
-    step $ update [gravity*50] 1
-
-
-step :: (RigidBody -> RigidBody) -> StateT RigidBody IO ()
-step update = do
-    modify update
-    body <- get
-    lift . putStrLn . show' $ body
-
-
-show' body =
-    "mass " ++ (show $ mass body) ++
-    ", position " ++ (showVec $ position body) ++
-    ", velocity " ++ (showVec $ velocity body) ++
-    ", acceleration " ++ (showVec $ acceleration body)
-
-
-showVec v = (show $ x v) ++ ", " ++ (show $ y v)-}
diff --git a/Spear/Math/Physics/Types.hs b/Spear/Math/Physics/Types.hs
deleted file mode 100644
index 59e6c74..0000000
--- a/Spear/Math/Physics/Types.hs
+++ /dev/null
@@ -1,11 +0,0 @@
-module Spear.Math.Physics.Types
-where
-
-import Spear.Math.Vector
-
-type Dt = Float
-type Force = Vector2
-type Mass = Float
-type Position = Vector2
-type Velocity = Vector2
-type Acceleration = Vector2
diff --git a/Spear/Physics/Collision.hs b/Spear/Physics/Collision.hs
new file mode 100644
index 0000000..9ade9ca
--- /dev/null
+++ b/Spear/Physics/Collision.hs
@@ -0,0 +1,63 @@
+{-# LANGUAGE FlexibleContexts      #-}
+{-# LANGUAGE MultiParamTypeClasses #-}
+{-# LANGUAGE NoImplicitPrelude     #-}
+{-# LANGUAGE TypeSynonymInstances  #-}
+
+module Spear.Physics.Collision
+(
+  BoundingVolume2(..)
+, Bounded2(..)
+, aabb2Volume
+, collide
+)
+where
+
+import           Spear.Math.AABB
+import           Spear.Math.Spatial
+import           Spear.Math.Spatial2
+import           Spear.Math.Vector
+import           Spear.Prelude
+
+import           Data.Maybe          (mapMaybe)
+
+
+-- Currently supporting AABB2. Add circles later when needed.
+data BoundingVolume2
+  = AABB2Volume { box2 :: {-# UNPACK #-} !AABB2 }
+
+
+class Bounded2 a where
+  boundingVolume :: a -> BoundingVolume2
+
+
+-- | Construct a new bounding volume from a 2D axis-aligned box.
+aabb2Volume :: AABB2 -> BoundingVolume2
+aabb2Volume = AABB2Volume
+
+
+-- | Find collisions between the objects in the first list and the objects in
+-- the second list.
+collide :: Bounded2 a => [a] -> [a] -> [(a,a)]
+collide xs ys =
+  mapMaybe testCollision pairs
+  where
+    testCollision [o1, o2] = if objectsCollide o1 o2 then Just (o1, o2) else Nothing
+    pairs = sequence [xs, ys]
+
+
+-- | Test two objects for collision.
+objectsCollide :: Bounded2 a => a -> a -> Bool
+objectsCollide o1 o2 =
+  collideAABB2 (box2 . boundingVolume $ o1) (box2 . boundingVolume $ o2)
+
+
+-- | Test two 2D axis-aligned bounding boxes for collision.
+collideAABB2 :: AABB2 -> AABB2 -> Bool
+collideAABB2 box1 box2 =
+  let (AABB2 (Vector2 xmin1 ymin1) (Vector2 xmax1 ymax1)) = box1
+      (AABB2 (Vector2 xmin2 ymin2) (Vector2 xmax2 ymax2)) = box2
+  in not $
+    xmax1 < xmin2 ||
+    xmin1 > xmax2 ||
+    ymax1 < ymin2 ||
+    ymin1 > ymax2
diff --git a/Spear/Physics/RigidBody.hs b/Spear/Physics/RigidBody.hs
new file mode 100644
index 0000000..1a8fe0a
--- /dev/null
+++ b/Spear/Physics/RigidBody.hs
@@ -0,0 +1,77 @@
+{-# LANGUAGE FlexibleContexts      #-}
+{-# LANGUAGE MultiParamTypeClasses #-}
+{-# LANGUAGE NoImplicitPrelude     #-}
+{-# LANGUAGE TypeSynonymInstances  #-}
+
+module Spear.Physics.RigidBody
+(
+  RigidBody2
+, rigidBody
+, setVelocity
+, setAcceleration
+, update
+)
+where
+
+import           Spear.Math.Spatial
+import           Spear.Math.Spatial2
+import           Spear.Math.Vector
+import           Spear.Prelude
+
+import           Control.Monad.State
+import           Data.List           (foldl')
+
+
+type Dt = Float
+type Force = Vector2
+type Mass = Float
+type Position = Vector2
+type Velocity = Vector2
+type Acceleration = Vector2
+
+
+{- class RigidBody2 a where
+  bodyMass         :: a -> Float
+  bodyPosition     :: a -> Vector2
+  bodyVelocity     :: a -> Vector2
+  bodyAcceleration :: a -> Vector2 -}
+
+
+data RigidBody2 = RigidBody2
+    { bodyMass         :: {-# UNPACK #-} !Float
+    , bodyPosition     :: {-# UNPACK #-} !Position
+    , bodyVelocity     :: {-# UNPACK #-} !Velocity
+    , bodyAcceleration :: {-# UNPACK #-} !Acceleration
+    }
+
+
+instance Positional RigidBody2 Vector2 where
+  setPosition p body = body { bodyPosition = p }
+  position = bodyPosition
+  translate v body = body { bodyPosition = bodyPosition body + v }
+
+
+-- | Build a 'RigidBody'.
+rigidBody :: Mass -> Position -> RigidBody2
+rigidBody mass position = RigidBody2 mass position zero2 zero2
+
+
+-- | Set the body's velocity.
+setVelocity :: Velocity -> RigidBody2 -> RigidBody2
+setVelocity velocity body = body { bodyVelocity = velocity }
+
+
+-- | Set the body's acceleration.
+setAcceleration :: Acceleration -> RigidBody2 -> RigidBody2
+setAcceleration acceleration body = body { bodyAcceleration = acceleration }
+
+
+-- | Update the given 'RigidBody'.
+update :: [Force] -> Dt -> RigidBody2 -> RigidBody2
+update forces dt body@(RigidBody2 m p v a) =
+    let f = foldl' (+) zero2 forces
+        a' = a + (f / m)
+        v' = v + (a' * dt)
+        p' = p + (v' * dt)
+    in
+        RigidBody2 m p' v' a'
-- 
cgit v1.2.3