Skip to content

Commit

Permalink
replace glm with our own math classes
Browse files Browse the repository at this point in the history
  • Loading branch information
handsomematt committed Dec 29, 2019
1 parent 1fd44a9 commit 861e294
Show file tree
Hide file tree
Showing 67 changed files with 2,854 additions and 890 deletions.
13 changes: 6 additions & 7 deletions src/AnimCamera.cpp
Expand Up @@ -5,7 +5,6 @@
#include <P3D/P3DFile.h>
#include <Render/SkinAnimation.h>
#include <filesystem>
#include <glm/gtx/quaternion.hpp>
#include <iostream>

namespace Donut
Expand Down Expand Up @@ -92,18 +91,18 @@ std::unique_ptr<AnimCamera> AnimCamera::LoadP3D(const std::string& filename)
return std::make_unique<AnimCamera>(p3d.GetRoot());
}

glm::mat4 AnimCamera::Update(double dt)
Matrix4x4 AnimCamera::Update(double dt)
{
return glm::mat4(1.0f);
return Matrix4x4::Identity;
//const auto& trans = _trans->Evaluate(0, (float)_time);
//const auto& forward = _forward->EvaluateDirection(0, (float)_time);
//const auto& up = glm::vec3(0, 1, 0);
//const auto& up = Vector3(0, 1, 0);
//const auto& right = glm::normalize(glm::cross(up, forward));
//glm::mat3 rotation(right.x, up.x, forward.x, right.y, up.y, forward.y, right.z, up.z, forward.z);
//auto lookAt = glm::quat_cast(rotation);
//Matrix3x3 rotation(right.x, up.x, forward.x, right.y, up.y, forward.y, right.z, up.z, forward.z);
//auto lookAt = Quat_cast(rotation);

//_time += dt;

//return glm::toMat4(lookAt) * glm::translate(glm::mat4(1.0f), -glm::vec3(trans[3]));
//return glm::toMat4(lookAt) * glm::translate(Matrix(1.0f), -Vector3(trans[3]));
}
} // namespace Donut
7 changes: 5 additions & 2 deletions src/AnimCamera.h
Expand Up @@ -2,12 +2,15 @@

#pragma once

#include <glm/glm.hpp>
#include "Core/Math/Fwd.h"

#include <memory>
#include <string>

