Add PhysicsEffects to Extras. The build is only tested on Windows and Android.

The Android/NEON optimized version of Physics Effects is thanks to Graham Rhodes and Anthony Hamilton, See Issue 587
This commit is contained in:
erwin.coumans
2012-03-05 04:59:58 +00:00
parent 6cf8dfc202
commit a93a661b94
462 changed files with 86626 additions and 0 deletions

View File

@@ -0,0 +1,39 @@
/*
Physics Effects Copyright(C) 2010 Sony Computer Entertainment Inc.
All rights reserved.
Physics Effects is open software; you can redistribute it and/or
modify it under the terms of the BSD License.
Physics Effects is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
See the BSD License for more details.
A copy of the BSD License is distributed with
Physics Effects under the filename: physics_effects_license.txt
*/
#ifndef _SCE_PFX_CONSTRAINT_PAIR_H
#define _SCE_PFX_CONSTRAINT_PAIR_H
#include "../sort/pfx_sort_data.h"
#include "../broadphase/pfx_broadphase_pair.h"
namespace sce {
namespace PhysicsEffects {
typedef PfxSortData16 PfxConstraintPair;
//J PfxBroadphasePairと共通
//E Same as PfxBroadphasePair
SCE_PFX_FORCE_INLINE void pfxSetConstraintId(PfxConstraintPair &pair,PfxUInt32 i) {pair.set32(2,i);}
SCE_PFX_FORCE_INLINE void pfxSetNumConstraints(PfxConstraintPair &pair,PfxUInt8 n) {pair.set8(7,n);}
SCE_PFX_FORCE_INLINE PfxUInt32 pfxGetConstraintId(const PfxConstraintPair &pair) {return pair.get32(2);}
SCE_PFX_FORCE_INLINE PfxUInt8 pfxGetNumConstraints(const PfxConstraintPair &pair) {return pair.get8(7);}
} //namespace PhysicsEffects
} //namespace sce
#endif // _SCE_PFX_CONSTRAINT_PAIR_H

View File

@@ -0,0 +1,40 @@
/*
Physics Effects Copyright(C) 2010 Sony Computer Entertainment Inc.
All rights reserved.
Physics Effects is open software; you can redistribute it and/or
modify it under the terms of the BSD License.
Physics Effects is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
See the BSD License for more details.
A copy of the BSD License is distributed with
Physics Effects under the filename: physics_effects_license.txt
*/
#ifndef _SCE_PFX_CONSTRAINT_ROW_H
#define _SCE_PFX_CONSTRAINT_ROW_H
#include "../base/pfx_vec_utils.h"
namespace sce {
namespace PhysicsEffects {
#include "../base/pfx_common.h"
//E Don't change following order of parameters
struct SCE_PFX_ALIGNED(16) PfxConstraintRow {
PfxFloat m_normal[3];
PfxFloat m_rhs;
PfxFloat m_jacDiagInv;
PfxFloat m_lowerLimit;
PfxFloat m_upperLimit;
PfxFloat m_accumImpulse;
};
} //namespace PhysicsEffects
} //namespace sce
#endif // _SCE_PFX_CONSTRAINT_ROW_H

View File

@@ -0,0 +1,59 @@
/*
Physics Effects Copyright(C) 2010 Sony Computer Entertainment Inc.
All rights reserved.
Physics Effects is open software; you can redistribute it and/or
modify it under the terms of the BSD License.
Physics Effects is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
See the BSD License for more details.
A copy of the BSD License is distributed with
Physics Effects under the filename: physics_effects_license.txt
*/
#ifndef _SCE_PFX_CONTACT_CONSTRAINT_H
#define _SCE_PFX_CONTACT_CONSTRAINT_H
#include "../rigidbody/pfx_rigid_state.h"
#include "pfx_constraint_row.h"
#include "pfx_solver_body.h"
namespace sce {
namespace PhysicsEffects {
void pfxSetupContactConstraint(
PfxConstraintRow &constraintResponse,
PfxConstraintRow &constraintFriction1,
PfxConstraintRow &constraintFriction2,
PfxFloat penetrationDepth,
PfxFloat restitution,
PfxFloat friction,
const PfxVector3 &contactNormal,
const PfxVector3 &contactPointA,
const PfxVector3 &contactPointB,
const PfxRigidState &stateA,
const PfxRigidState &stateB,
PfxSolverBody &solverBodyA,
PfxSolverBody &solverBodyB,
PfxFloat separateBias,
PfxFloat timeStep
);
void pfxSolveContactConstraint(
PfxConstraintRow &constraintResponse,
PfxConstraintRow &constraintFriction1,
PfxConstraintRow &constraintFriction2,
const PfxVector3 &contactPointA,
const PfxVector3 &contactPointB,
PfxSolverBody &solverBodyA,
PfxSolverBody &solverBodyB,
PfxFloat friction
);
} //namespace PhysicsEffects
} //namespace sce
#endif // _SCE_PFX_CONTACT_CONSTRAINT_H

