56 m_stretchConstraints =
nullptr;
57 m_bendConstraints =
nullptr;
58 m_bindPositions =
nullptr;
62 m_invMasses =
nullptr;
68 b2Free(m_stretchConstraints);
86 m_invMasses = (
float*)
b2Alloc(m_count *
sizeof(
float));
88 for (
int32 i = 0; i < m_count; ++i)
90 m_bindPositions[i] = def.
vertices[i];
91 m_ps[i] = def.
vertices[i] + m_position;
92 m_p0s[i] = def.
vertices[i] + m_position;
98 m_invMasses[i] = 1.0f / m;
102 m_invMasses[i] = 0.0f;
106 m_stretchCount = m_count - 1;
107 m_bendCount = m_count - 2;
112 for (
int32 i = 0; i < m_stretchCount; ++i)
129 for (
int32 i = 0; i < m_bendCount; ++i)
154 if (L1sqr * L2sqr == 0.0
f)
193 const float bendOmega = 2.0f *
b2_pi * m_tuning.bendHertz;
195 for (
int32 i = 0; i < m_bendCount; ++i)
199 float L1sqr = c.
L1 * c.
L1;
200 float L2sqr = c.
L2 * c.
L2;
202 if (L1sqr * L2sqr == 0.0
f)
210 float J2 = 1.0f / c.
L1 + 1.0f / c.
L2;
219 float mass = 1.0f / sum;
221 c.
spring = mass * bendOmega * bendOmega;
222 c.
damper = 2.0f * mass * m_tuning.bendDamping * bendOmega;
225 const float stretchOmega = 2.0f *
b2_pi * m_tuning.stretchHertz;
227 for (
int32 i = 0; i < m_stretchCount; ++i)
237 float mass = 1.0f / sum;
239 c.
spring = mass * stretchOmega * stretchOmega;
240 c.
damper = 2.0f * mass * m_tuning.stretchDamping * stretchOmega;
251 const float inv_dt = 1.0f / dt;
252 float d = expf(- dt * m_tuning.damping);
255 for (
int32 i = 0; i < m_count; ++i)
257 if (m_invMasses[i] > 0.0
f)
260 m_vs[i] += dt * m_gravity;
264 m_vs[i] = inv_dt * (m_bindPositions[i] + position - m_p0s[i]);
274 for (
int32 i = 0; i < m_bendCount; ++i)
276 m_bendConstraints[i].lambda = 0.0f;
279 for (
int32 i = 0; i < m_stretchCount; ++i)
281 m_stretchConstraints[i].lambda = 0.0f;
285 for (
int32 i = 0; i < m_count; ++i)
287 m_ps[i] += dt * m_vs[i];
291 for (
int32 i = 0; i < iterations; ++i)
295 SolveBend_PBD_Angle();
299 SolveBend_XPBD_Angle(dt);
303 SolveBend_PBD_Distance();
307 SolveBend_PBD_Height();
311 SolveBend_PBD_Triangle();
320 SolveStretch_XPBD(dt);
325 for (
int32 i = 0; i < m_count; ++i)
327 m_vs[i] = inv_dt * (m_ps[i] - m_p0s[i]);
334 m_position = position;
336 for (
int32 i = 0; i < m_count; ++i)
338 m_ps[i] = m_bindPositions[i] + m_position;
339 m_p0s[i] = m_bindPositions[i] + m_position;
343 for (
int32 i = 0; i < m_bendCount; ++i)
345 m_bendConstraints[i].lambda = 0.0f;
348 for (
int32 i = 0; i < m_stretchCount; ++i)
350 m_stretchConstraints[i].lambda = 0.0f;
356 const float stiffness = m_tuning.stretchStiffness;
358 for (
int32 i = 0; i < m_stretchCount; ++i)
377 p1 -= stiffness * s1 * (c.
L -
L) * d;
378 p2 += stiffness * s2 * (c.
L -
L) * d;
389 for (
int32 i = 0; i < m_stretchCount; ++i)
411 const float alpha = 1.0f / (c.
spring * dt * dt);
412 const float beta = dt * dt * c.
damper;
413 const float sigma = alpha * beta / dt;
419 float B = C + alpha * c.
lambda + sigma * Cdot;
420 float sum2 = (1.0f + sigma) * sum + alpha;
422 float impulse = -B / sum2;
435 const float stiffness = m_tuning.bendStiffness;
437 for (
int32 i = 0; i < m_bendCount; ++i)
448 float b =
b2Dot(d1, d2);
454 if (m_tuning.isometric)
465 if (L1sqr * L2sqr == 0.0
f)
478 if (m_tuning.fixedEffectiveMass)
492 float impulse = -stiffness * angle / sum;
508 for (
int32 i = 0; i < m_bendCount; ++i)
525 if (m_tuning.isometric)
536 if (L1sqr * L2sqr == 0.0
f)
542 float b =
b2Dot(d1, d2);
554 if (m_tuning.fixedEffectiveMass)
568 const float alpha = 1.0f / (c.
spring * dt * dt);
569 const float beta = dt * dt * c.
damper;
570 const float sigma = alpha * beta / dt;
576 float B = C + alpha * c.
lambda + sigma * Cdot;
577 float sum2 = (1.0f + sigma) * sum + alpha;
579 float impulse = -B / sum2;
595 const float omega = 2.0f *
b2_pi * m_tuning.bendHertz;
597 for (
int32 i = 0; i < m_bendCount; ++i)
614 if (m_tuning.isometric)
625 if (L1sqr * L2sqr == 0.0
f)
631 float b =
b2Dot(d1, d2);
643 if (m_tuning.fixedEffectiveMass)
657 float mass = 1.0f / sum;
659 const float spring = mass * omega * omega;
660 const float damper = 2.0f * mass * m_tuning.bendDamping * omega;
665 float impulse = -dt * (spring * C + damper * Cdot);
675 const float stiffness = m_tuning.bendStiffness;
677 for (
int32 i = 0; i < m_bendCount; ++i)
699 p1 -= stiffness * s1 * (c.
L1 + c.
L2 -
L) * d;
700 p2 += stiffness * s2 * (c.
L1 + c.
L2 -
L) * d;
711 const float stiffness = m_tuning.bendStiffness;
713 for (
int32 i = 0; i < m_bendCount; ++i)
730 b2Vec2 dHat = (1.0f / dLen) * d;
744 float mass = 1.0f / sum;
745 float impulse = -stiffness * mass * C;
760 const float stiffness = m_tuning.bendStiffness;
762 for (
int32 i = 0; i < m_bendCount; ++i)
774 float W = wb0 + wb1 + 2.0f * wv;
775 float invW = stiffness / W;
777 b2Vec2 d = v - (1.0f / 3.0f) * (b0 + v + b1);
779 b2Vec2 db0 = 2.0f * wb0 * invW * d;
780 b2Vec2 dv = -4.0f * wv * invW * d;
781 b2Vec2 db1 = 2.0f * wb1 * invW * d;
799 for (
int32 i = 0; i < m_count - 1; ++i)
803 const b2Color& pc = m_invMasses[i] > 0.0f ? pd : pg;
807 const b2Color& pc = m_invMasses[m_count - 1] > 0.0f ? pd : pg;
virtual void DrawSegment(const b2Vec2 &p1, const b2Vec2 &p2, const b2Color &color)=0
Draw a line segment.
void * b2Alloc(int32 size)
Implement this function to use your own memory allocator.
float b2Dot(const b2Vec2 &a, const b2Vec2 &b)
Perform the dot product on two vectors.
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
void Reset(const b2Vec2 &position)
void ApplyBendForces(float dt)
float Length() const
Get the length of this vector (the norm).
virtual void DrawPoint(const b2Vec2 &p, float size, const b2Color &color)=0
Draw a point.
void SolveBend_PBD_Distance()
void SetZero()
Set this vector to all zeros.
void SolveBend_XPBD_Angle(float dt)
Color for debug drawing. Each value has the range [0,1].
void SolveBend_PBD_Angle()
void SolveBend_PBD_Triangle()
void SetTuning(const b2RopeTuning &tuning)
void SolveBend_PBD_Height()
float LengthSquared() const
void Draw(b2Draw *draw) const
float b2Cross(const b2Vec2 &a, const b2Vec2 &b)
Perform the cross product on two vectors. In 2D this produces a scalar.
void Step(float timeStep, int32 iterations, const b2Vec2 &position)
B2_API void b2Distance(b2DistanceOutput *output, b2SimplexCache *cache, const b2DistanceInput *input)
b2Vec2 Skew() const
Get the skew vector such that dot(skew_vec, other) == cross(vec, other)
void SolveStretch_XPBD(float dt)
void b2Free(void *mem)
If you implement b2Alloc, you should also implement this function.
float Normalize()
Convert this vector into a unit vector. Returns the length.
void Create(const b2RopeDef &def)