150 int32 contactCapacity,
230 solverData.
step = step;
236 contactSolverDef.
step = step;
283 b2Vec2 translation = h * v;
309 bool positionSolved =
false;
314 bool jointsOkay =
true;
318 jointsOkay = jointsOkay && jointOkay;
321 if (contactsOkay && jointsOkay)
324 positionSolved =
true;
403 contactSolverDef.
step = subStep;
481 b2Vec2 translation = h * v;
#define b2_linearSleepTolerance
A body cannot sleep if its linear velocity is above this tolerance.
float32 b2Dot(const b2Vec2 &a, const b2Vec2 &b)
Perform the dot product on two vectors.
virtual void SolveVelocityConstraints(const b2SolverData &data)=0
This is an internal structure.
void Set(const b2Shape *shape, int32 index)
b2ContactListener * m_listener
void Report(const b2ContactVelocityConstraint *constraints)
float32 GetMilliseconds() const
Get the time since construction or the last reset.
This is an internal structure.
#define b2_timeToSleep
The time that a body must be still before it will go to sleep.
void SolveTOI(const b2TimeStep &subStep, int32 toiIndexA, int32 toiIndexB)
b2Vec2 c
center world positions
b2Velocity * m_velocities
#define b2_maxTranslation
A rigid body. These are created via b2World::CreateBody.
Profiling data. Times are in milliseconds.
virtual void InitVelocityConstraints(const b2SolverData &data)=0
void * Allocate(int32 size)
virtual bool SolvePositionConstraints(const b2SolverData &data)=0
b2StackAllocator * m_allocator
#define b2_maxRotationSquared
void Reset()
Reset the timer.
void SynchronizeTransform()
void b2Distance(b2DistanceOutput *output, b2SimplexCache *cache, const b2DistanceInput *input)
b2Island(int32 bodyCapacity, int32 contactCapacity, int32 jointCapacity, b2StackAllocator *allocator, b2ContactListener *listener)
b2BodyType GetType() const
Get the type of this body.
TFSIMD_FORCE_INLINE const tfScalar & w() const
void Solve(b2Profile *profile, const b2TimeStep &step, const b2Vec2 &gravity, bool allowSleep)
#define b2_maxTranslationSquared
float32 m_angularVelocity
#define b2_angularSleepTolerance
A body cannot sleep if its angular velocity is above this tolerance.
This is an internal structure.
const b2Transform & GetTransform() const
float32 Length() const
Get the length of this vector (the norm).