View File

@@ -0,0 +1,121 @@
/*
Physics Effects Copyright(C) 2010 Sony Computer Entertainment Inc.
All rights reserved.
Physics Effects is open software; you can redistribute it and/or
modify it under the terms of the BSD License.
Physics Effects is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
See the BSD License for more details.
A copy of the BSD License is distributed with
Physics Effects under the filename: physics_effects_license.txt
*/
#ifndef _SCE_PFX_INTEGRATE_H_
#define _SCE_PFX_INTEGRATE_H_
#include "../base/pfx_common.h"
#include "../rigidbody/pfx_rigid_body.h"
#include "../rigidbody/pfx_rigid_state.h"
namespace sce {
namespace PhysicsEffects {
template <typename T>
static SCE_PFX_FORCE_INLINE T pfxRungeKutta(const T &deriv,PfxFloat dt)
{
T k0, k1, k2, k3;
k0 = deriv * dt;
k1 = (deriv + k0 * 0.5f) * dt;
k2 = (deriv + k1 * 0.5f) * dt;
k3 = (deriv + k2) * dt;
return (k0 + k1*2.0f + k2*2.0f + k3) / 6.0f;
}
#define SCE_PFX_MOTION_MASK_INTEGRATE ((1<<kPfxMotionTypeFixed)|(1<<kPfxMotionTypeTrigger))
static SCE_PFX_FORCE_INLINE
void pfxIntegrate(
PfxRigidState &state,
const PfxRigidBody &body,
PfxFloat timeStep
)
{
(void) body;
if(((1<<state.getMotionMask())&SCE_PFX_MOTION_MASK_INTEGRATE) || state.isAsleep()) return;
PfxVector3 position = state.getPosition();
PfxQuat orientation = state.getOrientation();
PfxVector3 linearVelocity = state.getLinearVelocity();
PfxVector3 angularVelocity = state.getAngularVelocity();
PfxVector3 dx = linearVelocity;
PfxQuat dq = PfxQuat(angularVelocity,0) * orientation * 0.5f;
#ifdef SCE_PFX_ODE_EULER
position += dx * timeStep;
orientation += dq * timeStep;
orientation = normalize(orientation);
#else
position += pfxRungeKutta(dx,timeStep);
orientation += pfxRungeKutta(dq,timeStep);
orientation = normalize(orientation);
#endif
state.setPosition(position);
state.setOrientation(orientation);
}
#define SCE_PFX_MOTION_MASK_APPLYFORCE ((1<<kPfxMotionTypeFixed)|(1<<kPfxMotionTypeTrigger)|(1<<kPfxMotionTypeKeyframe))
static SCE_PFX_FORCE_INLINE
void pfxApplyExternalForce(
PfxRigidState &state,
const PfxRigidBody &body,
const PfxVector3 &extForce,
const PfxVector3 &extTorque,
PfxFloat timeStep
)
{
if(((1<<state.getMotionType())&SCE_PFX_MOTION_MASK_APPLYFORCE) || state.isAsleep()) return;
PfxVector3 angularVelocity = state.getAngularVelocity();
PfxMatrix3 m(state.getOrientation());
PfxMatrix3 worldInertia = m * body.getInertia() * transpose(m);
PfxMatrix3 worldInertiaInv = m * body.getInertiaInv() * transpose(m);
PfxVector3 dv = extForce * body.getMassInv();
PfxVector3 dw = worldInertiaInv * (cross(worldInertia * angularVelocity, angularVelocity) + extTorque);
PfxVector3 nv = state.getLinearVelocity();
PfxVector3 nw = state.getAngularVelocity();
#ifdef SCE_PFX_ODE_EULER
nv += dv * timeStep;
nw += dw * timeStep;
#else
nv += pfxRungeKutta(dv,timeStep);
nw += pfxRungeKutta(dw,timeStep);
#endif
nv *= state.getLinearDamping();
nw *= state.getAngularDamping();
if(length(nv) > state.getMaxLinearVelocity())
{
nv = normalize( nv ) * state.getMaxLinearVelocity();
}
if(length(nw) > state.getMaxAngularVelocity())
{
nw = normalize( nw ) * state.getMaxAngularVelocity();
}
state.setLinearVelocity(nv);
state.setAngularVelocity(nw);
}
} //namespace PhysicsEffects
} //namespace sce
#endif /* _SCE_PFX_INTEGRATE_H_ */

