Go to the documentation of this file.
154 if (L1sqr * L2sqr == 0.0
f)
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;
237 float mass = 1.0f / sum;
239 c.
spring = mass * stretchOmega * stretchOmega;
251 const float inv_dt = 1.0f / dt;
291 for (
int32 i = 0; i < iterations; ++i)
366 float L =
d.Normalize();
377 p1 -= stiffness * s1 * (c.
L - L) *
d;
378 p2 += stiffness * s2 * (c.
L - L) *
d;
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;
448 float b =
b2Dot(d1, d2);
465 if (L1sqr * L2sqr == 0.0
f)
492 float impulse = -stiffness *
angle / sum;
536 if (L1sqr * L2sqr == 0.0
f)
542 float b =
b2Dot(d1, d2);
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;
625 if (L1sqr * L2sqr == 0.0
f)
631 float b =
b2Dot(d1, d2);
657 float mass = 1.0f / sum;
659 const float spring = mass * omega * omega;
665 float impulse = -dt * (spring * C + damper * Cdot);
688 float L =
d.Normalize();
699 p1 -= stiffness * s1 * (c.
L1 + c.
L2 - L) *
d;
700 p2 += stiffness * s2 * (c.
L1 + c.
L2 - L) *
d;
723 float dLen =
d.Length();
730 b2Vec2 dHat = (1.0f / dLen) *
d;
744 float mass = 1.0f / sum;
745 float impulse = -stiffness * mass * C;
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;
@ b2_pbdTriangleBendingModel
float b2Cross(const b2Vec2 &a, const b2Vec2 &b)
Perform the cross product on two vectors. In 2D this produces a scalar.
void SolveBend_PBD_Distance()
void * b2Alloc(int32 size)
Implement this function to use your own memory allocator.
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
void SolveBend_XPBD_Angle(float dt)
float Normalize()
Convert this vector into a unit vector. Returns the length.
virtual void DrawSegment(const b2Vec2 &p1, const b2Vec2 &p2, const b2Color &color)=0
Draw a line segment.
void SolveBend_PBD_Triangle()
@ b2_pbdAngleBendingModel
b2Vec2 Skew() const
Get the skew vector such that dot(skew_vec, other) == cross(vec, other)
B2_API void b2Distance(b2DistanceOutput *output, b2SimplexCache *cache, const b2DistanceInput *input)
void SolveBend_PBD_Height()
void SetZero()
Set this vector to all zeros.
void Draw(b2Draw *draw) const
virtual void DrawPoint(const b2Vec2 &p, float size, const b2Color &color)=0
Draw a point.
b2BendingModel bendingModel
void Step(float timeStep, int32 iterations, const b2Vec2 &position)
b2StretchingModel stretchingModel
void SolveStretch_XPBD(float dt)
float b2Dot(const b2Vec2 &a, const b2Vec2 &b)
Perform the dot product on two vectors.
Color for debug drawing. Each value has the range [0,1].
void SetTuning(const b2RopeTuning &tuning)
float LengthSquared() const
void SolveBend_PBD_Angle()
b2RopeStretch * m_stretchConstraints
void Create(const b2RopeDef &def)
@ b2_pbdHeightBendingModel
@ b2_pbdDistanceBendingModel
@ b2_xpbdAngleBendingModel
void b2Free(void *mem)
If you implement b2Alloc, you should also implement this function.
@ b2_springAngleBendingModel
b2RopeBend * m_bendConstraints
void Reset(const b2Vec2 &position)
void ApplyBendForces(float dt)
mvsim
Author(s):
autogenerated on Wed May 28 2025 02:13:07