mirror of
https://github.com/AxioDL/metaforce.git
synced 2025-10-24 04:15:46 +00:00
More CPhysicsActor imps
This commit is contained in:
parent
c869814da3
commit
130108070d
@ -36,7 +36,8 @@ class CObjectReference
|
||||
Unload();
|
||||
if (IsLoading())
|
||||
CancelLoad();
|
||||
xC_objectStore->ObjectUnreferenced(x4_objTag);
|
||||
if (xC_objectStore)
|
||||
xC_objectStore->ObjectUnreferenced(x4_objTag);
|
||||
}
|
||||
return x0_refCount;
|
||||
}
|
||||
|
@ -9,6 +9,12 @@ CCollidableAABox::CCollidableAABox()
|
||||
{
|
||||
}
|
||||
|
||||
CCollidableAABox::CCollidableAABox(const zeus::CAABox& aabox, const CMaterialList& list)
|
||||
: CCollisionPrimitive(list)
|
||||
, x10_aabox(aabox)
|
||||
{
|
||||
}
|
||||
|
||||
zeus::CAABox CCollidableAABox::Transform(const zeus::CTransform& xf) const
|
||||
{
|
||||
return {xf.origin + x10_aabox.min, xf.origin + x10_aabox.max};
|
||||
|
@ -19,6 +19,7 @@ class CCollidableAABox : public CCollisionPrimitive
|
||||
zeus::CAABox x10_aabox;
|
||||
public:
|
||||
CCollidableAABox();
|
||||
CCollidableAABox(const zeus::CAABox&, const CMaterialList&);
|
||||
|
||||
zeus::CAABox Transform(const zeus::CTransform&) const;
|
||||
virtual u32 GetTableIndex() const;
|
||||
|
@ -14,10 +14,11 @@ static CMaterialList MakeAiMaterialList(const CMaterialList& in)
|
||||
}
|
||||
|
||||
CAi::CAi(TUniqueId uid, bool active, const std::string& name, const CEntityInfo& info, const zeus::CTransform& xf,
|
||||
CModelData&& mData, const zeus::CAABox& box, float mass, const CHealthInfo& hInfo, const CDamageVulnerability& dmgVuln,
|
||||
const CMaterialList& list, ResId, const CActorParameters& actorParams, float f1, float f2)
|
||||
: CPhysicsActor(uid, active, name, info, xf, std::move(mData), MakeAiMaterialList(list), box, SMoverData(mass), actorParams,
|
||||
f1, f2),
|
||||
CModelData&& mData, const zeus::CAABox& box, float mass, const CHealthInfo& hInfo,
|
||||
const CDamageVulnerability& dmgVuln, const CMaterialList& list, ResId, const CActorParameters& actorParams,
|
||||
float stepUp, float stepDown)
|
||||
: CPhysicsActor(uid, active, name, info, xf, std::move(mData), MakeAiMaterialList(list), box, SMoverData(mass),
|
||||
actorParams, stepUp, stepDown),
|
||||
x258_healthInfo(hInfo),
|
||||
x260_damageVulnerability(dmgVuln)
|
||||
{
|
||||
|
@ -6,27 +6,40 @@ namespace urde
|
||||
CPhysicsActor::CPhysicsActor(TUniqueId uid, bool active, const std::string& name, const CEntityInfo& info,
|
||||
const zeus::CTransform& xf, CModelData&& mData, const CMaterialList& matList,
|
||||
const zeus::CAABox& box, const SMoverData& moverData, const CActorParameters& actorParms,
|
||||
float, float)
|
||||
float stepUp, float stepDown)
|
||||
: CActor(uid, active, name, info, xf, std::move(mData), matList, actorParms, kInvalidUniqueId)
|
||||
, xe8_mass(moverData.x30_mass)
|
||||
, xec_massRecip(moverData.x30_mass <= 0.f ? 1.f : 1.f / moverData.x30_mass)
|
||||
, xf8_24_(true)
|
||||
, x150_momentum(moverData.x18_)
|
||||
, x1c0_collisionPrimitive(box, matList)
|
||||
, x200_(xf.buildMatrix3f())
|
||||
, x23c_stepUpHeight(stepUp)
|
||||
, x240_stepDownHeight(stepDown)
|
||||
{
|
||||
SetMass(moverData.x30_mass);
|
||||
MoveCollisionPrimitive(zeus::CVector3f::skZero);
|
||||
SetVelocityOR(moverData.x0_velocity);
|
||||
SetAngularVelocityOR(moverData.xc_angularVelocity);
|
||||
ComputeDerivedQuantities();
|
||||
}
|
||||
|
||||
void CPhysicsActor::Render(const CStateManager &mgr)
|
||||
void CPhysicsActor::Render(const CStateManager &mgr) const
|
||||
{
|
||||
CActor::Render(mgr);
|
||||
}
|
||||
|
||||
zeus::CVector3f CPhysicsActor::GetOrbitPosition(const CStateManager &)
|
||||
zeus::CVector3f CPhysicsActor::GetOrbitPosition(const CStateManager &) const
|
||||
{
|
||||
return GetBoundingBox().center();
|
||||
}
|
||||
|
||||
zeus::CVector3f CPhysicsActor::GetAimPosition(const CStateManager &, float val)
|
||||
zeus::CVector3f CPhysicsActor::GetAimPosition(const CStateManager&, float dt) const
|
||||
{
|
||||
if (val <= 0.0)
|
||||
if (dt <= 0.0)
|
||||
return GetBoundingBox().center();
|
||||
//zeus::CVector3f delta = PredictMotion(val);
|
||||
return zeus::CVector3f();
|
||||
zeus::CVector3f trans = PredictMotion(dt).x0_translation;
|
||||
return GetBoundingBox().center() + trans;
|
||||
}
|
||||
|
||||
void CPhysicsActor::CollidedWith(const TUniqueId &, const CCollisionInfoList &, CStateManager &)
|
||||
@ -100,13 +113,13 @@ zeus::CAABox CPhysicsActor::GetMotionVolume(float dt) const
|
||||
|
||||
zeus::CVector3f CPhysicsActor::CalculateNewVelocityWR_UsingImpulses() const
|
||||
{
|
||||
return x138_velocity + (xec_massRecip * (x168_ + x18c_));
|
||||
return x138_velocity + (xec_massRecip * (x168_impulse + x18c_));
|
||||
}
|
||||
|
||||
zeus::CAABox CPhysicsActor::GetBoundingBox()
|
||||
zeus::CAABox CPhysicsActor::GetBoundingBox() const
|
||||
{
|
||||
return { x1a4_baseBoundingBox.min + x1e8_primitiveOffset + x34_transform.origin,
|
||||
x1a4_baseBoundingBox.max + x1e8_primitiveOffset + x34_transform.origin };
|
||||
x1a4_baseBoundingBox.max + x1e8_primitiveOffset + x34_transform.origin };
|
||||
}
|
||||
|
||||
const zeus::CAABox& CPhysicsActor::GetBaseBoundingBox() const
|
||||
@ -124,16 +137,27 @@ void CPhysicsActor::AddMotionState(const CMotionState& mst)
|
||||
xe4_28_ = true;
|
||||
xe4_29_ = true;
|
||||
|
||||
SetTranslation(x34_transform.origin + mst.x0_origin);
|
||||
SetTranslation(x34_transform.origin + mst.x0_translation);
|
||||
|
||||
x108_ += mst.x1c_;
|
||||
x108_angularMomentum += mst.x1c_velocity;
|
||||
|
||||
ComputeDerivedQuantities();
|
||||
}
|
||||
|
||||
CMotionState CPhysicsActor::GetMotionState() const
|
||||
{
|
||||
return {x34_transform.origin, {x34_transform.buildMatrix3f()}, xfc_, x108_};
|
||||
return {x34_transform.origin, {x34_transform.buildMatrix3f()}, xfc_constantForce, x108_angularMomentum};
|
||||
}
|
||||
|
||||
void CPhysicsActor::SetMotionState(const CMotionState &mst)
|
||||
{
|
||||
x34_transform = zeus::CTransform::Translate(x34_transform.origin) * zeus::CMatrix3f(mst.xc_orientation);
|
||||
|
||||
xe4_27_ = true;
|
||||
xe4_28_ = true;
|
||||
xe4_29_ = true;
|
||||
SetTranslation(mst.x0_translation);
|
||||
ComputeDerivedQuantities();
|
||||
}
|
||||
|
||||
void CPhysicsActor::SetInertiaTensorScalar(float tensor)
|
||||
@ -158,7 +182,7 @@ void CPhysicsActor::SetMass(float mass)
|
||||
void CPhysicsActor::SetAngularVelocityOR(const zeus::CAxisAngle& angVel)
|
||||
{
|
||||
x144_angularVelocity = x34_transform.rotate(angVel);
|
||||
x108_ = xf0_inertiaTensor * x144_angularVelocity;
|
||||
x108_angularMomentum = xf0_inertiaTensor * x144_angularVelocity;
|
||||
}
|
||||
|
||||
zeus::CAxisAngle CPhysicsActor::GetAngularVelocityOR() const
|
||||
@ -169,13 +193,13 @@ zeus::CAxisAngle CPhysicsActor::GetAngularVelocityOR() const
|
||||
void CPhysicsActor::SetAngularVelocityWR(const zeus::CAxisAngle& angVel)
|
||||
{
|
||||
x144_angularVelocity = angVel;
|
||||
x108_ = xf0_inertiaTensor * x144_angularVelocity;
|
||||
x108_angularMomentum = xf0_inertiaTensor * x144_angularVelocity;
|
||||
}
|
||||
|
||||
void CPhysicsActor::SetVelocityWR(const zeus::CVector3f &vel)
|
||||
{
|
||||
x138_velocity = vel;
|
||||
xfc_ = xe8_mass * x138_velocity;
|
||||
xfc_constantForce = xe8_mass * x138_velocity;
|
||||
}
|
||||
|
||||
void CPhysicsActor::SetVelocityOR(const zeus::CVector3f& vel)
|
||||
@ -185,7 +209,7 @@ void CPhysicsActor::SetVelocityOR(const zeus::CVector3f& vel)
|
||||
|
||||
zeus::CVector3f CPhysicsActor::GetTotalForcesWR() const
|
||||
{
|
||||
return x15c_ + x150_;
|
||||
return x15c_force + x150_momentum;
|
||||
}
|
||||
|
||||
void CPhysicsActor::RotateInOneFrameOR(const zeus::CQuaternion &q, float d)
|
||||
@ -193,52 +217,254 @@ void CPhysicsActor::RotateInOneFrameOR(const zeus::CQuaternion &q, float d)
|
||||
x198_ += GetRotateToORAngularMomentumWR(q, d);
|
||||
}
|
||||
|
||||
zeus::CVector3f CPhysicsActor::GetRotateToORAngularMomentumWR(const zeus::CQuaternion& q, float d) const
|
||||
void CPhysicsActor::MoveInOneFrameOR(const zeus::CVector3f &trans, float d)
|
||||
{
|
||||
x18c_ += GetMoveToORImpulseWR(trans, d);
|
||||
}
|
||||
|
||||
void CPhysicsActor::RotateToOR(const zeus::CQuaternion& q, float d)
|
||||
{
|
||||
x108_angularMomentum = GetRotateToORAngularMomentumWR(q, d);
|
||||
ComputeDerivedQuantities();
|
||||
}
|
||||
|
||||
void CPhysicsActor::MoveToOR(const zeus::CVector3f& trans, float d)
|
||||
{
|
||||
xfc_constantForce = GetMoveToORImpulseWR(trans, d);
|
||||
ComputeDerivedQuantities();
|
||||
}
|
||||
|
||||
void CPhysicsActor::sub_8011B098(const zeus::CVector3f& trans, float d)
|
||||
{
|
||||
x18c_ += xe8_mass * (trans - x34_transform.origin) * (1.f / d);
|
||||
}
|
||||
|
||||
void CPhysicsActor::MoveToWR(const zeus::CVector3f& trans, float d)
|
||||
{
|
||||
xfc_constantForce = xe8_mass * (trans - x34_transform.origin) * (1.f / d);
|
||||
ComputeDerivedQuantities();
|
||||
}
|
||||
|
||||
zeus::CAxisAngle CPhysicsActor::GetRotateToORAngularMomentumWR(const zeus::CQuaternion& q, float d) const
|
||||
{
|
||||
if (q.w > 0.99999976)
|
||||
return zeus::CVector3f::skZero;
|
||||
return zeus::CAxisAngle::skZero;
|
||||
return (xf0_inertiaTensor * (((2.f * std::acos(q.w)) * (1.f / d)) *
|
||||
x34_transform.rotate({q.x, q.y, q.z}).normalized()));
|
||||
}
|
||||
|
||||
zeus::CVector3f CPhysicsActor::GetMoveToORImpulseWR(const zeus::CVector3f &trans, float d) const
|
||||
{
|
||||
return (xe8_mass * x34_transform.rotate(trans)) * (1.f / d);
|
||||
}
|
||||
|
||||
void CPhysicsActor::ClearImpulses()
|
||||
{
|
||||
x18c_ = x168_ = zeus::CVector3f::skZero;
|
||||
x198_ = x180_ = zeus::CAxisAngle::skZero;
|
||||
x18c_ = x168_impulse = zeus::CVector3f::skZero;
|
||||
x198_ = x180_angularImpulse = zeus::CAxisAngle::skZero;
|
||||
}
|
||||
|
||||
void CPhysicsActor::ClearForcesAndTorques()
|
||||
{
|
||||
x18c_ = x168_ = x15c_ = zeus::CVector3f::skZero;
|
||||
x198_ = x180_ = x174_ = zeus::CAxisAngle::skZero;
|
||||
x18c_ = x168_impulse = x15c_force = zeus::CVector3f::skZero;
|
||||
x198_ = x180_angularImpulse = x174_torque = zeus::CAxisAngle::skZero;
|
||||
}
|
||||
|
||||
void CPhysicsActor::Stop()
|
||||
{
|
||||
ClearForcesAndTorques();
|
||||
xfc_ = zeus::CVector3f::skZero;
|
||||
x108_ = zeus::CAxisAngle::skZero;
|
||||
xfc_constantForce = zeus::CVector3f::skZero;
|
||||
x108_angularMomentum = zeus::CAxisAngle::skZero;
|
||||
ComputeDerivedQuantities();
|
||||
}
|
||||
|
||||
void CPhysicsActor::ComputeDerivedQuantities()
|
||||
{
|
||||
x138_velocity = xec_massRecip * xfc_;
|
||||
x138_velocity = xec_massRecip * xfc_constantForce;
|
||||
x114_ = x34_transform.buildMatrix3f();
|
||||
x144_angularVelocity = xf0_inertiaTensor * x108_;
|
||||
x144_angularVelocity = xf0_inertiaTensor * x108_angularMomentum;
|
||||
}
|
||||
|
||||
bool CPhysicsActor::WillMove(const CStateManager&)
|
||||
{
|
||||
if (!zeus::close_enough(zeus::CVector3f::skZero, x138_velocity) ||
|
||||
!zeus::close_enough(zeus::CVector3f::skZero, x168_) ||
|
||||
!zeus::close_enough(zeus::CVector3f::skZero, x18c_) ||
|
||||
!zeus::close_enough(zeus::CVector3f::skZero, x144_angularVelocity) ||
|
||||
!zeus::close_enough(zeus::CVector3f::skZero, x180_) ||
|
||||
!zeus::close_enough(zeus::CVector3f::skZero, GetTotalForcesWR()))
|
||||
!zeus::close_enough(zeus::CVector3f::skZero, x168_impulse) ||
|
||||
!zeus::close_enough(zeus::CVector3f::skZero, x18c_) ||
|
||||
!zeus::close_enough(zeus::CVector3f::skZero, x144_angularVelocity) ||
|
||||
!zeus::close_enough(zeus::CVector3f::skZero, x180_angularImpulse) ||
|
||||
!zeus::close_enough(zeus::CVector3f::skZero, GetTotalForcesWR()))
|
||||
return true;
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
void CPhysicsActor::SetPhysicsState(const CPhysicsState &state)
|
||||
{
|
||||
SetTranslation(state.GetTranslation());
|
||||
x34_transform = zeus::CTransform::Translate(x34_transform.origin) * zeus::CMatrix3f(state.GetOrientation());
|
||||
xe4_27_ = true;
|
||||
xe4_28_ = true;
|
||||
xe4_29_ = true;
|
||||
|
||||
xfc_constantForce = state.GetConstantForceWR();
|
||||
x108_angularMomentum = state.GetAngularMomentumWR();;
|
||||
x150_momentum = state.GetMomentumWR();
|
||||
x15c_force = state.GetForceWR();
|
||||
x168_impulse = state.GetImpulseWR();
|
||||
x174_torque = state.GetTorque();
|
||||
x180_angularImpulse = state.GetAngularImpulseWR();
|
||||
ComputeDerivedQuantities();
|
||||
}
|
||||
|
||||
CPhysicsState CPhysicsActor::GetPhysicsState() const
|
||||
{
|
||||
return {x34_transform.origin, {x34_transform.buildMatrix3f()}, xfc_constantForce, x108_angularMomentum,
|
||||
x150_momentum, x15c_force, x168_impulse, x174_torque, x180_angularImpulse};
|
||||
}
|
||||
|
||||
CMotionState CPhysicsActor::PredictMotion_Internal(float dt) const
|
||||
{
|
||||
if (xf8_25_)
|
||||
return PredictMotion(dt);
|
||||
|
||||
CMotionState msl = PredictLinearMotion(dt);
|
||||
CMotionState msa = PredictAngularMotion(dt);
|
||||
return {msl.x0_translation, msa.xc_orientation, msl.x1c_velocity, msa.x28_angularVelocity};
|
||||
}
|
||||
|
||||
CMotionState CPhysicsActor::PredictMotion(float dt) const
|
||||
{
|
||||
CMotionState msl = PredictLinearMotion(dt);
|
||||
CMotionState msa = PredictAngularMotion(dt);
|
||||
return {msl.x0_translation, msa.xc_orientation, msl.x1c_velocity, msa.x28_angularVelocity};
|
||||
}
|
||||
|
||||
CMotionState CPhysicsActor::PredictLinearMotion(float dt) const
|
||||
{
|
||||
zeus::CVector3f velocity = CalculateNewVelocityWR_UsingImpulses();
|
||||
return {velocity * dt, zeus::CNUQuaternion::skNoRotation,
|
||||
((x15c_force + x150_momentum) * dt) + x168_impulse,
|
||||
zeus::CAxisAngle::skZero};
|
||||
}
|
||||
|
||||
CMotionState CPhysicsActor::PredictAngularMotion(float dt) const
|
||||
{
|
||||
const zeus::CVector3f v1 = xf4_inertiaTensorRecip * (x180_angularImpulse + x198_);
|
||||
zeus::CNUQuaternion q = 0.5f * zeus::CNUQuaternion({0.f, x144_angularVelocity + v1});
|
||||
return {zeus::CVector3f::skZero,
|
||||
q * zeus::CNUQuaternion(x34_transform.buildMatrix3f()) * dt,
|
||||
zeus::CVector3f::skZero,
|
||||
(x174_torque * dt) + x180_angularImpulse};
|
||||
}
|
||||
|
||||
void CPhysicsActor::ApplyForceOR(const zeus::CVector3f& force, const zeus::CAxisAngle& torque)
|
||||
{
|
||||
x15c_force += x34_transform.rotate(force);
|
||||
x174_torque += x34_transform.rotate(torque);
|
||||
}
|
||||
|
||||
void CPhysicsActor::ApplyForceWR(const zeus::CVector3f &force, const zeus::CAxisAngle& torque)
|
||||
{
|
||||
x15c_force += force;
|
||||
x174_torque += torque;
|
||||
}
|
||||
|
||||
void CPhysicsActor::ApplyImpulseOR(const zeus::CVector3f &impulse, const zeus::CAxisAngle &angle)
|
||||
{
|
||||
x168_impulse += x34_transform.rotate(impulse);
|
||||
x180_angularImpulse += x34_transform.rotate(angle);
|
||||
}
|
||||
|
||||
void CPhysicsActor::ApplyImpulseWR(const zeus::CVector3f &impulse, const zeus::CAxisAngle& angleImp)
|
||||
{
|
||||
x168_impulse += impulse;
|
||||
x180_angularImpulse += angleImp;
|
||||
}
|
||||
|
||||
void CPhysicsActor::ApplyTorqueWR(const zeus::CVector3f& torque)
|
||||
{
|
||||
x174_torque += torque;
|
||||
}
|
||||
|
||||
void CPhysicsActor::UseCollisionImpulses()
|
||||
{
|
||||
xfc_constantForce += x168_impulse;
|
||||
x108_angularMomentum += x180_angularImpulse;
|
||||
|
||||
x168_impulse = zeus::CVector3f::skZero;
|
||||
x180_angularImpulse = zeus::CAxisAngle::skZero;
|
||||
ComputeDerivedQuantities();
|
||||
}
|
||||
|
||||
CPhysicsState::CPhysicsState(const zeus::CVector3f& translation, const zeus::CQuaternion& orient,
|
||||
const zeus::CVector3f& v2, const zeus::CAxisAngle& a1,
|
||||
const zeus::CVector3f& v3, const zeus::CVector3f& v4,
|
||||
const zeus::CVector3f& v5, const zeus::CAxisAngle& a2, const zeus::CAxisAngle& a3)
|
||||
: x0_translation(translation)
|
||||
, xc_orientation(orient)
|
||||
, x1c_constantForce(v2)
|
||||
, x28_angularMomentum(a1)
|
||||
, x34_momentum(v3)
|
||||
, x40_force(v4)
|
||||
, x4c_impulse(v5)
|
||||
, x58_torque(a2)
|
||||
, x64_angularImpulse(a3)
|
||||
{
|
||||
}
|
||||
|
||||
void CPhysicsState::SetOrientation(const zeus::CQuaternion& orient)
|
||||
{
|
||||
xc_orientation = orient;
|
||||
}
|
||||
|
||||
const zeus::CQuaternion& CPhysicsState::GetOrientation() const
|
||||
{
|
||||
return xc_orientation;
|
||||
}
|
||||
|
||||
void CPhysicsState::SetTranslation(const zeus::CVector3f& tr)
|
||||
{
|
||||
x0_translation = tr;
|
||||
}
|
||||
|
||||
const zeus::CVector3f& CPhysicsState::GetTranslation() const
|
||||
{
|
||||
return x0_translation;
|
||||
}
|
||||
|
||||
const zeus::CVector3f& CPhysicsState::GetConstantForceWR() const
|
||||
{
|
||||
return x1c_constantForce;
|
||||
}
|
||||
|
||||
const zeus::CAxisAngle& CPhysicsState::GetAngularMomentumWR() const
|
||||
{
|
||||
return x28_angularMomentum;
|
||||
}
|
||||
|
||||
const zeus::CVector3f& CPhysicsState::GetMomentumWR() const
|
||||
{
|
||||
return x34_momentum;
|
||||
}
|
||||
|
||||
const zeus::CVector3f& CPhysicsState::GetForceWR() const
|
||||
{
|
||||
return x40_force;
|
||||
}
|
||||
|
||||
const zeus::CVector3f& CPhysicsState::GetImpulseWR() const
|
||||
{
|
||||
return x4c_impulse;
|
||||
}
|
||||
|
||||
const zeus::CAxisAngle& CPhysicsState::GetTorque() const
|
||||
{
|
||||
return x58_torque;
|
||||
}
|
||||
|
||||
const zeus::CAxisAngle& CPhysicsState::GetAngularImpulseWR() const
|
||||
{
|
||||
return x64_angularImpulse;
|
||||
}
|
||||
|
||||
}
|
||||
|
@ -22,19 +22,48 @@ struct SMoverData
|
||||
|
||||
struct CMotionState
|
||||
{
|
||||
zeus::CVector3f x0_origin;
|
||||
zeus::CQuaternion xc_rotation;
|
||||
zeus::CVector3f x1c_;
|
||||
zeus::CAxisAngle x28_;
|
||||
CMotionState(const zeus::CVector3f& origin, const zeus::CNUQuaternion& rotation,
|
||||
const zeus::CVector3f& v2, const zeus::CAxisAngle& angle)
|
||||
: x0_origin(origin)
|
||||
, xc_rotation(rotation)
|
||||
, x1c_(v2)
|
||||
, x28_(angle)
|
||||
zeus::CVector3f x0_translation;
|
||||
zeus::CNUQuaternion xc_orientation;
|
||||
zeus::CVector3f x1c_velocity;
|
||||
zeus::CAxisAngle x28_angularVelocity;
|
||||
CMotionState(const zeus::CVector3f& origin, const zeus::CNUQuaternion& orientation,
|
||||
const zeus::CVector3f& velocity, const zeus::CAxisAngle& angle)
|
||||
: x0_translation(origin)
|
||||
, xc_orientation(orientation)
|
||||
, x1c_velocity(velocity)
|
||||
, x28_angularVelocity(angle)
|
||||
{}
|
||||
};
|
||||
|
||||
class CPhysicsState
|
||||
{
|
||||
zeus::CVector3f x0_translation;
|
||||
zeus::CQuaternion xc_orientation;
|
||||
zeus::CVector3f x1c_constantForce;
|
||||
zeus::CAxisAngle x28_angularMomentum;
|
||||
zeus::CVector3f x34_momentum;
|
||||
zeus::CVector3f x40_force;
|
||||
zeus::CVector3f x4c_impulse;
|
||||
zeus::CAxisAngle x58_torque;
|
||||
zeus::CAxisAngle x64_angularImpulse;
|
||||
public:
|
||||
CPhysicsState(const zeus::CVector3f&, const zeus::CQuaternion&, const zeus::CVector3f&,
|
||||
const zeus::CAxisAngle&, const zeus::CVector3f&, const zeus::CVector3f&,
|
||||
const zeus::CVector3f&, const zeus::CAxisAngle&, const zeus::CAxisAngle&);
|
||||
|
||||
void SetOrientation(const zeus::CQuaternion&);
|
||||
const zeus::CQuaternion& GetOrientation() const;
|
||||
void SetTranslation(const zeus::CVector3f&);
|
||||
const zeus::CVector3f& GetTranslation() const;
|
||||
const zeus::CVector3f& GetConstantForceWR() const;
|
||||
const zeus::CAxisAngle& GetAngularMomentumWR() const;
|
||||
const zeus::CVector3f& GetMomentumWR() const;
|
||||
const zeus::CVector3f& GetForceWR() const;
|
||||
const zeus::CVector3f& GetImpulseWR() const;
|
||||
const zeus::CAxisAngle& GetTorque() const;
|
||||
const zeus::CAxisAngle& GetAngularImpulseWR() const;
|
||||
};
|
||||
|
||||
class CPhysicsActor : public CActor
|
||||
{
|
||||
protected:
|
||||
@ -42,27 +71,35 @@ protected:
|
||||
float xec_massRecip;
|
||||
float xf0_inertiaTensor;
|
||||
float xf4_inertiaTensorRecip;
|
||||
bool xf8_;
|
||||
bool xf9_;
|
||||
zeus::CVector3f xfc_;
|
||||
zeus::CAxisAngle x108_;
|
||||
union
|
||||
{
|
||||
struct
|
||||
{
|
||||
bool xf8_24_ : 1;
|
||||
bool xf8_25_ : 1;
|
||||
};
|
||||
u8 _dummy = 0;
|
||||
};
|
||||
bool xf9_ = false;
|
||||
zeus::CVector3f xfc_constantForce;
|
||||
zeus::CAxisAngle x108_angularMomentum;
|
||||
zeus::CMatrix3f x114_;
|
||||
zeus::CVector3f x138_velocity;
|
||||
zeus::CAxisAngle x144_angularVelocity;
|
||||
zeus::CVector3f x150_;
|
||||
zeus::CVector3f x15c_;
|
||||
zeus::CVector3f x168_;
|
||||
zeus::CAxisAngle x174_;
|
||||
zeus::CAxisAngle x180_;
|
||||
zeus::CVector3f x150_momentum;
|
||||
zeus::CVector3f x15c_force;
|
||||
zeus::CVector3f x168_impulse;
|
||||
zeus::CAxisAngle x174_torque;
|
||||
zeus::CAxisAngle x180_angularImpulse;
|
||||
zeus::CVector3f x18c_;
|
||||
zeus::CAxisAngle x198_;
|
||||
zeus::CAABox x1a4_baseBoundingBox;
|
||||
CCollidableAABox x1c0_collisionPrimitive;
|
||||
zeus::CVector3f x1e8_primitiveOffset;
|
||||
zeus::CQuaternion x200_;
|
||||
zeus::CVector3f x210_;
|
||||
zeus::CVector3f x21c_;
|
||||
bool x234_;
|
||||
zeus::CNUQuaternion x200_;
|
||||
zeus::CAxisAngle x210_;
|
||||
zeus::CAxisAngle x21c_;
|
||||
bool x234_ = false;
|
||||
float x238_ = 1000000.0f;
|
||||
float x23c_stepUpHeight;
|
||||
float x240_stepDownHeight;
|
||||
@ -76,9 +113,9 @@ public:
|
||||
const zeus::CAABox&, const SMoverData&, const CActorParameters&,
|
||||
float, float);
|
||||
|
||||
void Render(const CStateManager& mgr);
|
||||
zeus::CVector3f GetOrbitPosition(const CStateManager&);
|
||||
zeus::CVector3f GetAimPosition(const CStateManager&, float val);
|
||||
void Render(const CStateManager& mgr) const;
|
||||
zeus::CVector3f GetOrbitPosition(const CStateManager&) const;
|
||||
zeus::CVector3f GetAimPosition(const CStateManager&, float val) const;
|
||||
virtual const CCollisionPrimitive& GetCollisionPrimitive() const;
|
||||
virtual zeus::CTransform GetPrimitiveTransform() const;
|
||||
virtual void CollidedWith(const TUniqueId&, const CCollisionInfoList&, CStateManager&);
|
||||
@ -92,10 +129,11 @@ public:
|
||||
void SetBoundingBox(const zeus::CAABox& box);
|
||||
zeus::CAABox GetMotionVolume(float f31) const;
|
||||
zeus::CVector3f CalculateNewVelocityWR_UsingImpulses() const;
|
||||
zeus::CAABox GetBoundingBox();
|
||||
zeus::CAABox GetBoundingBox() const;
|
||||
const zeus::CAABox& GetBaseBoundingBox() const;
|
||||
void AddMotionState(const CMotionState& mst);
|
||||
CMotionState GetMotionState() const;
|
||||
void SetMotionState(const CMotionState& mst);
|
||||
void SetInertiaTensorScalar(float tensor);
|
||||
void SetMass(float mass);
|
||||
void SetAngularVelocityOR(const zeus::CAxisAngle& angVel);
|
||||
@ -105,12 +143,32 @@ public:
|
||||
void SetVelocityOR(const zeus::CVector3f& vel);
|
||||
zeus::CVector3f GetTotalForcesWR() const;
|
||||
void RotateInOneFrameOR(const zeus::CQuaternion& q, float d);
|
||||
zeus::CVector3f GetRotateToORAngularMomentumWR(const zeus::CQuaternion& q, float d) const;
|
||||
void MoveInOneFrameOR(const zeus::CVector3f& trans, float d);
|
||||
void RotateToOR(const zeus::CQuaternion& q, float d);
|
||||
void MoveToOR(const zeus::CVector3f& trans, float d);
|
||||
void sub_8011B098(const zeus::CVector3f &v1, float d);
|
||||
void MoveToWR(const zeus::CVector3f& trans, float d);
|
||||
zeus::CAxisAngle GetRotateToORAngularMomentumWR(const zeus::CQuaternion& q, float d) const;
|
||||
zeus::CVector3f GetMoveToORImpulseWR(const zeus::CVector3f& trans, float d) const;
|
||||
void ClearImpulses();
|
||||
void ClearForcesAndTorques();
|
||||
void Stop();
|
||||
void ComputeDerivedQuantities();
|
||||
bool WillMove(const CStateManager&);
|
||||
void SetPhysicsState(const CPhysicsState& state);
|
||||
CPhysicsState GetPhysicsState() const;
|
||||
|
||||
CMotionState PredictMotion_Internal(float) const;
|
||||
CMotionState PredictMotion(float dt) const;
|
||||
CMotionState PredictLinearMotion(float dt) const;
|
||||
CMotionState PredictAngularMotion(float dt) const;
|
||||
void ApplyForceOR(const zeus::CVector3f& force, const zeus::CAxisAngle& angle);
|
||||
void ApplyForceWR(const zeus::CVector3f& force, const zeus::CAxisAngle& angle);
|
||||
void ApplyImpulseOR(const zeus::CVector3f& impulse, const zeus::CAxisAngle& angle);
|
||||
void ApplyImpulseWR(const zeus::CVector3f& impulse, const zeus::CAxisAngle& angle);
|
||||
void ApplyTorqueWR(const zeus::CVector3f& torque);
|
||||
|
||||
void UseCollisionImpulses();
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -14,9 +14,11 @@ static CModelData MakePlayerAnimRes(ResId resId, const zeus::CVector3f& scale)
|
||||
}
|
||||
|
||||
CPlayer::CPlayer(TUniqueId uid, const zeus::CTransform& xf, const zeus::CAABox& aabb, unsigned int resId,
|
||||
const zeus::CVector3f& playerScale, float f1, float f2, float f3, float f4, const CMaterialList& ml)
|
||||
const zeus::CVector3f& playerScale, float mass, float stepUp, float stepDown, float f4,
|
||||
const CMaterialList& ml)
|
||||
: CPhysicsActor(uid, true, "CPlayer", CEntityInfo(kInvalidAreaId, CEntity::NullConnectionList),
|
||||
xf, MakePlayerAnimRes(resId, playerScale), ml, aabb, SMoverData(f1), CActorParameters::None(), f2, f3)
|
||||
xf, MakePlayerAnimRes(resId, playerScale), ml, aabb, SMoverData(mass), CActorParameters::None(),
|
||||
stepUp, stepDown)
|
||||
{
|
||||
x768_morphball.reset(new CMorphBall(*this, f4));
|
||||
}
|
||||
|
@ -14,10 +14,12 @@ CMaterialList MakeDockMaterialList()
|
||||
return list;
|
||||
}
|
||||
|
||||
CScriptDock::CScriptDock(TUniqueId uid, const std::string &name, const CEntityInfo &info, const zeus::CVector3f position,
|
||||
const zeus::CVector3f& extents, s32 dock, TAreaId area, bool active, s32 w1, bool b1)
|
||||
CScriptDock::CScriptDock(TUniqueId uid, const std::string &name, const CEntityInfo &info,
|
||||
const zeus::CVector3f position, const zeus::CVector3f& extents, s32 dock, TAreaId area,
|
||||
bool active, s32 w1, bool b1)
|
||||
: CPhysicsActor(uid, active, name, info, zeus::CTransform(zeus::CMatrix3f::skIdentityMatrix3f, position),
|
||||
CModelData::CModelDataNull(), MakeDockMaterialList(), zeus::CAABox(-extents * 0.5f, extents * 0.5f), SMoverData(1.f), CActorParameters::None(), 0.3f, 0.1f),
|
||||
CModelData::CModelDataNull(), MakeDockMaterialList(), zeus::CAABox(-extents * 0.5f, extents * 0.5f),
|
||||
SMoverData(1.f), CActorParameters::None(), 0.3f, 0.1f),
|
||||
x258_(w1),
|
||||
x25c_dock(dock),
|
||||
x260_area(area),
|
||||
|
@ -2,10 +2,11 @@
|
||||
|
||||
namespace urde
|
||||
{
|
||||
CScriptPickup::CScriptPickup(TUniqueId uid, const std::string& name, const CEntityInfo& info, const zeus::CTransform& xf,
|
||||
CModelData&& mData, const CActorParameters& aParams, const zeus::CAABox& aabb,
|
||||
s32, s32, s32, s32, float, float, float, float, bool active)
|
||||
: CPhysicsActor(uid, active, name, info, xf, std::move(mData), CMaterialList(), aabb, SMoverData(1.f), aParams, 0.3f, 0.1f)
|
||||
CScriptPickup::CScriptPickup(TUniqueId uid, const std::string& name, const CEntityInfo& info,
|
||||
const zeus::CTransform& xf, CModelData&& mData, const CActorParameters& aParams,
|
||||
const zeus::CAABox& aabb, s32, s32, s32, s32, float, float, float, float, bool active)
|
||||
: CPhysicsActor(uid, active, name, info, xf, std::move(mData), CMaterialList(), aabb, SMoverData(1.f), aParams,
|
||||
0.3f, 0.1f)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
Loading…
x
Reference in New Issue
Block a user