View File

@@ -0,0 +1,90 @@
/*
Physics Effects Copyright(C) 2010 Sony Computer Entertainment Inc.
All rights reserved.
Physics Effects is open software; you can redistribute it and/or
modify it under the terms of the BSD License.
Physics Effects is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
See the BSD License for more details.
A copy of the BSD License is distributed with
Physics Effects under the filename: physics_effects_license.txt
*/
#ifndef _SCE_PFX_JOINT_H
#define _SCE_PFX_JOINT_H
#include "../rigidbody/pfx_rigid_state.h"
#include "pfx_joint_constraint.h"
#include "pfx_constraint_pair.h"
namespace sce {
namespace PhysicsEffects {
// Joint Type
enum ePfxJointType {
kPfxJointBall = 0,
kPfxJointSwingtwist,
kPfxJointHinge,
kPfxJointSlider,
kPfxJointFix,
kPfxJointUniversal,
kPfxJointAnimation,
kPfxJointReserved0,
kPfxJointReserved1,
kPfxJointReserved2,
kPfxJointUser0,
kPfxJointUser1,
kPfxJointUser2,
kPfxJointUser3,
kPfxJointUser4,
kPfxJointCount // = 15
};
// Joint Structure
struct SCE_PFX_ALIGNED(128) PfxJoint {
PfxUInt8 m_active;
PfxUInt8 m_numConstraints;
PfxUInt8 m_type;
SCE_PFX_PADDING(1,1)
PfxUInt16 m_rigidBodyIdA;
PfxUInt16 m_rigidBodyIdB;
SCE_PFX_PADDING(2,8)
PfxJointConstraint m_constraints[6];
void *m_userData;
SCE_PFX_PADDING(3,12)
PfxVector3 m_param[4]; // Used by some joints for specific features
PfxVector3 m_anchorA;
PfxVector3 m_anchorB;
PfxMatrix3 m_frameA;
PfxMatrix3 m_frameB;
SCE_PFX_PADDING(4,32)
};
SCE_PFX_FORCE_INLINE
void pfxUpdateJointPairs(
PfxConstraintPair &pair,
PfxUInt32 jointId,
const PfxJoint &joint,
const PfxRigidState &stateA,
const PfxRigidState &stateB
)
{
SCE_PFX_ALWAYS_ASSERT(stateA.getRigidBodyId()==joint.m_rigidBodyIdA);
SCE_PFX_ALWAYS_ASSERT(stateB.getRigidBodyId()==joint.m_rigidBodyIdB);
pfxSetObjectIdA(pair,stateA.getRigidBodyId());
pfxSetObjectIdB(pair,stateB.getRigidBodyId());
pfxSetMotionMaskA(pair,stateA.getMotionMask());
pfxSetMotionMaskB(pair,stateB.getMotionMask());
pfxSetConstraintId(pair,jointId);
pfxSetNumConstraints(pair,joint.m_numConstraints);
pfxSetActive(pair,joint.m_active>0);
}
} //namespace PhysicsEffects
} //namespace sce
#endif // _PFX_JOINT_H

View File