namespace Donut
{

/* forward declarations */
class SkinAnimation;

namespace P3D
Expand All @@ -22,7 +25,7 @@ class AnimCamera

static std::unique_ptr<AnimCamera> LoadP3D(const std::string& filename);

glm::mat4 Update(double dt);
Matrix4x4 Update(double dt);

private:
double _time;
Expand Down
26 changes: 14 additions & 12 deletions src/Character.cpp
Expand Up @@ -16,7 +16,7 @@ namespace Donut
{

Character::Character(std::string name):
_name(std::move(name)), _position(glm::vec3(0.0f)), _rotation(glm::quat())
_name(std::move(name)), _position(Vector3(0.0f)), _rotation(Quaternion())
{
_characterController = std::make_unique<CharacterController>(this, &Game::GetInstance().GetWorldPhysics());
_boneBuffer = std::make_unique<GL::TextureBuffer>();
Expand Down Expand Up @@ -79,13 +79,15 @@ void Character::LoadAnimations(const std::string& name)
SetAnimation(_animations.begin()->first);
}

void Character::Draw(const glm::mat4& viewProjection, GL::ShaderProgram& shaderProgram, const ResourceManager& rm)
void Character::Draw(const Matrix4x4& viewProjection, GL::ShaderProgram& shaderProgram, const ResourceManager& rm)
{
const auto localPosition = _position; // -glm::vec3(0.0f, _characterController->GetShape().getHalfHeight() * 2, 0.0f);
const glm::mat4 mvp = glm::translate(viewProjection, localPosition) * glm::toMat4(_rotation);
// wtf just
const auto localPosition = _position; // -Vector3(0.0f, _characterController->GetShape().getHalfHeight() * 2, 0.0f);
//const Matrix4x4 mvp = glm::translate(viewProjection, localPosition) * glm::toMat4(_rotation);
//const Matrix4x4 mvp = glm::translate(viewProjection, localPosition) * glm::toMat4(_rotation);

shaderProgram.Bind(); // todo optimize: should already be bound?
shaderProgram.SetUniformValue("viewProj", mvp);
shaderProgram.SetUniformValue("viewProj", viewProjection);
shaderProgram.SetUniformValue("diffuseTex", 0); // todo optimize: should already be set
shaderProgram.SetUniformValue("boneBuffer", 1); // todo optimize: should already be set

Expand Down Expand Up @@ -118,19 +120,19 @@ void Character::Update(double deltatime)

// update our bonebuffer
auto joints = _skeleton->GetJoints();
std::vector<glm::mat4> matrices(joints.size());
std::vector<Matrix4x4> matrices(joints.size());
for (auto i = 0; i < joints.size(); i++)
matrices[i] = joints[i].finalGlobal;

_boneBuffer->SetBuffer(matrices.data(), matrices.size() * sizeof(glm::mat4));
_boneBuffer->SetBuffer(matrices.data(), matrices.size() * sizeof(Matrix4x4));
}

void Character::SetPosition(const glm::vec3& position)
void Character::SetPosition(const Vector3& position)
{
_position = position;
_characterController->warp(BulletCast<btVector3>(position));
}
void Character::SetRotation(const glm::quat& rotation)
void Character::SetRotation(const Quaternion& rotation)
{
_rotation = rotation;
}
Expand Down Expand Up @@ -158,8 +160,8 @@ void Character::addAnimation(const P3D::Animation& p3dAnim)
auto track = std::make_unique<SkinAnimation::Track>(joint.name);

const auto& jointRestPose = joint.rest;
const auto& jointTranslation = jointRestPose[3];
const auto& jointRotation = glm::quat_cast(jointRestPose);
const auto& jointTranslation = jointRestPose.Translation();
const auto& jointRotation = jointRestPose.Quat();

if (groupNameIndex.find(joint.name) == groupNameIndex.end())
{
Expand Down Expand Up @@ -202,7 +204,7 @@ void Character::addAnimation(const P3D::Animation& p3dAnim)
float x = (int16_t)((value >> 16) & 0xFFFF) / (float)0x7FFF;
float w = (int16_t)(value & 0xFFFF) / (float)0x7FFF;

track->AddRotationKey(frames[i], glm::quat(w, x, y, z));
track->AddRotationKey(frames[i], Quaternion(w, x, y, z));
}
}
else
Expand Down
24 changes: 13 additions & 11 deletions src/Character.h
Expand Up @@ -2,8 +2,10 @@

#pragma once

#include <glm/glm.hpp>
#include <glm/gtx/quaternion.hpp>
#include "Core/Math/Matrix4x4.h"
#include "Core/Math/Quaternion.h"
#include "Core/Math/Vector3.h"

#include <memory>
#include <string>
#include <unordered_map>
Expand Down Expand Up @@ -37,9 +39,9 @@ struct SkeletonJoint
{
std::string name;
uint32_t parent;
glm::mat4 restPose;
Matrix4x4 restPose;

SkeletonJoint(std::string name, const uint32_t parent, const glm::mat4 restPose):
SkeletonJoint(std::string name, const uint32_t parent, const Matrix4x4 restPose):
name(std::move(name)), parent(parent), restPose(restPose)
{
}
Expand All @@ -57,16 +59,16 @@ class Character
const std::string& GetName() const { return _name; }
const std::string& GetModelName() const { return _modelName; }
const std::string& GetAnimName() const { return _animName; }
void SetPosition(const glm::vec3& position);
void SetRotation(const glm::quat& rotation);
const glm::vec3& GetPosition() const { return _position; }
const glm::quat& GetRotation() const { return _rotation; }
void SetPosition(const Vector3& position);
void SetRotation(const Quaternion& rotation);
const Vector3& GetPosition() const { return _position; }
const Quaternion& GetRotation() const { return _rotation; }
void SetAnimation(const std::string&);
CharacterController& GetCharacterController() const { return *_characterController; }
Skeleton& GetSkeleton() const { return *_skeleton; }

void Update(double deltatime);
void Draw(const glm::mat4& viewProjection, GL::ShaderProgram&, const ResourceManager&);
void Draw(const Matrix4x4& viewProjection, GL::ShaderProgram&, const ResourceManager&);

// maybe change this to just anim names
const std::unordered_map<std::string, std::unique_ptr<SkinAnimation>>& GetAnimations() const { return _animations; }
Expand All @@ -82,8 +84,8 @@ class Character
std::string _modelName; // just for debug select
std::string _animName; // just for debug select

glm::vec3 _position;
glm::quat _rotation;
Vector3 _position;
Quaternion _rotation;

std::unique_ptr<CharacterController> _characterController;

Expand Down
18 changes: 9 additions & 9 deletions src/CharacterController.cpp
Expand Up @@ -12,7 +12,7 @@ namespace Donut
CharacterController::CharacterController(Character* character, WorldPhysics* physics):
_character(character), _worldPhysics(physics)
{
_walkDirection = glm::vec3(0.0f, 0.0f, 0.0f);
_walkDirection = Vector3(0.0f, 0.0f, 0.0f);
_verticalVelocity = 0.0f;
_verticalOffset = 0.0f;
_stepHeight = 0.05;
Expand Down Expand Up @@ -58,7 +58,7 @@ void CharacterController::reset(btCollisionWorld* collisionWorld) {}

void CharacterController::setWalkDirection(const btVector3& walkDirection)
{
_walkDirection = BulletCast<glm::vec3>(walkDirection);
_walkDirection = BulletCast<Vector3>(walkDirection);
}

void CharacterController::setVelocityForTimeInterval(const btVector3& velocity, btScalar timeInterval)
Expand All @@ -73,7 +73,7 @@ void CharacterController::warp(const btVector3& origin)
transform.setOrigin(origin);

_physGhostObject->setWorldTransform(transform);
_position = BulletCast<glm::vec3>(origin);
_position = BulletCast<Vector3>(origin);
_targetPosition = origin;
}

Expand All @@ -83,7 +83,7 @@ void CharacterController::preStep(btCollisionWorld* collisionWorld)
while (recoverFromPenetration(collisionWorld) && numPenetrationLoops < 4)
numPenetrationLoops++;

_position = BulletCast<glm::vec3>(_physGhostObject->getWorldTransform().getOrigin());
_position = BulletCast<Vector3>(_physGhostObject->getWorldTransform().getOrigin());
_targetPosition = BulletCast<btVector3>(_position);
}

Expand All @@ -108,7 +108,7 @@ void CharacterController::playerStep(btCollisionWorld* collisionWorld, btScalar
// stepForwardAndStrafe()
stepDown(collisionWorld, dt);

_position = BulletCast<glm::vec3>(_targetPosition);
_position = BulletCast<Vector3>(_targetPosition);
transform.setOrigin(BulletCast<btVector3>(_position));
_physGhostObject->setWorldTransform(transform);
_character->SetPosition(_position);
Expand Down Expand Up @@ -191,7 +191,7 @@ bool CharacterController::recoverFromPenetration(btCollisionWorld* collisionWorl
collisionWorld->getDispatchInfo(),
collisionWorld->getDispatcher());

_position = BulletCast<glm::vec3>(_physGhostObject->getWorldTransform().getOrigin());
_position = BulletCast<Vector3>(_physGhostObject->getWorldTransform().getOrigin());

btScalar maxPenetration = 0.0;

Expand Down Expand Up @@ -233,7 +233,7 @@ bool CharacterController::recoverFromPenetration(btCollisionWorld* collisionWorl
_touchingNormal = pt.m_normalWorldOnB * directionSign;
}

_position += BulletCast<glm::vec3>(pt.m_normalWorldOnB * directionSign * dist * 0.2);
_position += BulletCast<Vector3>(pt.m_normalWorldOnB * directionSign * dist * 0.2);
penetration = true;
}
}
Expand Down Expand Up @@ -266,8 +266,8 @@ btVector3 CharacterController::perpendicularComponent(const btVector3& direction
void CharacterController::stepUp(btCollisionWorld* world)
{
btTransform start, end;
_targetPosition = BulletCast<btVector3>(_position + glm::vec3(0.0f, 1.0f, 0.0f) * _stepHeight);
_position = BulletCast<glm::vec3>(_targetPosition);
_targetPosition = BulletCast<btVector3>(_position + Vector3(0.0f, 1.0f, 0.0f) * _stepHeight);
_position = BulletCast<Vector3>(_targetPosition);
}

void CharacterController::updateTargetPositionBasedOnCollision(const btVector3& hitNormal,
Expand Down
9 changes: 4 additions & 5 deletions src/CharacterController.h
Expand Up @@ -5,8 +5,7 @@
#include <BulletCollision/CollisionDispatch/btGhostObject.h>
#include <BulletCollision/CollisionShapes/btCapsuleShape.h>
#include <BulletDynamics/Character/btKinematicCharacterController.h>
#include <glm/glm.hpp>
#include <glm/gtx/quaternion.hpp>

#include <memory>

class btDiscreteDynamicsWorld;
Expand Down Expand Up @@ -64,12 +63,12 @@ class CharacterController: public btCharacterControllerInterface
btConvexShape* _convexShape;
btManifoldArray _manifoldArray;

glm::vec3 _position;
glm::quat _rotation;
Vector3 _position;
Quaternion _rotation;

btVector3 _targetPosition;

glm::vec3 _walkDirection;
Vector3 _walkDirection;
btScalar _verticalVelocity;
btScalar _verticalOffset;
btScalar _stepHeight;
Expand Down
26 changes: 0 additions & 26 deletions src/Core/BoundingBox.h

This file was deleted.

26 changes: 26 additions & 0 deletions src/Core/Math/BoundingBox.h
@@ -0,0 +1,26 @@
// Copyright 2019 the donut authors. See AUTHORS.md

#pragma once

#include "Core/Math/Vector3.h"

namespace Donut
{

class BoundingBox
{
public:
BoundingBox():
_min(Vector3(0.0f)), _max(Vector3(0.0f)) {}
BoundingBox(const Vector3& min, const Vector3& max):
_min(min), _max(max) {}

Vector3 GetMin() const { return _min; }
Vector3 GetMax() const { return _max; }

private:
Vector3 _min;
Vector3 _max;
};

} // namespace Donut
10 changes: 5 additions & 5 deletions src/Core/BoundingSphere.h → src/Core/Math/BoundingSphere.h
Expand Up @@ -2,7 +2,7 @@

#pragma once

#include <glm/glm.hpp>
#include "Core/Math/Vector3.h"

namespace Donut
{
Expand All @@ -11,15 +11,15 @@ class BoundingSphere
{
public:
BoundingSphere():
_center(glm::vec3(0.0f)), _radius(0.0f) {}
BoundingSphere(const glm::vec3& center, const float radius):
_center(Vector3(0.0f)), _radius(0.0f) {}
BoundingSphere(const Vector3& center, const float radius):
_center(center), _radius(radius) {}

glm::vec3 GetCenter() const { return _center; }
Vector3 GetCenter() const { return _center; }
float GetRadius() const { return _radius; }

private:
glm::vec3 _center;
Vector3 _center;
float _radius;
};

Expand Down
15 changes: 15 additions & 0 deletions src/Core/Math/Fwd.h
@@ -0,0 +1,15 @@
// Copyright 2019 the donut authors. See AUTHORS.md

#pragma once

namespace Donut
{
struct Matrix3x3;
struct Matrix4x4;
struct Quaternion;
struct Vector2;
struct Vector2Int;
struct Vector3;
struct Vector3Int;
struct Vector4;
} // namespace Donut

0 comments on commit 861e294

Please sign in to comment.