Go to the documentation of this file.
135 b2Rot qA(aA), qB(aB);
140 b2Vec2 d = (cB - cA) + rB - rA;
247 float LA = impulse *
m_a1;
248 float LB = impulse *
m_a2;
268 float LA = impulse *
m_a1;
269 float LB = impulse *
m_a2;
289 float LA = impulse *
m_a1;
290 float LB = impulse *
m_a2;
309 float LA = df.
x *
m_s1 + df.
y;
310 float LB = df.
x *
m_s2 + df.
y;
339 b2Rot qA(aA), qB(aB);
362 float linearError =
b2Abs(C1.
x);
363 float angularError =
b2Abs(C1.
y);
369 float translation =
b2Dot(axis,
d);
373 linearError =
b2Max(linearError,
b2Abs(translation));
392 float k11 = mA + mB + iA * s1 * s1 + iB * s2 * s2;
393 float k12 = iA * s1 + iB * s2;
394 float k13 = iA * s1 * a1 + iB * s2 * a2;
401 float k23 = iA * a1 + iB * a2;
402 float k33 = mA + mB + iA * a1 * a1 + iB * a2 * a2;
405 K.
ex.
Set(k11, k12, k13);
406 K.
ey.
Set(k12, k22, k23);
407 K.
ez.
Set(k13, k23, k33);
418 float k11 = mA + mB + iA * s1 * s1 + iB * s2 * s2;
419 float k12 = iA * s1 + iB * s2;
431 impulse.
x = impulse1.
x;
432 impulse.
y = impulse1.
y;
436 b2Vec2 P = impulse.
x * perp + impulse.
z * axis;
437 float LA = impulse.
x * s1 + impulse.
y + impulse.
z * a1;
438 float LB = impulse.
x * s2 + impulse.
y + impulse.
z * a2;
480 float translation =
b2Dot(
d, axis);
593 b2Dump(
" b2PrismaticJointDef jd;\n");
594 b2Dump(
" jd.bodyA = bodies[%d];\n", indexA);
595 b2Dump(
" jd.bodyB = bodies[%d];\n", indexB);
607 b2Dump(
" joints[%d] = m_world->CreateJoint(&jd);\n",
m_index);
633 draw->
DrawSegment(lower - 0.5
f * perp, lower + 0.5
f * perp, c2);
634 draw->
DrawSegment(upper - 0.5
f * perp, upper + 0.5
f * perp, c3);
float b2Cross(const b2Vec2 &a, const b2Vec2 &b)
Perform the cross product on two vectors. In 2D this produces a scalar.
bool IsMotorEnabled() const
Is the joint motor enabled?
void EnableMotor(bool flag)
Enable/disable the joint motor.
void Draw(b2Draw *draw) const override
Debug draw this joint.
void EnableLimit(bool flag)
Enable/disable the joint limit.
b2Vec2 localAnchorA
The local anchor point relative to bodyA's origin.
void Dump() override
Dump to b2Log.
float GetLowerLimit() const
Get the lower joint limit, usually in meters.
float lowerTranslation
The lower translation limit, usually in meters.
b2Vec2 localCenter
local center of mass position
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.
A 2D column vector with 3 elements.
A 2-by-2 matrix. Stored in column-major order.
b2Vec2 localAnchorB
The local anchor point relative to bodyB's origin.
A rigid body. These are created via b2World::CreateBody.
void SetZero()
Set this vector to all zeros.
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
void b2Dump(const char *string,...)
bool SolvePositionConstraints(const b2SolverData &data) override
void Set(float x_, float y_)
Set this vector to some specified coordinates.
float referenceAngle
The constrained angle between the bodies: bodyB_angle - bodyA_angle.
void InitVelocityConstraints(const b2SolverData &data) override
b2Vec2 GetAnchorB() const override
Get the anchor point on bodyB in world coordinates.
virtual void DrawPoint(const b2Vec2 &p, float size, const b2Color &color)=0
Draw a point.
T b2Clamp(T a, T low, T high)
b2Vec2 Solve(const b2Vec2 &b) const
b2Vec2 GetWorldVector(const b2Vec2 &localVector) const
void Set(float x_, float y_, float z_)
Set this vector to some specified coordinates.
float GetReactionTorque(float inv_dt) const override
Get the reaction torque on bodyB in N*m.
void SetLimits(float lower, float upper)
Set the joint limits, usually in meters.
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].
bool enableLimit
Enable/disable the joint limit.
b2Vec2 GetLocalPoint(const b2Vec2 &worldPoint) const
b2Vec3 Solve33(const b2Vec3 &b) const
b2Vec2 GetLocalVector(const b2Vec2 &worldVector) const
b2Vec2 GetAnchorA() const override
Get the anchor point on bodyA in world coordinates.
void SolveVelocityConstraints(const b2SolverData &data) override
b2PrismaticJoint(const b2PrismaticJointDef *def)
float GetJointSpeed() const
Get the current joint translation speed, usually in meters per second.
float upperTranslation
The upper translation limit, usually in meters.
A 3-by-3 matrix. Stored in column-major order.
float motorSpeed
The desired motor speed in radians per second.
bool IsLimitEnabled() const
Is the joint limit enabled?
void SetMaxMotorForce(float force)
Set the maximum motor force, usually in N.
float GetMotorForce(float inv_dt) const
Get the current motor force given the inverse time step, usually in N.
void SetMotorSpeed(float speed)
Set the motor speed, usually in meters per second.
bool enableMotor
Enable/disable the joint motor.
b2Vec2 c
center world positions
float GetUpperLimit() const
Get the upper joint limit, usually in meters.
b2Vec2 GetWorldPoint(const b2Vec2 &localPoint) const
b2Vec2 GetReactionForce(float inv_dt) const override
Get the reaction force on bodyB at the joint anchor in Newtons.
const b2Transform & GetTransform() const
float maxMotorForce
The maximum motor torque, usually in N-m.
b2Vec2 localAxisA
The local translation unit axis in bodyA.
b2Body * bodyA
The first attached body.
void Initialize(b2Body *bodyA, b2Body *bodyB, const b2Vec2 &anchor, const b2Vec2 &axis)
float GetJointTranslation() const
Get the current joint translation, usually in meters.
b2Body * bodyB
The second attached body.
mvsim
Author(s):
autogenerated on Wed May 28 2025 02:13:07