@@ -0,0 +1,62 @@
/*
Physics Effects Copyright(C) 2010 Sony Computer Entertainment Inc.
All rights reserved.
Physics Effects is open software; you can redistribute it and/or
modify it under the terms of the BSD License.
Physics Effects is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
See the BSD License for more details.
A copy of the BSD License is distributed with
Physics Effects under the filename: physics_effects_license.txt
*/
#ifndef _SCE_PFX_JOINT_BALL_H
#define _SCE_PFX_JOINT_BALL_H
#include "pfx_joint.h"
#include "pfx_solver_body.h"
namespace sce {
namespace PhysicsEffects {
struct PfxBallJointInitParam {
PfxVector3 anchorPoint;
PfxBallJointInitParam()
{
anchorPoint = PfxVector3(0.0f);
}
};
PfxInt32 pfxInitializeBallJoint(
PfxJoint &joint,
const PfxRigidState &stateA,
const PfxRigidState &stateB,
const PfxBallJointInitParam &param);
void pfxSetupBallJoint(
PfxJoint &joint,
const PfxRigidState &stateA,
const PfxRigidState &stateB,
PfxSolverBody &solverBodyA,
PfxSolverBody &solverBodyB,
PfxFloat timeStep);
void pfxWarmStartBallJoint(
PfxJoint &joint,
PfxSolverBody &solverBodyA,
PfxSolverBody &solverBodyB);
void pfxSolveBallJoint(
PfxJoint &joint,
PfxSolverBody &solverBodyA,
PfxSolverBody &solverBodyB);
} //namespace PhysicsEffects
} //namespace sce
#endif // _SCE_PFX_JOINT_BALL_H

View File

@@ -0,0 +1,67 @@
/*
Physics Effects Copyright(C) 2010 Sony Computer Entertainment Inc.
All rights reserved.
Physics Effects is open software; you can redistribute it and/or
modify it under the terms of the BSD License.
Physics Effects is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
See the BSD License for more details.
A copy of the BSD License is distributed with
Physics Effects under the filename: physics_effects_license.txt
*/
#ifndef _SCE_PFX_JOINT_CONSTRAINT_H
#define _SCE_PFX_JOINT_CONSTRAINT_H
#include "../base/pfx_common.h"
#include "../base/pfx_vec_utils.h"
#include "pfx_constraint_row.h"
namespace sce {
namespace PhysicsEffects {
// Lock type
#define SCE_PFX_JOINT_LOCK_FREE 0
#define SCE_PFX_JOINT_LOCK_LIMIT 1
#define SCE_PFX_JOINT_LOCK_FIX 2
// Slop
#define SCE_PFX_JOINT_LINEAR_SLOP 0.01f
#define SCE_PFX_JOINT_ANGULAR_SLOP 0.01f
///////////////////////////////////////////////////////////////////////////////// Joint Constraint
struct PfxJointConstraint {
PfxInt8 m_lock;
PfxInt8 m_warmStarting;
SCE_PFX_PADDING(1,2)
PfxFloat m_movableLowerLimit;
PfxFloat m_movableUpperLimit;
PfxFloat m_bias;
PfxFloat m_weight;
PfxFloat m_damping;
PfxFloat m_maxImpulse;
SCE_PFX_PADDING(2,4)
PfxConstraintRow m_constraintRow;
void reset()
{
m_lock = SCE_PFX_JOINT_LOCK_FIX;
m_warmStarting = 0;
m_movableLowerLimit = 0.0f;
m_movableUpperLimit = 0.0f;
m_bias = 0.2f;
m_weight = 1.0f;
m_damping = 0.0f;
m_maxImpulse = SCE_PFX_FLT_MAX;
memset(&m_constraintRow,0,sizeof(PfxConstraintRow));
}
};
} //namespace PhysicsEffects
} //namespace sce
#endif // _SCE_PFX_JOINT_CONSTRAINT_H

View File

@@ -0,0 +1,49 @@
/*
Physics Effects Copyright(C) 2010 Sony Computer Entertainment Inc.
All rights reserved.
Physics Effects is open software; you can redistribute it and/or
modify it under the terms of the BSD License.
Physics Effects is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
See the BSD License for more details.
A copy of the BSD License is distributed with
Physics Effects under the filename: physics_effects_license.txt
*/
#ifndef _SCE_PFX_JOINT_FIX_H
#define _SCE_PFX_JOINT_FIX_H
#include "pfx_joint.h"
#include "pfx_solver_body.h"
namespace sce {
namespace PhysicsEffects {
struct PfxFixJointInitParam {
PfxVector3 anchorPoint;
PfxFixJointInitParam()
{
anchorPoint = PfxVector3(0.0f);
}
};
PfxInt32 pfxInitializeFixJoint(
PfxJoint &joint,
const PfxRigidState &stateA,
const PfxRigidState &stateB,
const PfxFixJointInitParam &param);
// pfxSetupFixJoint = pfxSetupSwingTwistJoint
// pfxWarmStartFixJoint = pfxWarmStartSwingTwistJoint
// pfxSolveFixJoint = pfxSolveSwingTwistJoint
} //namespace PhysicsEffects
} //namespace sce
#endif // _SCE_PFX_JOINT_FIX_H

