summaryrefslogtreecommitdiff
path: root/engine-ocean/Game/Systems/CollisionSystems
diff options
context:
space:
mode:
Diffstat (limited to 'engine-ocean/Game/Systems/CollisionSystems')
-rw-r--r--engine-ocean/Game/Systems/CollisionSystems/BVH/bvhtree.cpp234
-rw-r--r--engine-ocean/Game/Systems/CollisionSystems/BVH/bvhtree.h106
-rw-r--r--engine-ocean/Game/Systems/CollisionSystems/UniformGrid/uniformgrid.cpp127
-rw-r--r--engine-ocean/Game/Systems/CollisionSystems/UniformGrid/uniformgrid.h67
-rw-r--r--engine-ocean/Game/Systems/CollisionSystems/accelerationsystem.cpp6
-rw-r--r--engine-ocean/Game/Systems/CollisionSystems/accelerationsystem.h11
-rw-r--r--engine-ocean/Game/Systems/CollisionSystems/collisionsystem.cpp183
-rw-r--r--engine-ocean/Game/Systems/CollisionSystems/collisionsystem.h53
-rw-r--r--engine-ocean/Game/Systems/CollisionSystems/ellipsoidtrianglecollisionsystem.cpp370
-rw-r--r--engine-ocean/Game/Systems/CollisionSystems/ellipsoidtrianglecollisionsystem.h69
-rw-r--r--engine-ocean/Game/Systems/CollisionSystems/environmentcollisiondetectionsystem.cpp93
-rw-r--r--engine-ocean/Game/Systems/CollisionSystems/environmentcollisiondetectionsystem.h43
12 files changed, 1362 insertions, 0 deletions
diff --git a/engine-ocean/Game/Systems/CollisionSystems/BVH/bvhtree.cpp b/engine-ocean/Game/Systems/CollisionSystems/BVH/bvhtree.cpp
new file mode 100644
index 0000000..46155bc
--- /dev/null
+++ b/engine-ocean/Game/Systems/CollisionSystems/BVH/bvhtree.cpp
@@ -0,0 +1,234 @@
+#include "bvhtree.h"
+#include "Game/Components/CollisionComponents/CollisionComponent.h"
+#include "Game/Components/CollisionComponents/boundingtriangle.h"
+#include "Game/GameObjects/GameObject.h"
+#include "Game/Systems/CollisionSystems/ellipsoidtrianglecollisionsystem.h"
+#include <map>
+
+BVHTree::BVHTree(std::map<std::string, std::shared_ptr<GameObject>>& rigid_gameobjects) :
+ m_rigid_gameobjects(rigid_gameobjects)
+{
+ initializePrimitiveInfo();
+ buildBVH();
+ BVHNode one = m_bvhNodes[0];
+ BVHNode two = m_bvhNodes[1];
+ BVHNode three = m_bvhNodes[2];
+
+
+ std::cout << "primitives size: " << m_primitives.size() << std::endl;
+}
+
+// populate primitive info vector -> primitives = triangles
+void BVHTree::initializePrimitiveInfo(){
+ for (const auto &go : m_rigid_gameobjects){
+ N += go.second->getComponent<CollisionComponent>()->getCollisionShape<BoundingTriangle>()->getTriangleData().size();
+ for (const Triangle &tri : go.second->getComponent<CollisionComponent>()->getCollisionShape<BoundingTriangle>()->getTriangleData()){
+ // the order might not be accurate....
+ BVHPrimitive prim = {tri};
+ //std::cout << "centroid: (" << prim.centroid.x << ", " << prim.centroid.y << ", " << prim.centroid.z << ")" << std::endl;
+
+ m_primitives.push_back(prim);
+
+ }
+ }
+}
+
+void BVHTree::buildBVH(){
+ // initialize array of primitive indices
+ m_primitive_indices = new int[N];
+ for (int i=0; i<N; i++){
+ m_primitive_indices[i] = i;
+ }
+
+ m_bvhNodes = new BVHNode[N*2 - 1];
+ int rootNodeID = 0;
+ m_nodesUsed = 1;
+
+ // assign all primitives to root node
+ BVHNode& root = m_bvhNodes[0];
+ root.leftNode = 0;
+ root.firstPrimitiveIndex = 0;
+ root.primitiveCount = N;
+
+ updateNodeBounds(rootNodeID);
+ // subdivide recursively
+ subdivide(rootNodeID);
+}
+
+void BVHTree::updateNodeBounds(int nodeIndex){
+ BVHNode& node = m_bvhNodes[nodeIndex];
+ node.bounds.max = glm::vec3(-INFINITY);
+ node.bounds.min = glm::vec3(INFINITY);
+
+ for (int first = node.firstPrimitiveIndex, i=0; i<node.primitiveCount; i++){
+ int leafIndex = m_primitive_indices[first + i];
+ BVHPrimitive& leafPrimitive = m_primitives[leafIndex];
+ // update node bounds with the most max and most min coordinates
+ node.bounds = getNodeBounds<Bounds3f>(node.bounds, leafPrimitive.bounds);
+ }
+}
+
+void BVHTree::subdivide(int nodeIndex){
+ BVHNode& node = m_bvhNodes[nodeIndex];
+ // terminate recursion
+
+
+ if (node.primitiveCount <= 1) return;
+
+ // otherwise determine split axis and position
+// // SAHH HEREEEEE
+// int bestAxis = 0;
+// float bestPos = 0;
+// float bestCost = INFINITY;
+// for (int axis=0; axis<3; axis++){
+// for (int i=0; i<node.primitiveCount; i++){
+// BVHPrimitive& primitive = m_primitives[m_primitive_indices[node.firstPrimitiveIndex + i]];
+// float candidatePos = primitive.centroid[axis];
+// float cost = evaluateSAH(node, axis, candidatePos);
+// if (cost < bestCost){
+// bestPos = candidatePos;
+// bestAxis = axis;
+// bestCost = cost;
+// }
+
+// }
+// }
+
+// int axis = bestAxis;
+// float splitPos = bestPos;
+
+// glm::vec3 e = node.bounds.max - node.bounds.min;
+// float parentArea = (e.x*e.y) + (e.y*e.z) * (e.z*e.x);
+// float parentCost = node.primitiveCount*parentArea;
+// if (bestCost >= parentCost) return;
+
+ // longest axis split (temporary)
+ glm::vec3 extent = node.bounds.max - node.bounds.min;
+ int axis = 0; // initialize to be x axis
+ if (extent.y > extent.x) axis = 1;
+ if (extent.z > extent[axis]) axis = 2;
+ float splitPos = node.bounds.min[axis] + extent[axis] * 0.5f;
+
+ // in-place partition
+ int i = node.firstPrimitiveIndex;
+ int j = i + node.primitiveCount - 1;
+ while (i <= j){
+ // if to the left of split axis
+ if (m_primitives[m_primitive_indices[i]].centroid[axis] < splitPos){
+ i++;
+ } else {
+ std::swap(m_primitive_indices[i], m_primitive_indices[j--]);
+ }
+ }
+
+ // abort split if one of the sides is empty
+ int leftCount = i - node.firstPrimitiveIndex;
+ if (leftCount == 0 || leftCount == node.primitiveCount) return;
+
+ // create child nodes
+ int leftChildID = m_nodesUsed++;
+ int rightChildID = m_nodesUsed++;
+
+ // left child
+ m_bvhNodes[leftChildID].firstPrimitiveIndex = node.firstPrimitiveIndex;
+ m_bvhNodes[leftChildID].primitiveCount = leftCount;
+
+ // right child
+ m_bvhNodes[rightChildID].firstPrimitiveIndex = i;
+ m_bvhNodes[rightChildID].primitiveCount = node.primitiveCount - leftCount;
+
+ node.leftNode = leftChildID;
+ node.primitiveCount = 0;
+
+ // recurse
+ updateNodeBounds(leftChildID);
+ updateNodeBounds(rightChildID);
+ subdivide(leftChildID);
+ subdivide(rightChildID);
+}
+
+float BVHTree::evaluateSAH(BVHNode& node, int axis, float pos){
+ BVHaabb leftBox, rightBox;
+ leftBox.bounds.min = glm::vec3(INFINITY), rightBox.bounds.min = glm::vec3(INFINITY);
+ leftBox.bounds.max = glm::vec3(-INFINITY), rightBox.bounds.max = glm::vec3(-INFINITY);
+
+ int leftCount = 0, rightCount = 0;
+ for (int i=0; i<node.primitiveCount; i++){
+ BVHPrimitive& primitive = m_primitives[m_primitive_indices[node.firstPrimitiveIndex + i]];
+ if (primitive.centroid[axis] < pos){
+ leftCount++;
+ leftBox.grow(getNodeBounds_Point<Bounds3f>(leftBox.bounds, primitive.triangle.vertexA));
+ leftBox.grow(getNodeBounds_Point<Bounds3f>(leftBox.bounds, primitive.triangle.vertexB));
+ leftBox.grow(getNodeBounds_Point<Bounds3f>(leftBox.bounds, primitive.triangle.vertexC));
+ } else {
+ rightCount++;
+ rightBox.grow(getNodeBounds_Point<Bounds3f>(rightBox.bounds, primitive.triangle.vertexA));
+ rightBox.grow(getNodeBounds_Point<Bounds3f>(rightBox.bounds, primitive.triangle.vertexB));
+ rightBox.grow(getNodeBounds_Point<Bounds3f>(rightBox.bounds, primitive.triangle.vertexC));
+ }
+ }
+ float cost = leftCount * leftBox.area() + rightCount * rightBox.area();
+ return cost > 0 ? cost : INFINITY;
+}
+
+
+void BVHTree::intersectBVH(const glm::vec3 posA, const glm::vec3 posB, const int nodeIndex, std::vector<Triangle> &candidates, glm::vec3 ellip_R){
+ //std::cout << "-" << std::endl;
+
+ BVHNode& node = m_bvhNodes[nodeIndex];
+ if (!intersectsNode(posA, posB, node.bounds.min, node.bounds.max, ellip_R+glm::vec3(.001))){
+ return;
+ }
+ if (node.isLeaf()){
+ // intersect with primitives of the leaf
+ //std::cout << "candidate size: " << node.primitiveCount << std::endl;
+ for (int i=0; i<node.primitiveCount; i++){
+ Triangle triangle = m_primitives[m_primitive_indices[node.firstPrimitiveIndex + i]].triangle;
+// BVHPrimitive prim = m_primitives[m_primitive_indices[node.firstPrimitiveIndex + i]];
+
+// if (prim.centroid == glm::vec3(39.42457, 1.84954, -15.7088)){
+// std::cout << "found correct triangle" << std::endl;
+// }
+ //std::cout << "centroid: (" << prim.centroid.x << ", " << prim.centroid.y << ", " << prim.centroid.z << ")" << std::endl;
+ candidates.push_back(triangle);
+
+ }
+ } else {
+ // recurse
+ intersectBVH(posA, posB, node.leftNode, candidates, ellip_R);
+ intersectBVH(posA, posB, node.leftNode + 1, candidates, ellip_R);
+ }
+}
+
+std::vector<Triangle> BVHTree::getBVHDetectedCollisions(glm::vec3 posA, glm::vec3 posB, glm::vec3 ellip_R){
+ // keep recursing, starting at root node, and then return final result in candidate_obstacles
+ std::vector<Triangle> candidate_rigid_tri;
+ intersectBVH(posA, posB, 0, candidate_rigid_tri, ellip_R);
+ return candidate_rigid_tri;
+}
+
+// determines if movement ray intersects an AABB via the slab test
+bool BVHTree::intersectsNode(glm::vec3 posA, glm::vec3 posB, glm::vec3 min, glm::vec3 max, glm::vec3 ellip_R){
+ glm::vec3 object_min = glm::vec3(std::min(posA.x, posB.x), std::min(posA.y, posB.y), std::min(posA.z, posB.z));
+ glm::vec3 object_max = glm::vec3(std::max(posA.x, posB.x), std::max(posA.y, posB.y), std::max(posA.z, posB.z));
+ object_min -= ellip_R;
+ object_max += ellip_R;
+
+ bool x_int = object_max.x > min.x && object_min.x < max.x;
+ bool y_int = object_max.y > min.y && object_min.y < max.y;
+ bool z_int = object_max.z > min.z && object_min.z < max.z;
+
+ if (x_int && y_int && z_int){
+ return true;
+ }
+ return false;
+}
+
+BVHTree::~BVHTree(){
+ delete[] m_bvhNodes;
+ delete[] m_primitive_indices;
+ m_bvhNodes = NULL;
+ m_primitive_indices = NULL;
+
+}
+
diff --git a/engine-ocean/Game/Systems/CollisionSystems/BVH/bvhtree.h b/engine-ocean/Game/Systems/CollisionSystems/BVH/bvhtree.h
new file mode 100644
index 0000000..b175e44
--- /dev/null
+++ b/engine-ocean/Game/Systems/CollisionSystems/BVH/bvhtree.h
@@ -0,0 +1,106 @@
+#ifndef BVHTREE_H
+#define BVHTREE_H
+#include "Game/Components/CollisionComponents/BoundingTriangle.h"
+#include "Game/GameObjects/GameObject.h"
+#include "glm/glm.hpp"
+#include <map>
+#include <vector>
+
+// primitive = triangle
+struct BVHPrimitive{
+
+ Bounds3f bounds;
+ glm::vec3 centroid;
+ Triangle triangle;
+
+ BVHPrimitive(const Triangle &tri):
+ triangle(tri),
+ bounds(tri.bounds),
+ centroid(.333f*(tri.vertexA + tri.vertexB + tri.vertexC)){}
+};
+
+struct BVHNode{
+ // glm::vec3 aabbMin, aabbMax;
+ Bounds3f bounds;
+ int leftNode, firstPrimitiveIndex, primitiveCount;
+ bool isLeaf(){
+ return primitiveCount > 0;
+ }
+};
+
+struct BVHaabb {
+ Bounds3f bounds;
+
+
+ void grow(Bounds3f newbounds){
+ bounds.min = newbounds.min;
+ bounds.max = newbounds.max;
+ }
+
+ float area(){
+ glm::vec3 e = bounds.max-bounds.min;
+ return (e.x*e.y) + (e.y*e.z) * (e.z*e.x);
+ }
+};
+
+
+template <typename T> Bounds3f
+getNodeBounds(const Bounds3f &b1, const Bounds3f &b2){
+ Bounds3f bounds;
+ bounds.min = glm::vec3(std::min(b1.min.x, b2.min.x),
+ std::min(b1.min.y, b2.min.y),
+ std::min(b1.min.z, b2.min.z));
+ bounds.max = glm::vec3(std::max(b1.max.x, b2.max.x),
+ std::max(b1.max.y, b2.max.y),
+ std::max(b1.max.z, b2.max.z));
+ return bounds;
+}
+
+template <typename T> Bounds3f
+getNodeBounds_Point(const Bounds3f &b, const glm::vec3 &p){
+ Bounds3f bounds;
+ bounds.min = glm::vec3(std::min(b.min.x, p.x),
+ std::min(b.min.y, p.y),
+ std::min(b.min.z, p.z));
+ bounds.max = glm::vec3(std::max(b.max.x, p.x),
+ std::max(b.max.y, p.y),
+ std::max(b.max.z, p.z));
+ return bounds;
+}
+
+class BVHTree
+
+{
+ BVHNode *m_bvhNodes;
+ int *m_primitive_indices;
+public:
+ BVHTree(std::map<std::string, std::shared_ptr<GameObject>>& rigid_gameobjects);
+ ~BVHTree();
+ std::vector<Triangle> getBVHDetectedCollisions(glm::vec3 posA, glm::vec3 posB, glm::vec3 ellip_R);
+ void intersectBVH(glm::vec3 posA, glm::vec3 posB, const int nodeIndex, std::vector<Triangle> &candidates, glm::vec3 ellip_R);
+
+
+private:
+ float evaluateSAH(BVHNode& node, int axis, float pos);
+ void initializePrimitiveInfo();
+ void buildBVH();
+ void updateNodeBounds(int nodeIndex);
+ void subdivide(int nodeIndex);
+ bool intersectsNode(glm::vec3 posA, glm::vec3 posB, glm::vec3 min, glm::vec3 max, glm::vec3 ellip_R);
+
+
+ //std::unique_ptr<EllipsoidTriangleCollisionSystem> m_ellipsoid_triangle_collision_system;
+
+ std::vector<BVHPrimitive> m_primitives;
+ std::map<std::string, std::shared_ptr<GameObject>>& m_rigid_gameobjects;
+
+
+ //std::vector<BVHNode> m_bvhNodes;
+ //std::vector<int> m_primitive_indices;
+ int m_nodesUsed = 1;
+ int N = 0;
+
+ // std::pair<std::vector<CollisionData>, glm::vec3> m_detected_collisions;
+};
+
+#endif // BVHTREE_H
diff --git a/engine-ocean/Game/Systems/CollisionSystems/UniformGrid/uniformgrid.cpp b/engine-ocean/Game/Systems/CollisionSystems/UniformGrid/uniformgrid.cpp
new file mode 100644
index 0000000..822129b
--- /dev/null
+++ b/engine-ocean/Game/Systems/CollisionSystems/UniformGrid/uniformgrid.cpp
@@ -0,0 +1,127 @@
+#include "uniformgrid.h"
+#include "Game/Components/CollisionComponents/BoundingDynamicMesh.h"
+#include "Game/Components/CollisionComponents/BoundingTriangle.h"
+#include "Game/Components/CollisionComponents/CollisionComponent.h"
+#include "Game/Components/CollisionComponents/CylinderCollider.h"
+#include <algorithm>
+
+UniformGrid::UniformGrid(std::map<std::string, std::shared_ptr<GameObject>>& dynamic_gameobjects):
+ m_dynamic_gameobjects(dynamic_gameobjects)
+{
+ initializeGrid();
+}
+
+void UniformGrid::initializeGrid(){
+ // grid square: size it based on the largest entity
+
+ // set default square size to be same dimensions as player
+ m_square_dimensions = ceil(m_dynamic_gameobjects.at("player")->getComponent<CollisionComponent>()->getCollisionShape<BoundingDynamicMesh>()->getCylinder().aabbDimensions);
+
+
+ // find largest shape dimension in order to set grid square dimensions
+ for (const auto &go : m_dynamic_gameobjects){
+ if (go.second->hasComponent<CollisionComponent>()){
+ glm::vec3 shape_dimensions = go.second->getComponent<CollisionComponent>()->getCollisionShape<BoundingDynamicMesh>()->getCylinder().aabbDimensions;
+ // find the largest Bounds3f for a shape
+ if (glm::all(glm::greaterThan(shape_dimensions, m_square_dimensions))){
+ m_square_dimensions = ceil(shape_dimensions);
+ }
+ }
+ }
+
+ // initialize grid based on where entities are initially placed
+ for (const auto &go : m_dynamic_gameobjects){
+ updateUniformGrid(go);
+ }
+}
+
+std::string UniformGrid::vecToString(glm::vec3 v){
+ std::string square_bound = std::to_string(v.x) + std::to_string(v.y) + std::to_string(v.z);
+ return square_bound;
+}
+
+
+void UniformGrid::populateContainingCell(glm::vec3 bound_corner, std::string entity_id){
+ glm::vec3 factor = floor(bound_corner/m_square_dimensions);
+ glm::vec3 container_min = factor*m_square_dimensions;
+
+ for (auto &square : m_grid_map){
+ //if the containing square is already in map, then append entity id to its associate list
+ if (square.first == vecToString(container_min)){
+ m_grid_map.at(square.first).insert(entity_id);
+ return;
+ }
+ }
+ // if not yet in map, add to map
+ std::set<std::string> ids;
+ ids.insert(entity_id);
+ m_grid_map.insert(std::pair(vecToString(container_min), ids));
+}
+
+void UniformGrid::updateUniformGrid(const std::pair<std::string, std::shared_ptr<GameObject>> &go){
+ if (go.second->hasComponent<CollisionComponent>()){
+ Bounds3f shapeBounds = go.second->getComponent<CollisionComponent>()->getCollisionShape<BoundingDynamicMesh>()->getCylinder().bounds;
+ // if bounds min is within an interval of square dimensions, then occupy map with that entity
+ glm::vec3 shape_dimensions = go.second->getComponent<CollisionComponent>()->getCollisionShape<BoundingDynamicMesh>()->getCylinder().aabbDimensions;
+
+
+ // check all 6 aabb corners
+ float x_val = shapeBounds.min.x;
+ for (int x=0; x<2; x++){
+ float y_val = shapeBounds.min.y;
+ for (int y=0; y<2; y++){
+ float z_val = shapeBounds.min.z;
+ for (int z=0; z<2; z++){
+ glm::vec3 corner = glm::vec3(x_val,y_val,z_val);
+ populateContainingCell(corner, go.first);
+ z_val += shape_dimensions.z;
+ }
+ y_val += shape_dimensions.y;
+ }
+ x_val += shape_dimensions.x;
+ }
+ }
+}
+
+// only for entities that moved:
+void UniformGrid::moveEntityGridPosition(const std::pair<std::string, std::shared_ptr<GameObject>> &go){
+ // remove previous cells that entity occupied
+ for (auto &cell : m_grid_map){
+ cell.second.erase(go.first);
+ }
+
+ // if there are no more ids associated with that cell, remove it from map
+ for (auto cell = m_grid_map.cbegin(), next_i = cell; cell != m_grid_map.cend(); cell = next_i){
+ ++next_i;
+ if (cell->second.empty()){
+ m_grid_map.erase(cell);
+ }
+ }
+
+ // then update based on new pos
+ updateUniformGrid(go);
+}
+
+void UniformGrid::updateAllGrid(){
+ // initialize grid based on where entities are initially placed
+ for (const auto &go : m_dynamic_gameobjects){
+ moveEntityGridPosition(go);
+ }
+
+ //std::cout << "new ugrid size: " << m_grid_map.size() << std::endl;
+}
+
+std::set<std::set<std::string>> UniformGrid::detectPossibleCollisions(){
+ // store list of names of objects that are near e/o
+ // uses set there are no duplicate inner sets of the same objects
+ std::set<std::set<std::string>> candidate_collision_sets;
+
+ for (const auto &cell : m_grid_map){
+ if (cell.second.size() > 1){
+ candidate_collision_sets.insert(cell.second);
+ }
+ }
+
+ // then for each inner set, detect collisions between the contained objects
+ return candidate_collision_sets;
+}
diff --git a/engine-ocean/Game/Systems/CollisionSystems/UniformGrid/uniformgrid.h b/engine-ocean/Game/Systems/CollisionSystems/UniformGrid/uniformgrid.h
new file mode 100644
index 0000000..c4e5aaa
--- /dev/null
+++ b/engine-ocean/Game/Systems/CollisionSystems/UniformGrid/uniformgrid.h
@@ -0,0 +1,67 @@
+#ifndef UNIFORMGRID_H
+#define UNIFORMGRID_H
+
+
+#include "Game/Components/CollisionComponents/BoundingTriangle.h"
+#include "Game/GameObjects/GameObject.h"
+#include <set>
+#include <vector>
+
+struct GridSquare {
+ Bounds3f bounds;
+ glm::vec3 centroid = (bounds.max - bounds.min)/ 2.f;
+
+
+// bool operator<( const GridSquare & s ) const {
+// return glm::all(glm::lessThan(this->bounds.min,s.bounds.min)); // for example
+// }
+
+
+};
+
+//bool operator<(const GridSquare& l, const GridSquare& r)
+//{
+// return glm::all(glm::lessThan(l.bounds.min, r.bounds.min));
+//}
+
+//bool operator==(const GridSquare& l, const GridSquare& r)
+//{
+// return l.bounds.min == r.bounds.min;
+//}
+
+//bool operator<(const glm::vec3& l, const glm::vec3& r)
+//{
+// return glm::all(glm::lessThan(l, r));;
+//}
+
+//bool operator==(const glm::vec3& l, const glm::vec3& r)
+//{
+// return glm::all(glm::equal(l, r));;
+//}
+
+
+class UniformGrid
+{
+public:
+ UniformGrid(std::map<std::string, std::shared_ptr<GameObject>>& dynamic_gameobjects);
+ std::set<std::set<std::string>> detectPossibleCollisions();
+ void updateAllGrid();
+
+
+
+private:
+ void populateContainingCell(glm::vec3 bound_corner, std::string entity_id);
+ void updateUniformGrid(const std::pair<std::string, std::shared_ptr<GameObject>> &go);
+ void moveEntityGridPosition(const std::pair<std::string, std::shared_ptr<GameObject>> &go);
+ void initializeGrid();
+ std::string vecToString(glm::vec3 v);
+
+
+ std::map<std::string, std::shared_ptr<GameObject>>& m_dynamic_gameobjects;
+ // maps square corner to set of strings
+ std::map<std::string, std::set<std::string>> m_grid_map;
+ glm::vec3 m_square_dimensions;
+
+};
+
+#endif // UNIFORMGRID_H
diff --git a/engine-ocean/Game/Systems/CollisionSystems/accelerationsystem.cpp b/engine-ocean/Game/Systems/CollisionSystems/accelerationsystem.cpp
new file mode 100644
index 0000000..c81be68
--- /dev/null
+++ b/engine-ocean/Game/Systems/CollisionSystems/accelerationsystem.cpp
@@ -0,0 +1,6 @@
+#include "accelerationsystem.h"
+
+AccelerationSystem::AccelerationSystem()
+{
+
+}
diff --git a/engine-ocean/Game/Systems/CollisionSystems/accelerationsystem.h b/engine-ocean/Game/Systems/CollisionSystems/accelerationsystem.h
new file mode 100644
index 0000000..dd47731
--- /dev/null
+++ b/engine-ocean/Game/Systems/CollisionSystems/accelerationsystem.h
@@ -0,0 +1,11 @@
+#ifndef ACCELERATIONSYSTEM_H
+#define ACCELERATIONSYSTEM_H
+
+
+class AccelerationSystem
+{
+public:
+ AccelerationSystem();
+};
+
+#endif // ACCELERATIONSYSTEM_H
diff --git a/engine-ocean/Game/Systems/CollisionSystems/collisionsystem.cpp b/engine-ocean/Game/Systems/CollisionSystems/collisionsystem.cpp
new file mode 100644
index 0000000..40816de
--- /dev/null
+++ b/engine-ocean/Game/Systems/CollisionSystems/collisionsystem.cpp
@@ -0,0 +1,183 @@
+#include "collisionsystem.h"
+#include "Game/Components/CollisionComponents/BoundingDynamicMesh.h"
+#include "Game/Components/CollisionComponents/CollisionComponent.h"
+#include "Game/Components/CollisionComponents/CylinderCollider.h"
+#include "Game/Components/TransformComponent.h"
+
+CollisionSystem::CollisionSystem(std::map<std::string, std::shared_ptr<GameObject>>& gameobjects,
+ std::map<std::string, std::shared_ptr<GameObject>>& dynamic_gameobjects,
+ std::map<std::string, std::shared_ptr<GameObject>>& rigid_gameobjects,
+ std::map<int, Input>& input_map,
+ std::map<std::string, BlackboardData>& global_blackboard) :
+ m_gameobjects(gameobjects),
+ m_dynamic_gameobjects(dynamic_gameobjects),
+ m_rigid_gameobjects(rigid_gameobjects),
+ m_uniform_grid_system(std::make_unique<UniformGrid>(dynamic_gameobjects)),
+ m_global_blackboard(global_blackboard)
+{
+
+}
+
+TransformComponent* CollisionSystem::getTransform(std::shared_ptr<GameObject> &go){
+ return go->getComponent<TransformComponent>();
+
+}
+
+CollisionComponent* CollisionSystem::getCollisionComp(std::shared_ptr<GameObject> &go){
+ return go->getComponent<CollisionComponent>();
+}
+
+glm::vec2 CollisionSystem::calculateCircleMVT(const Cylinder &a, const Cylinder &b){
+ float len = glm::length(a.point - b.point);
+
+ glm::vec2 mtv = ((b.point - a.point)/len) * (a.radius+b.radius - len);
+ return mtv;
+}
+
+float CollisionSystem::calculateLineMVT(const Cylinder &a, const Cylinder &b){
+ float aRight = b.max - a.min;
+ float aLeft = a.max - b.min;
+ if ((aLeft < 0) || (aRight < 0)){
+ return -1.f;
+ }
+ if (aRight < aLeft){
+ return aRight;
+ }
+ return -aLeft;
+}
+
+glm::vec3 CollisionSystem::collideCylinderCylinder(const std::shared_ptr<GameObject> &a_go, const std::shared_ptr<GameObject> &b_go){
+ Cylinder a = a_go->getComponent<CollisionComponent>()->getCollisionShape<BoundingDynamicMesh>()->getCylinder();
+ Cylinder b = b_go->getComponent<CollisionComponent>()->getCollisionShape<BoundingDynamicMesh>()->getCylinder();
+
+ //std::cout << "a max: " << a.max << std::endl;
+ //std::cout << "b max: " << b.max << std::endl;
+
+
+
+ float len_squared = pow(a.point[0]-b.point[0],2) + pow(a.point[1]-b.point[1],2);
+ float radius_sum = pow(a.radius + b.radius, 2);
+
+ // check if circles overlap
+ if (len_squared < radius_sum){
+ //std::cout << "CIRCLES OVERLAP" << std::endl;
+ // check if lines overlap
+ if ((a.min < b.max) && (b.min < a.max)){
+ std::cout << "COLLIDINGGG" << std::endl;
+ // calculate both circle and line mtvs, and then return the shortest mtv
+ glm::vec2 circle_mtv = calculateCircleMVT(a, b);
+ float circle_len = glm::length(circle_mtv);
+
+ float line_mtv = calculateLineMVT(a, b);
+
+ if (abs(circle_len) < abs(line_mtv)){
+ return glm::vec3(circle_mtv[0], 0.f, circle_mtv[1]);
+ } else {
+ return glm::vec3(0.f, line_mtv, 0.f);
+ }
+ }
+ }
+
+ // return translation of 0 if there is no collision
+ return glm::vec3(0.f);
+}
+
+
+bool CollisionSystem::checkCollisionShape(const std::shared_ptr<GameObject> &go, std::string shape_type){
+ // add more collision shapes here
+ if (shape_type == "cylinder"){
+ return (go->getComponent<CollisionComponent>()->hasCollisionShape<CylinderCollider>());
+ }
+ return false;
+}
+
+void CollisionSystem::resolveCollision(std::shared_ptr<GameObject> &go,
+ glm::vec3 mtv,
+ float deltaTime,
+ std::string go_name){
+ glm::vec3 potential_pos = go->getComponent<TransformComponent>()->getPos();
+ go->getComponent<TransformComponent>()->old_pos = potential_pos;
+ go->getComponent<TransformComponent>()->movingLaterally = false;
+
+ // translate, and also update the collision cylinder point
+ float a = go->getComponent<CollisionComponent>()->getAcceleration();
+ float v = go->getComponent<CollisionComponent>()->getReboundVel();
+ float delta_x = mtv.x + v*deltaTime + .5*a*pow(deltaTime, 2);
+ float delta_z = mtv.z + v*deltaTime + .5*a*pow(deltaTime, 2);
+
+ // update estimated_final_pos, so that tri-ellip collision can see if the new pos collides with environment
+ glm::vec3 translationDir = glm::vec3(delta_x, mtv.y, delta_z);
+ if (delta_x != 0 || delta_z != 0){
+ go->getComponent<TransformComponent>()->movingLaterally = true;
+ }
+
+ std::shared_ptr<ModelTransform> temp_mt = go->getComponent<TransformComponent>()->getMT();
+ temp_mt->translate(translationDir);
+ potential_pos = temp_mt->getPos();
+
+
+ m_global_blackboard[go_name].locationData.setToPos = potential_pos;
+ go->getComponent<TransformComponent>()->estimated_final_pos = potential_pos;
+}
+
+void CollisionSystem::detectCylinderCollisions(std::shared_ptr<GameObject> &a,
+ std::shared_ptr<GameObject> &b,
+ float deltaTime,
+ std::string a_name, std::string b_name){
+ // if its a cyl-cyl collision
+ glm::vec3 mtv(0.f);
+
+ mtv = collideCylinderCylinder(a, b);
+ if (mtv != glm::vec3(0.f)){
+ resolveCollision(b, 1.f*mtv, deltaTime, b_name);
+ resolveCollision(a, -1.f*mtv, deltaTime, a_name);
+ }
+
+}
+
+bool CollisionSystem::areCollidable(const std::shared_ptr<GameObject> &a, const std::shared_ptr<GameObject> &b){
+ return (a->hasComponent<CollisionComponent>() && b->hasComponent<CollisionComponent>());
+}
+
+
+// DYNAMIC-DYNAMIC COLLISIONS: CYLINDER
+void CollisionSystem::dynamicDynamicCollisions(double deltaTime){
+ std::set<std::set<std::string>> candidate_collison_set = m_uniform_grid_system->detectPossibleCollisions();
+
+ // std::cout << "all collisions size : " << candidate_collison_set.size() << std::endl;
+
+ for (const std::set<std::string> &set : candidate_collison_set){
+
+ // std::cout << "collision group size : " << set.size() << std::endl;
+
+ std::vector<std::string> coll_group;
+ for (const std::string &name : set){
+ coll_group.push_back(name);
+ }
+
+ for (int i=0; i < coll_group.size(); i++){
+ auto a = m_dynamic_gameobjects.at(coll_group[i]);
+ for (int j=i+1; j < coll_group.size(); j++){
+ auto b = m_dynamic_gameobjects.at(coll_group[j]);
+ // if a is not the same GO as b, and at least has collide components and thus is collidable,
+ if ((a != b) && (areCollidable(a, b))){
+ //std::cout << "collide: " << coll_group[i] << " + " << coll_group[j] << std::endl;
+ detectCylinderCollisions(a, b, deltaTime, coll_group[i], coll_group[j]);
+ }
+ }
+ }
+ }
+}
+
+
+void CollisionSystem::update(double deltaTime){
+ // update uniform grid before detecting with it
+ m_uniform_grid_system->updateAllGrid();
+ dynamicDynamicCollisions(deltaTime);
+}
+
+void CollisionSystem::draw(){}
+void CollisionSystem::scrollEvent(double distance){}
+void CollisionSystem::mousePosEvent(double xpos, double ypos){}
+
+
diff --git a/engine-ocean/Game/Systems/CollisionSystems/collisionsystem.h b/engine-ocean/Game/Systems/CollisionSystems/collisionsystem.h
new file mode 100644
index 0000000..5c635ba
--- /dev/null
+++ b/engine-ocean/Game/Systems/CollisionSystems/collisionsystem.h
@@ -0,0 +1,53 @@
+#ifndef COLLISIONSYSTEM_H
+#define COLLISIONSYSTEM_H
+#include "Game/Components/CollisionComponents/CollisionComponent.h"
+#include "Game/Components/CollisionComponents/CylinderCollider.h"
+#include "Game/Components/TransformComponent.h"
+#include "Game/GameWorld.h"
+#include "Game/Systems/CollisionSystems/UniformGrid/uniformgrid.h"
+#include "Game/Systems/CollisionSystems/ellipsoidtrianglecollisionsystem.h"
+#include "Game/Systems/system.h"
+
+class CollisionSystem : public System
+{
+public:
+ CollisionSystem(std::map<std::string, std::shared_ptr<GameObject>>& gameobjects,
+ std::map<std::string, std::shared_ptr<GameObject>>& dynamic_gameobjects,
+ std::map<std::string, std::shared_ptr<GameObject>>& rigid_gameobjects,
+ std::map<int, Input>& input_map,
+ std::map<std::string, BlackboardData>& global_blackboard);
+ void draw() override;
+ void update(double deltaTime) override;
+ void scrollEvent(double distance) override;
+ void mousePosEvent(double xpos, double ypos) override;
+private:
+ bool areCollidable(const std::shared_ptr<GameObject> &a, const std::shared_ptr<GameObject> &b);
+ void detectCylinderCollisions(std::shared_ptr<GameObject> &a, std::shared_ptr<GameObject> &b, float deltaTime,
+ std::string a_name, std::string b_name);
+ void resolveCollision(std::shared_ptr<GameObject> &go, glm::vec3 translation, float deltaTime, std::string go_name);
+ bool checkCollisionShape(const std::shared_ptr<GameObject> &go, std::string shape_type);
+ glm::vec3 projectMotion(const glm::vec3 &initial_pos, float deltaTime);
+
+ TransformComponent* getTransform(std::shared_ptr<GameObject> &go);
+ CollisionComponent* getCollisionComp(std::shared_ptr<GameObject> &go);
+
+ void rigidDynamicCollisions(double deltaTime);
+ void dynamicDynamicCollisions(double deltaTime);
+
+
+ // cylinder-cylinder
+ glm::vec3 collideCylinderCylinder(const std::shared_ptr<GameObject> &a_go, const std::shared_ptr<GameObject> &b_go);
+ float calculateLineMVT(const Cylinder &a, const Cylinder &b);
+ glm::vec2 calculateCircleMVT(const Cylinder &a, const Cylinder &b);
+
+
+ std::map<std::string, std::shared_ptr<GameObject>>& m_gameobjects;
+ std::map<std::string, std::shared_ptr<GameObject>>& m_dynamic_gameobjects;
+ std::map<std::string, std::shared_ptr<GameObject>>& m_rigid_gameobjects;
+
+ std::unique_ptr<UniformGrid> m_uniform_grid_system;
+ std::map<std::string, BlackboardData>& m_global_blackboard;
+};
+
+
+#endif // COLLISIONSYSTEM_H
diff --git a/engine-ocean/Game/Systems/CollisionSystems/ellipsoidtrianglecollisionsystem.cpp b/engine-ocean/Game/Systems/CollisionSystems/ellipsoidtrianglecollisionsystem.cpp
new file mode 100644
index 0000000..52b8916
--- /dev/null
+++ b/engine-ocean/Game/Systems/CollisionSystems/ellipsoidtrianglecollisionsystem.cpp
@@ -0,0 +1,370 @@
+#include "ellipsoidtrianglecollisionsystem.h"
+#include "Game/Components/CollisionComponents/BoundingTriangle.h"
+#include "Game/Components/CollisionComponents/CollisionComponent.h"
+#include "Game/Components/CollisionComponents/boundingellipsoid.h"
+#include "Game/Components/DrawComponent.h"
+#include "Game/Components/TransformComponent.h"
+#include "Game/GameObjects/GameObject.h"
+#include <memory>
+
+EllipsoidTriangleCollisionSystem::EllipsoidTriangleCollisionSystem(std::map<std::string, std::shared_ptr<GameObject>>& rigid_gameobjects) :
+ m_rigid_gameobjects(rigid_gameobjects),
+ m_bvh_system(std::make_unique<BVHTree>(rigid_gameobjects))
+{
+}
+
+
+Triangle EllipsoidTriangleCollisionSystem::convertTriangleToSphereSpace(const glm::vec3 &orig_R, const Triangle &orig_triangle){
+ Triangle transformed_triangle;
+
+ // divide vertex pos by Rs
+ transformed_triangle.vertexA = orig_triangle.vertexA / orig_R;
+ transformed_triangle.vertexB = orig_triangle.vertexB / orig_R;
+ transformed_triangle.vertexC = orig_triangle.vertexC / orig_R;
+
+ transformed_triangle.edge1 = transformed_triangle.vertexB - transformed_triangle.vertexA;
+ transformed_triangle.edge2 = transformed_triangle.vertexC - transformed_triangle.vertexA;
+
+ // does the normal stay the same across transformations?
+ transformed_triangle.normal = glm::normalize(glm::cross(transformed_triangle.edge1, transformed_triangle.edge2));
+
+ return transformed_triangle;
+}
+
+
+glm::vec3 EllipsoidTriangleCollisionSystem::getIntersectionPt(const glm::vec3 &ray_p, const glm::vec3 &ray_d, const float t){
+ return ray_p + t*ray_d;
+}
+
+float EllipsoidTriangleCollisionSystem::solveQuadratic(float a, float b, float c){
+ float discriminant = pow(b,2) - 4*a*c;
+
+ // check for imaginary numbers
+ if (discriminant >= 0){
+ float pos_quad = (-b + sqrt(discriminant)) / (2*a);
+ float neg_quad = (-b - sqrt(discriminant)) / (2*a);
+
+ // if the mininum is a neg number, then return the larger of the two
+ if (fmin(pos_quad, neg_quad) < ZERO){
+ return fmax(pos_quad, neg_quad);
+ } else {
+ return fmin(pos_quad, neg_quad);
+ }
+ }
+ return -1;
+}
+
+
+float EllipsoidTriangleCollisionSystem::raycastSphere(const glm::vec3 &ray_p, const glm::vec3 &ray_d, const glm::vec3 posA, const glm::vec3 posB){
+ // shift ray and ellipsoid to center first in order to use regular implicit sphere equation
+ glm::vec3 p = ray_p - posA;
+ glm::vec3 d = ray_d - posA;
+
+ float a = (d.x*d.x) + (d.y*d.y) + (d.z*d.z);
+ float b = (2.f*p.x*d.x) + (2.f*p.y*d.y) + (2.f*p.z*d.z);
+ float c = (p.x*p.x) + (p.y*p.y) + (p.z*p.z) - 1.f;
+
+ return solveQuadratic(a,b,c);
+}
+
+float EllipsoidTriangleCollisionSystem::raycastTriangle(const glm::vec3 &ray_p, const glm::vec3 &ray_d, const Triangle &triangle){
+ float t = (glm::dot((triangle.vertexA - ray_p), triangle.normal))/(glm::dot(ray_d, triangle.normal));
+ return t;
+}
+
+glm::vec3 EllipsoidTriangleCollisionSystem::getTriangleEdge(const glm::vec3 v1, const glm::vec3 v2){
+ return v2 - v1;
+}
+
+bool EllipsoidTriangleCollisionSystem::isSameDirection(const glm::vec3 edge1, const glm::vec3 edge2, const glm::vec3 n){
+ if (glm::dot(glm::cross(edge1, edge2), n) > 0){
+ return true;
+ }
+ return false;
+}
+
+void EllipsoidTriangleCollisionSystem::makeCollisionData(const float t, const glm::vec3 triangle_n,
+ const glm::vec3 intersection_pos,
+ const glm::vec3 point_of_contact,
+ const bool isVertex){
+ CollisionData data;
+ data.t = t;
+ data.triangle_n = triangle_n;
+ data.intersection_pos = intersection_pos;
+ data.point_of_contact = point_of_contact;
+ data.isVertex = isVertex;
+ m_collisionData.push_back(data);
+}
+
+
+bool EllipsoidTriangleCollisionSystem::detectSphere_with_Interior(const Triangle &triangle, const glm::vec3 posA, const glm::vec3 posB){
+ // calculate point on sphere closest to the plane and cast a ray
+ glm::vec3 ray_p = posA-triangle.normal; // closest point on unit sphere
+ glm::vec3 ray_d = (posB-posA);
+
+ glm::vec3 n = triangle.normal;
+ glm::vec3 v = triangle.vertexA;
+ float plane_const = -1 * (n.x*v.x + n.y*v.y + n.z*v.z);
+
+ // pdf equation
+ float t = (1-(glm::dot(n, posA) + plane_const)) / (glm::dot(n, (posB-posA)));
+ if (t < ZERO || t > ONE){
+ return false;
+ }
+
+ // the point P on the sphere closest to plane surface
+ glm::vec3 P_edge = getIntersectionPt(ray_p, ray_d, t);
+
+
+ // determine if point is on triangle plane
+ // determine if point is also within triangle bounds
+ glm::vec3 AB = getTriangleEdge(triangle.vertexA, triangle.vertexB);
+ glm::vec3 BC = getTriangleEdge(triangle.vertexB, triangle.vertexC);
+ glm::vec3 CA = getTriangleEdge(triangle.vertexC, triangle.vertexA);
+
+ glm::vec3 AP = getTriangleEdge(triangle.vertexA, P_edge);
+ glm::vec3 BP = getTriangleEdge(triangle.vertexB, P_edge);
+ glm::vec3 CP = getTriangleEdge(triangle.vertexC, P_edge);
+
+ if (isSameDirection(AB, AP, triangle.normal) &&
+ isSameDirection(BC, BP, triangle.normal) &&
+ isSameDirection(CA, CP, triangle.normal)){
+
+ // the actual center of sphere
+ glm::vec3 P_centered = getIntersectionPt(posA, posB-posA, t);
+ makeCollisionData(t, triangle.normal, P_centered, P_edge, false);
+ return true;
+ }
+ return false;
+}
+
+// do this for each vertex pair AB, BC, CA
+bool EllipsoidTriangleCollisionSystem::detectSphere_with_Edge(const glm::vec3 &v1, const glm::vec3 &v2,
+ const glm::vec3 &triangle_normal,
+ const glm::vec3 &posA, const glm::vec3 &posB){
+ glm::vec3 C = v1;
+ glm::vec D = v2;
+
+ float a = pow(glm::length(glm::cross(posB-posA, D-C)),2);
+ float b = glm::dot(2.f*glm::cross(posB-posA, D-C), glm::cross(posA-C, D-C));
+ float c = pow(glm::length(glm::cross(posA-C, D-C)),2) - pow(glm::length(D-C),2);
+
+ float t = solveQuadratic(a,b,c);
+
+ // discard a negative t --> indicates no collision with edge
+ if (t < ZERO || t > ONE){
+ return false;
+ }
+
+ glm::vec3 P = getIntersectionPt(posA, posB-posA, t);
+
+ glm::vec3 AP = P-C;
+ glm::vec3 AB = D-C;
+ glm::vec3 normal = AP - (glm::dot(AB,AP)/glm::dot(AB,AB))*AB;
+
+ // determine if intersection pt is between C and D
+ if ( (0 < glm::dot(P-C,D-C)) && (glm::dot(P-C,D-C) < pow(glm::length(D-C),2)) ){
+ makeCollisionData(t, normal, P, P, false);
+ return true;
+ }
+
+ return false;
+}
+
+// needs to be done with each vertex
+bool EllipsoidTriangleCollisionSystem::detectSphere_with_Vertex(const glm::vec3 &v, const glm::vec3 triangle_normal, const glm::vec3 &posA, const glm::vec3 &posB){
+ glm::vec3 ray_p = v;
+ //glm::vec3 ray_d = v-(posB-posA);
+
+ // convert to origin space:
+ glm::vec3 vel = posB-posA;
+ glm::vec3 v_origined = v - posA;
+
+ float a = glm::dot(vel,vel);
+ float b = 2*(glm::dot(vel, -v_origined));
+ float c = pow(glm::length(v_origined),2) - 1.f;
+
+ float t = solveQuadratic(a,b,c);
+ if (t < ZERO || t > ONE){
+ return false;
+ }
+
+ // where the center is when the sphere hits vertex
+ glm::vec3 center_pt_origined = t*vel;
+ // convert back to non-origin space
+ glm::vec3 center_pt = center_pt_origined + posA;
+ glm::vec3 normal = center_pt - v;
+ makeCollisionData(t, normal, center_pt, v, true);
+ return true;
+}
+
+CollisionData EllipsoidTriangleCollisionSystem::getNearestCollision(const std::vector<CollisionData> &collisionData, const Triangle &sphere_tri){
+ CollisionData nearestCollision;
+ nearestCollision.t = INFINITY;
+
+ for (const CollisionData &data : collisionData){
+ if (data.t < nearestCollision.t){
+ // set nearest collision to datapoint
+ nearestCollision = data;
+ }
+ }
+ return nearestCollision;
+}
+
+// SPHERE SPACE
+CollisionData EllipsoidTriangleCollisionSystem::detectTriangleCollision(const Triangle &sphere_tri, const glm::vec3 &posA, const glm::vec3 &posB){
+
+ m_collisionData.clear();
+ // if interior is true, no need to check rest. get the only collision data
+ if (detectSphere_with_Interior(sphere_tri, posA, posB)){
+ return m_collisionData[0];
+ }
+
+ // otherwise check rest:
+
+ // detect edge with all 3 edges
+ // | operator executes regardless of if left hand side is true or not
+ if (
+ detectSphere_with_Edge(sphere_tri.vertexA, sphere_tri.vertexB, sphere_tri.normal, posA, posB) |
+ detectSphere_with_Edge(sphere_tri.vertexB, sphere_tri.vertexC, sphere_tri.normal, posA, posB) |
+ detectSphere_with_Edge(sphere_tri.vertexC, sphere_tri.vertexA, sphere_tri.normal, posA, posB) ){
+ return getNearestCollision(m_collisionData, sphere_tri);
+ }
+
+ // detect vertex with all 3 vertices
+ detectSphere_with_Vertex(sphere_tri.vertexA, sphere_tri.normal, posA, posB);
+ detectSphere_with_Vertex(sphere_tri.vertexB, sphere_tri.normal, posA, posB);
+ detectSphere_with_Vertex(sphere_tri.vertexC, sphere_tri.normal, posA, posB);
+
+ return getNearestCollision(m_collisionData, sphere_tri);
+}
+
+CollisionData EllipsoidTriangleCollisionSystem::revertDataToOriginalSpace(const CollisionData &sphere_datum, const glm::vec3 &ellip_R, const glm::vec3 orig_triangle_n){
+ CollisionData reverted_datum = sphere_datum;
+ reverted_datum.intersection_pos = reverted_datum.intersection_pos*ellip_R;
+ reverted_datum.point_of_contact = reverted_datum.point_of_contact*ellip_R;
+
+ return reverted_datum;
+}
+
+void EllipsoidTriangleCollisionSystem::setEllipsoidDimensions(const glm::vec3 &dimensions){
+ m_ellipsoid_dimensions = dimensions;
+}
+
+CollisionData EllipsoidTriangleCollisionSystem::collideWithWorld(const glm::vec3 &posA, const glm::vec3 &posB){
+ // makes ellipsoids
+ Ellipsoid ellipsoidA;
+ ellipsoidA.R = m_ellipsoid_dimensions;
+ ellipsoidA.center_pos = posA;
+
+
+ Ellipsoid ellipsoidB;
+ ellipsoidB.R = m_ellipsoid_dimensions;
+ ellipsoidB.center_pos = posB;
+
+ // convert ellipsoid centers to sphere space
+ glm::vec3 sphere_posA = ellipsoidA.center_pos/m_ellipsoid_dimensions;
+ glm::vec3 sphere_posB = ellipsoidB.center_pos/m_ellipsoid_dimensions;
+
+ CollisionData nearestCollision;
+ nearestCollision.t = INFINITY;
+
+
+ std::vector<Triangle> candidates = m_bvh_system->getBVHDetectedCollisions(posA, posB, ellipsoidA.R);
+ // std::cout << "candidate size: " << candidates.size() << std::endl;
+
+
+// for (auto &rigid_go : candidates){
+// //std::cout << "candidate shape name: " << rigid_go->getComponent<DrawComponent>()->getShapeName() << std::endl;
+// if (rigid_go->hasComponent<CollisionComponent>()){
+// if (rigid_go->getComponent<CollisionComponent>()->hasCollisionShape<BoundingTriangle>()){
+// // for every triangle in game obj, transform to sphere space and collide with ellipsoid (aka sphere)
+ for (int i=0; i< candidates.size(); i++){
+ Triangle triangle = candidates[i];
+// std::cout<< "triangle i: " << i << ", v1: (" << triangle.vertexA.x << ", " << triangle.vertexA.y << ", " << triangle.vertexA.z << "), v2: ("
+// << triangle.vertexB.x << ", " << triangle.vertexB.y << ", " << triangle.vertexB.z << "), v3: ("
+// << triangle.vertexC.x << ", " << triangle.vertexC.y << ", " << triangle.vertexC.z << ")" << std::endl;
+
+ // transform triangle to sphere space and detect collision data (in sphere space) for this specific triangle
+ Triangle sphere_triangle = convertTriangleToSphereSpace(m_ellipsoid_dimensions, triangle);
+ CollisionData sphere_collisionDatum = detectTriangleCollision(sphere_triangle, sphere_posA, sphere_posB);
+ CollisionData ellip_collisionDatum = revertDataToOriginalSpace(sphere_collisionDatum, m_ellipsoid_dimensions, triangle.normal);
+
+ // keep track of nearest Collision
+ if (ellip_collisionDatum.t < nearestCollision.t && ellip_collisionDatum.t <= ONE && ellip_collisionDatum.t >= ZERO){
+ nearestCollision = ellip_collisionDatum;
+ }
+ // repeat for the other triangles
+ }
+ //}
+ //}
+ // repeat for all gameobjects
+ //}
+
+ return nearestCollision;
+}
+
+glm::vec3 EllipsoidTriangleCollisionSystem::doNudge(glm::vec3 curr_pos, CollisionData collision){
+ glm::vec3 nudge = m_scale_normals_mt*collision.triangle_n;
+
+ glm::vec3 pos_nudged = collision.intersection_pos + nudge * .01f;
+ int MAX_NUDGES = 3;
+ for (int i=0; i<MAX_NUDGES; i++){
+ CollisionData nudge_collision = collideWithWorld(curr_pos, pos_nudged);
+ if (nudge_collision.t == INFINITY){
+ curr_pos = pos_nudged;
+ break;
+ } else {
+ if (glm::length((m_scale_normals_mt*nudge_collision.triangle_n) - nudge) < .0001 || glm::length((m_scale_normals_mt*nudge_collision.triangle_n) + nudge) < .0001){
+ nudge = -m_scale_normals_mt*nudge_collision.triangle_n;
+ } else {
+ nudge = m_scale_normals_mt*nudge_collision.triangle_n;
+ }
+ pos_nudged = nudge_collision.intersection_pos + nudge * .01f;
+ }
+ }
+ return curr_pos;
+
+}
+
+glm::mat3 EllipsoidTriangleCollisionSystem::makeConversionMT(glm::vec3 initial_center_pos, glm::vec3 dimensions){
+ m_conversion_mt = std::make_shared<ModelTransform>();
+ m_conversion_mt->translate(-initial_center_pos);
+ m_conversion_mt->scale(dimensions);
+ m_scale_normals_mt = glm::transpose((glm::inverse(glm::mat3(m_conversion_mt->getModelMatrix()))));
+ m_scale_normals_mt = glm::mat4(1.f);
+ return m_scale_normals_mt;
+}
+
+// in sphere space
+std::pair<std::vector<CollisionData>, glm::vec3> EllipsoidTriangleCollisionSystem::mtvSlide(glm::vec3 initial_pos, glm::vec3 final_pos, glm::vec3 dimensions){
+ setEllipsoidDimensions(dimensions);
+ glm::mat3 normals_scale = makeConversionMT(initial_pos, dimensions);
+
+ std::vector<CollisionData> collisions;
+ glm::vec3 curr_pos = initial_pos;
+ glm::vec3 next_pos = final_pos;
+ int MAX_TRANSLATIONS = 3;
+ for (int i=0; i<MAX_TRANSLATIONS; i++){
+ CollisionData c = collideWithWorld(initial_pos, next_pos);
+
+ // if no collisions [0,1] found, then continue on regular path
+ if (c.t == INFINITY){
+ //std::cout << "--mtv-- " << next_pos.x << "," << next_pos.y << "," << next_pos.z << std::endl;
+ return std::pair<std::vector<CollisionData>, glm::vec3>(collisions, next_pos);
+ } else {
+ // nudge along the collision data
+ //std::cout << "COLLIDING......" << std::endl;
+ curr_pos = doNudge(curr_pos, c);
+ glm::vec3 d = next_pos - curr_pos;
+ glm::vec3 d_corrected = (d - glm::dot(d, normals_scale*c.triangle_n)) * (normals_scale*c.triangle_n);
+ next_pos = curr_pos + d_corrected;
+ collisions.push_back(c);
+ }
+
+ }
+
+ return std::pair<std::vector<CollisionData>, glm::vec3>(collisions, curr_pos);
+}
+
+
diff --git a/engine-ocean/Game/Systems/CollisionSystems/ellipsoidtrianglecollisionsystem.h b/engine-ocean/Game/Systems/CollisionSystems/ellipsoidtrianglecollisionsystem.h
new file mode 100644
index 0000000..8a7d102
--- /dev/null
+++ b/engine-ocean/Game/Systems/CollisionSystems/ellipsoidtrianglecollisionsystem.h
@@ -0,0 +1,69 @@
+#ifndef ELLIPSOIDTRIANGLECOLLISIONSYSTEM_H
+#define ELLIPSOIDTRIANGLECOLLISIONSYSTEM_H
+#include "Game/Components/CollisionComponents/BoundingEllipsoid.h"
+#include "Game/Components/CollisionComponents/BoundingTriangle.h"
+#include "Game/GameObjects/GameObject.h"
+#include "Game/Systems/CollisionSystems/BVH/bvhtree.h"
+#include "glm/glm.hpp"
+#include <vector>
+
+struct CollisionData{
+ bool hasCollided = true; // only false when there is no collision data to return
+ bool isVertex = false;
+ float t = INFINITY;
+ glm::vec3 triangle_n; // normal of the triangle its colliding with
+ glm::vec3 intersection_pos;
+ glm::vec3 point_of_contact;
+};
+
+class EllipsoidTriangleCollisionSystem
+{
+public:
+ EllipsoidTriangleCollisionSystem(std::map<std::string, std::shared_ptr<GameObject>>& rigid_gameobjects);
+
+
+ std::pair<std::vector<CollisionData>, glm::vec3> mtvSlide(glm::vec3 initial_pos, glm::vec3 final_pos, glm::vec3 dimensions);
+
+private:
+ CollisionData collideWithWorld(const glm::vec3 &posA, const glm::vec3 &posB);
+ void setEllipsoidDimensions(const glm::vec3 &dimensions);
+ glm::vec3 doNudge(glm::vec3 curr_pos, CollisionData collision);
+ CollisionData revertDataToOriginalSpace(const CollisionData &sphere_datum, const glm::vec3 &ellip_R, const glm::vec3 orig_triangle_n);
+ CollisionData detectTriangleCollision(const Triangle &sphere_tri, const glm::vec3 &posA, const glm::vec3 &posB);
+ CollisionData getNearestCollision(const std::vector<CollisionData> &collisionData, const Triangle &sphere_tri);
+ glm::mat3 makeConversionMT(glm::vec3 initial_center_pos, glm::vec3 dimensions);
+
+
+ bool detectSphere_with_Vertex(const glm::vec3 &v, const glm::vec3 triangle_normal, const glm::vec3 &posA, const glm::vec3 &posB);
+ bool detectSphere_with_Edge(const glm::vec3 &v1, const glm::vec3 &v2,
+ const glm::vec3 &triangle_normal,
+ const glm::vec3 &posA, const glm::vec3 &posB);
+ void makeCollisionData(const float t, const glm::vec3 triangle_n, const glm::vec3 intersection_pos, const glm::vec3 point_of_contact, const bool isVertex);
+ bool detectSphere_with_Interior(const Triangle &triangle, const glm::vec3 posA, const glm::vec3 posB);
+
+
+ bool isSameDirection(const glm::vec3 edge1, const glm::vec3 edge2, const glm::vec3 n);
+ glm::vec3 getTriangleEdge(const glm::vec3 v1, const glm::vec3 v2);
+ float raycastSphere(const glm::vec3 &ray_p, const glm::vec3 &ray_d, const glm::vec3 posA, const glm::vec3 posB);
+ float raycastTriangle(const glm::vec3 &ray_p, const glm::vec3 &ray_d, const Triangle &triangle);
+ float solveQuadratic(float a, float b, float c);
+ glm::vec3 getIntersectionPt(const glm::vec3 &ray_p, const glm::vec3 &ray_d, const float t);
+ Triangle convertTriangleToSphereSpace(const glm::vec3 &orig_R, const Triangle &orig_triangle);
+
+ std::vector<CollisionData> m_collisionData;
+ std::map<std::string, std::shared_ptr<GameObject>>& m_rigid_gameobjects;
+
+ glm::vec3 m_ellipsoid_dimensions = glm::vec3(1.0);
+
+ float ZERO = -.0001f;
+ float ONE = 1.0001f;
+
+ std::shared_ptr<ModelTransform> m_conversion_mt;
+ glm::mat3 m_scale_normals_mt = glm::mat3(1.f);
+
+ std::vector<std::shared_ptr<GameObject>> m_candidate_obstacles;
+ std::unique_ptr<BVHTree> m_bvh_system;
+
+};
+
+#endif // ELLIPSOIDTRIANGLECOLLISIONSYSTEM_H
diff --git a/engine-ocean/Game/Systems/CollisionSystems/environmentcollisiondetectionsystem.cpp b/engine-ocean/Game/Systems/CollisionSystems/environmentcollisiondetectionsystem.cpp
new file mode 100644
index 0000000..3470dd8
--- /dev/null
+++ b/engine-ocean/Game/Systems/CollisionSystems/environmentcollisiondetectionsystem.cpp
@@ -0,0 +1,93 @@
+#include "environmentcollisiondetectionsystem.h"
+#include "Game/Components/CollisionComponents/BoundingDynamicMesh.h"
+#include "Game/Components/CollisionComponents/CollisionComponent.h"
+#include "Game/Components/TransformComponent.h"
+#include "Game/GameObjects/GameObject.h"
+#include "Game/Systems/CollisionSystems/ellipsoidtrianglecollisionsystem.h"
+#include <utility>
+
+EnvironmentCollisionDetectionSystem::EnvironmentCollisionDetectionSystem(
+ std::map<std::string, std::shared_ptr<GameObject>>& dynamic_gameobjects,
+ std::map<std::string, std::shared_ptr<GameObject>>& rigid_gameobjects,
+ std::map<std::string, std::vector<std::shared_ptr<GameObject>>>& lootables,
+ std::map<std::string, BlackboardData>& global_blackboard) :
+ m_dynamic_gameobjects(dynamic_gameobjects),
+ m_ellipsoid_triangle_collision_system(std::make_unique<EllipsoidTriangleCollisionSystem>(rigid_gameobjects)),
+ m_global_blackboard(global_blackboard),
+ m_lootables(lootables)
+{
+
+}
+
+TransformComponent* EnvironmentCollisionDetectionSystem::getTransform(std::shared_ptr<GameObject> &go){
+ return go->getComponent<TransformComponent>();
+
+}
+
+CollisionComponent* EnvironmentCollisionDetectionSystem::getCollisionComp(std::shared_ptr<GameObject> &go){
+ return go->getComponent<CollisionComponent>();
+}
+
+void EnvironmentCollisionDetectionSystem::detectCollisionWithEnvironment(double deltaTime){
+ for (auto &go : m_dynamic_gameobjects){
+ collideDynamic(go.first, go.second);
+
+ }
+}
+
+
+void EnvironmentCollisionDetectionSystem::collideDynamic(std::string go_name, std::shared_ptr<GameObject> go){
+ if (!go->hasComponent<CollisionComponent>()){
+ return;
+ }
+
+ std::pair<std::vector<CollisionData>, glm::vec3> pair =
+ m_ellipsoid_triangle_collision_system->mtvSlide(getTransform(go)->old_pos,
+ //getTransform(go.second)->estimated_final_pos,
+ m_global_blackboard[go_name].locationData.setToPos,
+ getCollisionComp(go)->getCollisionShape<BoundingDynamicMesh>()->getEllipsoidDimensions());
+
+ // assume not on ground first; then determine if we are touching ground
+ getTransform(go)->onGround = false;
+ m_global_blackboard[go_name].conditionData["onGround"].conditionTrue = false;
+ for (const CollisionData &collision : pair.first){
+ if (glm::dot(glm::vec3(0,1,0), collision.triangle_n) > 0.f){
+ getTransform(go)->onGround = true;
+ m_global_blackboard[go_name].conditionData["onGround"].conditionTrue = true;
+
+ }
+ }
+
+ if (getTransform(go)->onGround){
+ if (getTransform(go)->yVelocity < 0){
+ getTransform(go)->yVelocity = 0.f;
+ getTransform(go)->gravity = 0.f;
+ }
+ }
+
+ if (!getTransform(go)->onGround){
+ getTransform(go)->gravity = -25.f;
+ }
+
+
+ if (!getTransform(go)->movingLaterally &&
+ getTransform(go)->onGround){
+ getTransform(go)->setPos(getTransform(go)->old_pos);
+ } else {
+ getTransform(go)->setPos(pair.second);
+ }
+
+ getCollisionComp(go)->getCollisionShape<BoundingDynamicMesh>()->updateCenterPos(getTransform(go)->getPos());
+}
+
+
+void EnvironmentCollisionDetectionSystem::update(double deltaTime){
+ detectCollisionWithEnvironment(deltaTime);
+}
+
+void EnvironmentCollisionDetectionSystem::draw(){}
+void EnvironmentCollisionDetectionSystem::scrollEvent(double distance){}
+void EnvironmentCollisionDetectionSystem::mousePosEvent(double xpos, double ypos){}
+
+
+
diff --git a/engine-ocean/Game/Systems/CollisionSystems/environmentcollisiondetectionsystem.h b/engine-ocean/Game/Systems/CollisionSystems/environmentcollisiondetectionsystem.h
new file mode 100644
index 0000000..8beca39
--- /dev/null
+++ b/engine-ocean/Game/Systems/CollisionSystems/environmentcollisiondetectionsystem.h
@@ -0,0 +1,43 @@
+#ifndef ENVIRONMENTCOLLISIONDETECTIONSYSTEM_H
+#define ENVIRONMENTCOLLISIONDETECTIONSYSTEM_H
+
+
+#include "Game/Components/CollisionComponents/CollisionComponent.h"
+#include "Game/Components/TransformComponent.h"
+#include "Game/Systems/CollisionSystems/ellipsoidtrianglecollisionsystem.h"
+#include <memory>
+#include "Game/Systems/system.h"
+
+class EnvironmentCollisionDetectionSystem /*: public System*/
+{
+public:
+ EnvironmentCollisionDetectionSystem(
+ std::map<std::string, std::shared_ptr<GameObject>>& dynamic_gameobjects,
+ std::map<std::string, std::shared_ptr<GameObject>>& rigid_gameobjects,
+ std::map<std::string, std::vector<std::shared_ptr<GameObject>>>& lootables,
+ std::map<std::string, BlackboardData>& global_blackboard);
+ void draw() ;
+ void update(double deltaTime);
+ void scrollEvent(double distance);
+ void mousePosEvent(double xpos, double ypos) ;
+
+
+private:
+ void detectCollisionWithEnvironment(double deltaTime);
+ CollisionComponent* getCollisionComp(std::shared_ptr<GameObject> &go);
+ TransformComponent* getTransform(std::shared_ptr<GameObject> &go);
+
+ void collideDynamic(std::string go_name, std::shared_ptr<GameObject> go);
+
+
+ std::map<std::string, std::shared_ptr<GameObject>>& m_dynamic_gameobjects;
+ std::unique_ptr<EllipsoidTriangleCollisionSystem> m_ellipsoid_triangle_collision_system;
+ //std::unique_ptr<BVHTree> m_bvh_system;
+ std::vector<std::shared_ptr<GameObject>> all_rigid_go;
+ std::map<std::string, BlackboardData>& m_global_blackboard;
+
+ std::map<std::string, std::vector<std::shared_ptr<GameObject>>>& m_lootables;
+
+};
+
+#endif // ENVIRONMENTCOLLISIONDETECTIONSYSTEM_H