View File

@@ -0,0 +1,56 @@
/*
Physics Effects Copyright(C) 2010 Sony Computer Entertainment Inc.
All rights reserved.
Physics Effects is open software; you can redistribute it and/or
modify it under the terms of the BSD License.
Physics Effects is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
See the BSD License for more details.
A copy of the BSD License is distributed with
Physics Effects under the filename: physics_effects_license.txt
*/
#ifndef _SCE_PFX_JOINT_HINGE_H_
#define _SCE_PFX_JOINT_HINGE_H_
#include "pfx_joint.h"
#include "pfx_solver_body.h"
namespace sce {
namespace PhysicsEffects {
struct PfxHingeJointInitParam {
PfxVector3 anchorPoint;
PfxVector3 axis;
PfxFloat lowerAngle;
PfxFloat upperAngle;
SCE_PFX_PADDING(1,8)
PfxHingeJointInitParam()
{
anchorPoint = PfxVector3(0.0f);
axis = PfxVector3(1.0f,0.0f,0.0f);
lowerAngle = 0.0f;
upperAngle = 0.0f;
}
};
PfxInt32 pfxInitializeHingeJoint(
PfxJoint &joint,
const PfxRigidState &stateA,
const PfxRigidState &stateB,
const PfxHingeJointInitParam &param);
// pfxSetupHingeJoint = pfxSetupSwingTwistJoint
// pfxWarmStartHingeJoint = pfxWarmStartSwingTwistJoint
// pfxSolveHingeJoint = pfxSolveSwingTwistJoint
} //namespace PhysicsEffects
} //namespace sce
#endif // _SCE_PFX_JOINT_HINGE_H

View File

@@ -0,0 +1,57 @@
/*
Physics Effects Copyright(C) 2010 Sony Computer Entertainment Inc.
All rights reserved.
Physics Effects is open software; you can redistribute it and/or
modify it under the terms of the BSD License.
Physics Effects is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
See the BSD License for more details.
A copy of the BSD License is distributed with
Physics Effects under the filename: physics_effects_license.txt
*/
#ifndef _SCE_PFX_JOINT_SLIDER_H
#define _SCE_PFX_JOINT_SLIDER_H
#include "pfx_joint.h"
#include "pfx_solver_body.h"
namespace sce {
namespace PhysicsEffects {
struct PfxSliderJointInitParam {
PfxVector3 anchorPoint;
PfxVector3 direction;
PfxFloat lowerDistance;
PfxFloat upperDistance;
SCE_PFX_PADDING(1,8)
PfxSliderJointInitParam()
{
anchorPoint = PfxVector3(0.0f);
direction = PfxVector3(1.0f,0.0f,0.0f);
lowerDistance = 0.0f;
upperDistance = 0.0f;
}
};
PfxInt32 pfxInitializeSliderJoint(
PfxJoint &joint,
const PfxRigidState &stateA,
const PfxRigidState &stateB,
const PfxSliderJointInitParam &param);
// pfxSetupSliderJoint = pfxSetupSwingTwistJoint
// pfxWarmStartSliderJoint = pfxWarmStartSwingTwistJoint
// pfxSolveSliderJoint = pfxSolveSwingTwistJoint
} //namespace PhysicsEffects
} //namespace sce
#endif // _SCE_PFX_JOINT_SLIDER_H

View File

@@ -0,0 +1,70 @@
/*
Physics Effects Copyright(C) 2010 Sony Computer Entertainment Inc.
All rights reserved.
Physics Effects is open software; you can redistribute it and/or
modify it under the terms of the BSD License.
Physics Effects is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
See the BSD License for more details.
A copy of the BSD License is distributed with
Physics Effects under the filename: physics_effects_license.txt
*/
#ifndef _SCE_PFX_JOINT_SWING_TWIST_H
#define _SCE_PFX_JOINT_SWING_TWIST_H
#include "pfx_joint.h"
#include "pfx_solver_body.h"
namespace sce {
namespace PhysicsEffects {
struct PfxSwingTwistJointInitParam {
PfxVector3 anchorPoint;
PfxVector3 twistAxis;
PfxFloat twistLowerAngle;
PfxFloat twistUpperAngle;
PfxFloat swingLowerAngle;
PfxFloat swingUpperAngle;
PfxSwingTwistJointInitParam()
{
anchorPoint = PfxVector3(0.0f);
twistAxis = PfxVector3(1.0f,0.0f,0.0f);
twistLowerAngle = -0.26f;
twistUpperAngle = 0.26f;
swingLowerAngle = 0.0f;
swingUpperAngle = 0.7f;
}
};
PfxInt32 pfxInitializeSwingTwistJoint(
PfxJoint &joint,
const PfxRigidState &stateA,
const PfxRigidState &stateB,
const PfxSwingTwistJointInitParam &param);
void pfxSetupSwingTwistJoint(
PfxJoint &joint,
const PfxRigidState &stateA,
const PfxRigidState &stateB,
PfxSolverBody &solverBodyA,
PfxSolverBody &solverBodyB,
PfxFloat timeStep);
void pfxWarmStartSwingTwistJoint(
PfxJoint &joint,
PfxSolverBody &solverBodyA,
PfxSolverBody &solverBodyB);
void pfxSolveSwingTwistJoint(
PfxJoint &joint,
PfxSolverBody &solverBodyA,
PfxSolverBody &solverBodyB);
} //namespace PhysicsEffects
} //namespace sce
#endif // _SCE_PFX_JOINT_SWING_TWIST_H

View File

@@ -0,0 +1,65 @@
/*
Physics Effects Copyright(C) 2010 Sony Computer Entertainment Inc.
All rights reserved.
Physics Effects is open software; you can redistribute it and/or
modify it under the terms of the BSD License.
Physics Effects is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
See the BSD License for more details.
A copy of the BSD License is distributed with
Physics Effects under the filename: physics_effects_license.txt
*/
#ifndef _SCE_PFX_JOINT_UNIVERSAL_H
#define _SCE_PFX_JOINT_UNIVERSAL_H
#include "pfx_joint.h"
#include "pfx_solver_body.h"
namespace sce {
namespace PhysicsEffects {
struct PfxUniversalJointInitParam {
PfxVector3 anchorPoint;
PfxVector3 axis;
PfxFloat swing1LowerAngle;
PfxFloat swing1UpperAngle;
PfxFloat swing2LowerAngle;
PfxFloat swing2UpperAngle;
PfxUniversalJointInitParam()
{
anchorPoint = PfxVector3(0.0f);
axis = PfxVector3(1.0f,0.0f,0.0f);
swing1LowerAngle = -0.7f;
swing1UpperAngle = 0.7f;
swing2LowerAngle = -0.7f;
swing2UpperAngle = 0.7f;
}
};
PfxInt32 pfxInitializeUniversalJoint(
PfxJoint &joint,
const PfxRigidState &stateA,
const PfxRigidState &stateB,
const PfxUniversalJointInitParam &param);
void pfxSetupUniversalJoint(
PfxJoint &joint,
const PfxRigidState &stateA,
const PfxRigidState &stateB,
PfxSolverBody &solverBodyA,
PfxSolverBody &solverBodyB,
PfxFloat timeStep);
// pfxWarmStartUniversalJoint = pfxWarmStartSwingTwistJoint
// pfxSolveUniversalJoint = pfxSolveSwingTwistJoint
} //namespace PhysicsEffects
} //namespace sce
#endif // _SCE_PFX_JOINT_UNIVERSAL_H

View File

@@ -0,0 +1,37 @@
/*
Physics Effects Copyright(C) 2010 Sony Computer Entertainment Inc.
All rights reserved.
Physics Effects is open software; you can redistribute it and/or
modify it under the terms of the BSD License.
Physics Effects is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
See the BSD License for more details.
A copy of the BSD License is distributed with
Physics Effects under the filename: physics_effects_license.txt
*/
#ifndef _SCE_PFX_SOLVER_BODY_H
#define _SCE_PFX_SOLVER_BODY_H
#include "../base/pfx_common.h"
namespace sce {
namespace PhysicsEffects {
struct SCE_PFX_ALIGNED(128) PfxSolverBody {
PfxVector3 m_deltaLinearVelocity;
PfxVector3 m_deltaAngularVelocity;
PfxQuat m_orientation;
PfxMatrix3 m_inertiaInv;
PfxFloat m_massInv;
PfxUInt32 m_motionType;
SCE_PFX_PADDING(1,24)
};
} //namespace PhysicsEffects
} //namespace sce
#endif // _SCE_PFX_SOLVER_BODY_H