diff --git a/example/Car.js b/example/Car.js index 6b28b293..dd754673 100644 --- a/example/Car.js +++ b/example/Car.js @@ -149,35 +149,33 @@ wheelBack.createFixture(new Circle(0.4), wheelFD); var wheelFront = world.createDynamicBody(new Vec2(1.0, 0.4)); wheelFront.createFixture(new Circle(0.4), wheelFD); +const massWheelBack = wheelBack.getMass(); +const massWheelFront = wheelFront.getMass(); + +const omega = 2.0 * Math.PI * HZ; + var springBack = world.createJoint(new WheelJoint({ motorSpeed : 0.0, maxMotorTorque : 20.0, enableMotor : true, - frequencyHz : HZ, - dampingRatio : ZETA + stiffness : massWheelBack * omega * omega, + damping : 2.0 * massWheelBack * ZETA * omega, + lowerTranslation : -0.25, + upperTranslation : 0.25, + enableLimit : true }, car, wheelBack, wheelBack.getPosition(), new Vec2(0.0, 1.0))); var springFront = world.createJoint(new WheelJoint({ motorSpeed : 0.0, maxMotorTorque : 10.0, enableMotor : false, - frequencyHz : HZ, - dampingRatio : ZETA + stiffness : massWheelFront * omega * omega, + damping : 2.0 * massWheelFront * ZETA * omega, + lowerTranslation : -0.25, + upperTranslation : 0.25, + enableLimit : true }, car, wheelFront, wheelFront.getPosition(), new Vec2(0.0, 1.0))); -testbed.keydown = function() { - if (testbed.activeKeys.down) { - HZ = Math.max(0.0, HZ - 1.0); - springBack.setSpringFrequencyHz(HZ); - springFront.setSpringFrequencyHz(HZ); - - } else if (testbed.activeKeys.up) { - HZ += 1.0; - springBack.setSpringFrequencyHz(HZ); - springFront.setSpringFrequencyHz(HZ); - } -}; - testbed.step = function() { if (testbed.activeKeys.right && testbed.activeKeys.left) { springBack.setMotorSpeed(0); diff --git a/example/Prismatic.js b/example/Prismatic.js index 1a3da22f..6958d39b 100644 --- a/example/Prismatic.js +++ b/example/Prismatic.js @@ -21,7 +21,7 @@ * SOFTWARE. */ -// The motor in this test gets smoother with higher velocity iterations. +// Test the prismatic joint with limits and motor options. const { World, Vec2, PrismaticJoint, Edge, Box, Circle } = planck; @@ -30,6 +30,8 @@ var world = new World(new Vec2(0, -10)); const testbed = planck.testbed(); testbed.start(world); +var ENABLE_LIMIT = true; +var ENABLE_MOTOR = false; var MOTOR_SPEED = 10; var ground = world.createBody(); @@ -41,22 +43,17 @@ var body = world.createBody({ angle : 0.5 * Math.PI, allowSleep : false }); -body.createFixture(new Box(2.0, 0.5), 5.0); +body.createFixture(new Box(1.0, 1.5), 5.0); // Bouncy limit -var axis = new Vec2(2.0, 1.0); -axis.normalize(); var joint = new PrismaticJoint({ motorSpeed : MOTOR_SPEED, maxMotorForce : 10000.0, - enableMotor : true, - lowerTranslation : 0.0, - upperTranslation : 20.0, - enableLimit : true -}, ground, body, new Vec2(0.0, 0.0), axis); - -// Non-bouncy limit -// (ground, body, new Vec2(-10.0, 10.0), new Vec2(1.0, 0.0)); + enableMotor : ENABLE_MOTOR, + lowerTranslation : -10.0, + upperTranslation : 10.0, + enableLimit : ENABLE_LIMIT +}, ground, body, new Vec2(0.0, 0.0), new Vec2(1.0, 0.0)); world.createJoint(joint); diff --git a/example/WheelJoint.js b/example/WheelJoint.js new file mode 100644 index 00000000..9231ce9b --- /dev/null +++ b/example/WheelJoint.js @@ -0,0 +1,89 @@ +/* + * MIT License + * Copyright (c) 2019 Erin Catto + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +// Test the wheel joint with motor, spring, and limit options. + +var { World, Vec2, Edge, Box, Circle, Polygon, RevoluteJoint, WheelJoint } = planck; + +var testbed = planck.testbed(); + +var world = new World({ + gravity : new Vec2(0, -10) +}); + +testbed.start(world); + +var ground = world.createBody(); +ground.createFixture(new Edge(new Vec2(-40.0, 0.0), new Vec2(40.0, 0.0)), 0.0); + + +var enableLimit = true; +var enableMotor = false; +var motorSpeed = 0.0; + +var body = world.createBody({ + type : 'dynamic', + position : new Vec2(0.0, 10.0), + allowSleep : false +}); +body.createFixture(new Circle(2.0), 5.0); + +var mass = body.getMass(); +var hertz = 1.0; +var dampingRatio = 0.7; +var omega = 2.0 * Math.PI * hertz; + +var joint = new WheelJoint({ + motorSpeed : motorSpeed, + maxMotorTorque : 10000.0, + enableMotor : enableMotor, + stiffness : mass * omega * omega, + damping : 2.0 * mass * dampingRatio * omega, + lowerTranslation : -3.0, + upperTranslation : 3.0, + enableLimit : enableLimit +}, ground, body, new Vec2(0.0, 10.0), new Vec2(0.0, 1.0)); + +world.createJoint(joint); + +testbed.step = function() { + var torque = joint.getMotorTorque(testbed.hz); + testbed.status({ + "Motor Torque" : torque, + "Motor Speed" : joint.getMotorSpeed(), + }); + + if (testbed.activeKeys.right && testbed.activeKeys.left) { + joint.setMotorSpeed(0); + joint.enableMotor(true); + } else if (testbed.activeKeys.right) { + joint.setMotorSpeed(-10); + joint.enableMotor(true); + } else if (testbed.activeKeys.left) { + joint.setMotorSpeed(10); + joint.enableMotor(true); + } else { + joint.setMotorSpeed(0); + joint.enableMotor(false); + } +}; diff --git a/example/list.json b/example/list.json index 83b5a93d..e4c1564e 100644 --- a/example/list.json +++ b/example/list.json @@ -57,5 +57,6 @@ "VaryingFriction", "VaryingRestitution", "VerticalStack", - "Web" + "Web", + "WheelJoint" ] diff --git a/src/collision/shape/CircleShape.ts b/src/collision/shape/CircleShape.ts index 42e4218a..2e8fb24b 100644 --- a/src/collision/shape/CircleShape.ts +++ b/src/collision/shape/CircleShape.ts @@ -36,6 +36,9 @@ const _ASSERT = typeof ASSERT === 'undefined' ? false : ASSERT; const _CONSTRUCTOR_FACTORY = typeof CONSTRUCTOR_FACTORY === 'undefined' ? false : CONSTRUCTOR_FACTORY; +/** + * A solid circle shape + */ export class CircleShape extends Shape { static TYPE = 'circle' as const; m_type: 'circle'; @@ -138,6 +141,8 @@ export class CircleShape extends Shape { /** * Cast a ray against a child shape. + * @note because the circle is solid, rays that start inside do not hit + * because the normal is not defined. * * @param output The ray-cast results. * @param input The ray-cast input parameters. diff --git a/src/collision/shape/PolygonShape.ts b/src/collision/shape/PolygonShape.ts index 24d9641f..d6851d5f 100644 --- a/src/collision/shape/PolygonShape.ts +++ b/src/collision/shape/PolygonShape.ts @@ -38,8 +38,8 @@ const _CONSTRUCTOR_FACTORY = typeof CONSTRUCTOR_FACTORY === 'undefined' ? false /** - * A convex polygon. It is assumed that the interior of the polygon is to the - * left of each edge. Polygons have a maximum number of vertices equal to + * A solid convex polygon. It is assumed that the interior of the polygon is to + * the left of each edge. Polygons have a maximum number of vertices equal to * Settings.maxPolygonVertices. In most cases you should not need many vertices * for a convex polygon. extends Shape */ @@ -316,6 +316,8 @@ export class PolygonShape extends Shape { /** * Cast a ray against a child shape. + * @note because the polygon is solid, rays that start inside do not hit + * because the normal is not defined. * * @param output The ray-cast results. * @param input The ray-cast input parameters. diff --git a/src/dynamics/joint/PrismaticJoint.ts b/src/dynamics/joint/PrismaticJoint.ts index 0ea323e2..1f835ddd 100644 --- a/src/dynamics/joint/PrismaticJoint.ts +++ b/src/dynamics/joint/PrismaticJoint.ts @@ -130,16 +130,16 @@ export class PrismaticJoint extends Joint { /** @internal */ m_localXAxisA: Vec2; /** @internal */ m_localYAxisA: Vec2; /** @internal */ m_referenceAngle: number; - /** @internal */ m_impulse: Vec3; - /** @internal */ m_motorMass: number; + /** @internal */ m_impulse: Vec2; /** @internal */ m_motorImpulse: number; + /** @internal */ m_lowerImpulse: number; + /** @internal */ m_upperImpulse: number; /** @internal */ m_lowerTranslation: number; /** @internal */ m_upperTranslation: number; /** @internal */ m_maxMotorForce: number; /** @internal */ m_motorSpeed: number; /** @internal */ m_enableLimit: boolean; /** @internal */ m_enableMotor: boolean; - /** @internal */ m_limitState: number; // TODO enum /** @internal */ m_axis: Vec2; /** @internal */ m_perp: Vec2; // Solver temp @@ -153,7 +153,9 @@ export class PrismaticJoint extends Joint { /** @internal */ m_s2: number; /** @internal */ m_a1: number; /** @internal */ m_a2: number; - /** @internal */ m_K: Mat33; + /** @internal */ m_K: Mat22; + /** @internal */ m_translation: number; + /** @internal */ m_axialMass: number; constructor(def: PrismaticJointDef); constructor(def: PrismaticJointOpt, bodyA: Body, bodyB: Body, anchor: Vec2, axis: Vec2); @@ -177,22 +179,26 @@ export class PrismaticJoint extends Joint { this.m_localYAxisA = Vec2.crossNumVec2(1.0, this.m_localXAxisA); this.m_referenceAngle = Math.isFinite(def.referenceAngle) ? def.referenceAngle : bodyB.getAngle() - bodyA.getAngle(); - this.m_impulse = new Vec3(); - this.m_motorMass = 0.0; + this.m_impulse = new Vec2(); + this.m_axialMass = 0.0; this.m_motorImpulse = 0.0; + this.m_lowerImpulse = 0.0; + this.m_upperImpulse = 0.0; this.m_lowerTranslation = def.lowerTranslation; this.m_upperTranslation = def.upperTranslation; + + _ASSERT && Math.assert(this.m_lowerTranslation <= this.m_upperTranslation); + this.m_maxMotorForce = def.maxMotorForce; this.m_motorSpeed = def.motorSpeed; this.m_enableLimit = def.enableLimit; this.m_enableMotor = def.enableMotor; - this.m_limitState = inactiveLimit; this.m_axis = Vec2.zero(); this.m_perp = Vec2.zero(); - this.m_K = new Mat33(); + this.m_K = new Mat22(); // Linear constraint (point-to-line) // d = p2 - p1 = x2 + r2 - x1 - r1 @@ -218,54 +224,30 @@ export class PrismaticJoint extends Joint { // Motor/Limit linear constraint // C = dot(ax1, d) - // Cdot = = -dot(ax1, v1) - dot(cross(d + r1, ax1), w1) + dot(ax1, v2) + + // Cdot = -dot(ax1, v1) - dot(cross(d + r1, ax1), w1) + dot(ax1, v2) + // dot(cross(r2, ax1), v2) // J = [-ax1 -cross(d+r1,ax1) ax1 cross(r2,ax1)] + // Predictive limit is applied even when the limit is not active. + // Prevents a constraint speed that can lead to a constraint error in one time step. + // Want C2 = C1 + h * Cdot >= 0 + // Or: + // Cdot + C1/h >= 0 + // I do not apply a negative constraint error because that is handled in position correction. + // So: + // Cdot + max(C1, 0)/h >= 0 + // Block Solver - // We develop a block solver that includes the joint limit. This makes the - // limit stiff (inelastic) even - // when the mass has poor distribution (leading to large torques about the - // joint anchor points). + // We develop a block solver that includes the angular and linear constraints. + // This makes the limit stiffer. // - // The Jacobian has 3 rows: + // The Jacobian has 2 rows: // J = [-uT -s1 uT s2] // linear // [0 -1 0 1] // angular - // [-vT -a1 vT a2] // limit // // u = perp - // v = axis // s1 = cross(d + r1, u), s2 = cross(r2, u) // a1 = cross(d + r1, v), a2 = cross(r2, v) - - // M * (v2 - v1) = JT * df - // J * v2 = bias - // - // v2 = v1 + invM * JT * df - // J * (v1 + invM * JT * df) = bias - // K * df = bias - J * v1 = -Cdot - // K = J * invM * JT - // Cdot = J * v1 - bias - // - // Now solve for f2. - // df = f2 - f1 - // K * (f2 - f1) = -Cdot - // f2 = invK * (-Cdot) + f1 - // - // Clamp accumulated limit impulse. - // lower: f2(3) = max(f2(3), 0) - // upper: f2(3) = min(f2(3), 0) - // - // Solve for correct f2(1:2) - // K(1:2, 1:2) * f2(1:2) = -Cdot(1:2) - K(1:2,3) * f2(3) + K(1:2,1:3) * f1 - // = -Cdot(1:2) - K(1:2,3) * f2(3) + K(1:2,1:2) * f1(1:2) + K(1:2,3) * f1(3) - // K(1:2, 1:2) * f2(1:2) = -Cdot(1:2) - K(1:2,3) * (f2(3) - f1(3)) + - // K(1:2,1:2) * f1(1:2) - // f2(1:2) = invK(1:2,1:2) * (-Cdot(1:2) - K(1:2,3) * (f2(3) - f1(3))) + - // f1(1:2) - // - // Now compute impulse to be applied: - // df = f2 - f1 } /** @internal */ @@ -406,7 +388,8 @@ export class PrismaticJoint extends Joint { this.m_bodyA.setAwake(true); this.m_bodyB.setAwake(true); this.m_enableLimit = flag; - this.m_impulse.z = 0.0; + this.m_lowerImpulse = 0.0; + this.m_upperImpulse = 0.0; } } @@ -434,7 +417,8 @@ export class PrismaticJoint extends Joint { this.m_bodyB.setAwake(true); this.m_lowerTranslation = lower; this.m_upperTranslation = upper; - this.m_impulse.z = 0.0; + this.m_lowerImpulse = 0.0; + this.m_upperImpulse = 0.0; } } @@ -511,7 +495,7 @@ export class PrismaticJoint extends Joint { * Get the reaction force on bodyB at the joint anchor in Newtons. */ getReactionForce(inv_dt: number): Vec2 { - return Vec2.combine(this.m_impulse.x, this.m_perp, this.m_motorImpulse + this.m_impulse.z, this.m_axis).mul(inv_dt); + return Vec2.combine(this.m_impulse.x, this.m_perp, this.m_motorImpulse + this.m_lowerImpulse + this.m_upperImpulse, this.m_axis).mul(inv_dt); } /** @@ -560,10 +544,10 @@ export class PrismaticJoint extends Joint { this.m_a1 = Vec2.crossVec2Vec2(Vec2.add(d, rA), this.m_axis); this.m_a2 = Vec2.crossVec2Vec2(rB, this.m_axis); - this.m_motorMass = mA + mB + iA * this.m_a1 * this.m_a1 + iB * this.m_a2 + this.m_axialMass = mA + mB + iA * this.m_a1 * this.m_a1 + iB * this.m_a2 * this.m_a2; - if (this.m_motorMass > 0.0) { - this.m_motorMass = 1.0 / this.m_motorMass; + if (this.m_axialMass > 0.0) { + this.m_axialMass = 1.0 / this.m_axialMass; } } @@ -578,47 +562,21 @@ export class PrismaticJoint extends Joint { const k11 = mA + mB + iA * this.m_s1 * this.m_s1 + iB * this.m_s2 * this.m_s2; const k12 = iA * this.m_s1 + iB * this.m_s2; - const k13 = iA * this.m_s1 * this.m_a1 + iB * this.m_s2 * this.m_a2; let k22 = iA + iB; if (k22 == 0.0) { // For bodies with fixed rotation. k22 = 1.0; } - const k23 = iA * this.m_a1 + iB * this.m_a2; - const k33 = mA + mB + iA * this.m_a1 * this.m_a1 + iB * this.m_a2 * this.m_a2; - this.m_K.ex.set(k11, k12, k13); - this.m_K.ey.set(k12, k22, k23); - this.m_K.ez.set(k13, k23, k33); + this.m_K.ex.set(k11, k12); + this.m_K.ey.set(k12, k22); } - // Compute motor and limit terms. if (this.m_enableLimit) { - - const jointTranslation = Vec2.dot(this.m_axis, d); // float - if (Math.abs(this.m_upperTranslation - this.m_lowerTranslation) < 2.0 * Settings.linearSlop) { - this.m_limitState = equalLimits; - - } else if (jointTranslation <= this.m_lowerTranslation) { - if (this.m_limitState != atLowerLimit) { - this.m_limitState = atLowerLimit; - this.m_impulse.z = 0.0; - } - - } else if (jointTranslation >= this.m_upperTranslation) { - if (this.m_limitState != atUpperLimit) { - this.m_limitState = atUpperLimit; - this.m_impulse.z = 0.0; - } - - } else { - this.m_limitState = inactiveLimit; - this.m_impulse.z = 0.0; - } - + this.m_translation = Vec2.dot(this.m_axis, d); } else { - this.m_limitState = inactiveLimit; - this.m_impulse.z = 0.0; + this.m_lowerImpulse = 0.0; + this.m_upperImpulse = 0.0; } if (this.m_enableMotor == false) { @@ -629,13 +587,13 @@ export class PrismaticJoint extends Joint { // Account for variable time step. this.m_impulse.mul(step.dtRatio); this.m_motorImpulse *= step.dtRatio; + this.m_lowerImpulse *= step.dtRatio; + this.m_upperImpulse *= step.dtRatio; - const P = Vec2.combine(this.m_impulse.x, this.m_perp, this.m_motorImpulse - + this.m_impulse.z, this.m_axis); - const LA = this.m_impulse.x * this.m_s1 + this.m_impulse.y - + (this.m_motorImpulse + this.m_impulse.z) * this.m_a1; - const LB = this.m_impulse.x * this.m_s2 + this.m_impulse.y - + (this.m_motorImpulse + this.m_impulse.z) * this.m_a2; + const axialImpulse = this.m_motorImpulse + this.m_lowerImpulse - this.m_upperImpulse; + const P = Vec2.combine(this.m_impulse.x, this.m_perp, axialImpulse, this.m_axis); + const LA = this.m_impulse.x * this.m_s1 + this.m_impulse.y + axialImpulse * this.m_a1; + const LB = this.m_impulse.x * this.m_s2 + this.m_impulse.y + axialImpulse * this.m_a2; vA.subMul(mA, P); wA -= iA * LA; @@ -645,6 +603,8 @@ export class PrismaticJoint extends Joint { } else { this.m_impulse.setZero(); this.m_motorImpulse = 0.0; + this.m_lowerImpulse = 0.0; + this.m_upperImpulse = 0.0; } this.m_bodyA.c_velocity.v.setVec2(vA); @@ -664,11 +624,11 @@ export class PrismaticJoint extends Joint { const iA = this.m_invIA; const iB = this.m_invIB; - // Solve linear motor constraint. - if (this.m_enableMotor && this.m_limitState != equalLimits) { + // Solve linear motor constraint + if (this.m_enableMotor) { const Cdot = Vec2.dot(this.m_axis, Vec2.sub(vB, vA)) + this.m_a2 * wB - this.m_a1 * wA; - let impulse = this.m_motorMass * (this.m_motorSpeed - Cdot); + let impulse = this.m_axialMass * (this.m_motorSpeed - Cdot); const oldImpulse = this.m_motorImpulse; const maxImpulse = step.dt * this.m_maxMotorForce; this.m_motorImpulse = Math.clamp(this.m_motorImpulse + impulse, @@ -681,57 +641,59 @@ export class PrismaticJoint extends Joint { vA.subMul(mA, P); wA -= iA * LA; - vB.addMul(mB, P); wB += iB * LB; } - const Cdot1 = Vec2.zero(); - Cdot1.x += Vec2.dot(this.m_perp, vB) + this.m_s2 * wB; - Cdot1.x -= Vec2.dot(this.m_perp, vA) + this.m_s1 * wA; - Cdot1.y = wB - wA; - - if (this.m_enableLimit && this.m_limitState != inactiveLimit) { - // Solve prismatic and limit constraint in block form. - let Cdot2 = 0; - Cdot2 += Vec2.dot(this.m_axis, vB) + this.m_a2 * wB; - Cdot2 -= Vec2.dot(this.m_axis, vA) + this.m_a1 * wA; - - const Cdot = new Vec3(Cdot1.x, Cdot1.y, Cdot2); - - const f1 = Vec3.clone(this.m_impulse); - let df = this.m_K.solve33(Vec3.neg(Cdot)); // Vec3 - this.m_impulse.add(df); - - if (this.m_limitState == atLowerLimit) { - this.m_impulse.z = Math.max(this.m_impulse.z, 0.0); - } else if (this.m_limitState == atUpperLimit) { - this.m_impulse.z = Math.min(this.m_impulse.z, 0.0); + if (this.m_enableLimit) { + // Lower limit + { + const C = this.m_translation - this.m_lowerTranslation; + const Cdot = Vec2.dot(this.m_axis, Vec2.sub(vB, vA)) + this.m_a2 * wB - this.m_a1 * wA; + let impulse = -this.m_axialMass * (Cdot + Math.max(C, 0.0) * step.inv_dt); + const oldImpulse = this.m_lowerImpulse; + this.m_lowerImpulse = Math.max(this.m_lowerImpulse + impulse, 0.0); + impulse = this.m_lowerImpulse - oldImpulse; + + const P = Vec2.mulNumVec2(impulse, this.m_axis); + const LA = impulse * this.m_a1; + const LB = impulse * this.m_a2; + + vA.subMul(mA, P); + wA -= iA * LA; + vB.addMul(mB, P); + wB += iB * LB; } + // Upper limit + // Note: signs are flipped to keep C positive when the constraint is satisfied. + // This also keeps the impulse positive when the limit is active. + { + const C = this.m_upperTranslation - this.m_translation; + const Cdot = Vec2.dot(this.m_axis, Vec2.sub(vA, vB)) + this.m_a1 * wA - this.m_a2 * wB; + let impulse = -this.m_axialMass * (Cdot + Math.max(C, 0.0) * step.inv_dt); + const oldImpulse = this.m_upperImpulse; + this.m_upperImpulse = Math.max(this.m_upperImpulse + impulse, 0.0); + impulse = this.m_upperImpulse - oldImpulse; + + const P = Vec2.mulNumVec2(impulse, this.m_axis); + const LA = impulse * this.m_a1; + const LB = impulse * this.m_a2; + + vA.addMul(mA, P); + wA += iA * LA; + vB.subMul(mB, P); + wB -= iB * LB; + } + } - // f2(1:2) = invK(1:2,1:2) * (-Cdot(1:2) - K(1:2,3) * (f2(3) - f1(3))) + - // f1(1:2) - const b = Vec2.combine(-1, Cdot1, -(this.m_impulse.z - f1.z), Vec2.neo(this.m_K.ez.x, this.m_K.ez.y)); // Vec2 - const f2r = Vec2.add(this.m_K.solve22(b), Vec2.neo(f1.x, f1.y)); // Vec2 - this.m_impulse.x = f2r.x; - this.m_impulse.y = f2r.y; - - df = Vec3.sub(this.m_impulse, f1); - - const P = Vec2.combine(df.x, this.m_perp, df.z, this.m_axis); // Vec2 - const LA = df.x * this.m_s1 + df.y + df.z * this.m_a1; // float - const LB = df.x * this.m_s2 + df.y + df.z * this.m_a2; // float - - vA.subMul(mA, P); - wA -= iA * LA; + // Solve the prismatic constraint in block form. + { + const Cdot = Vec2.zero(); + Cdot.x = Vec2.dot(this.m_perp, Vec2.sub(vB, vA)) + this.m_s2 * wB - this.m_s1 * wA; + Cdot.y = wB - wA; - vB.addMul(mB, P); - wB += iB * LB; - } else { - // Limit is inactive, just solve the prismatic constraint in block form. - const df = this.m_K.solve22(Vec2.neg(Cdot1)); // Vec2 - this.m_impulse.x += df.x; - this.m_impulse.y += df.y; + const df = this.m_K.solve(Vec2.neg(Cdot)); + this.m_impulse.add(df); const P = Vec2.mulNumVec2(df.x, this.m_perp); // Vec2 const LA = df.x * this.m_s1 + df.y; // float @@ -797,23 +759,18 @@ export class PrismaticJoint extends Joint { const translation = Vec2.dot(axis, d); // float if (Math.abs(this.m_upperTranslation - this.m_lowerTranslation) < 2.0 * linearSlop) { - // Prevent large angular corrections - C2 = Math.clamp(translation, -maxLinearCorrection, maxLinearCorrection); + C2 = translation; linearError = Math.max(linearError, Math.abs(translation)); active = true; } else if (translation <= this.m_lowerTranslation) { - // Prevent large linear corrections and allow some slop. - C2 = Math.clamp(translation - this.m_lowerTranslation + linearSlop, - -maxLinearCorrection, 0.0); + C2 = Math.min(translation - this.m_lowerTranslation, 0.0); linearError = Math .max(linearError, this.m_lowerTranslation - translation); active = true; } else if (translation >= this.m_upperTranslation) { - // Prevent large linear corrections and allow some slop. - C2 = Math.clamp(translation - this.m_upperTranslation - linearSlop, 0.0, - maxLinearCorrection); + C2 = Math.max(translation - this.m_upperTranslation, 0.0); linearError = Math .max(linearError, translation - this.m_upperTranslation); active = true; diff --git a/src/dynamics/joint/WheelJoint.ts b/src/dynamics/joint/WheelJoint.ts index 8c9bae74..a4ab81f0 100644 --- a/src/dynamics/joint/WheelJoint.ts +++ b/src/dynamics/joint/WheelJoint.ts @@ -32,6 +32,7 @@ import { Body } from '../Body'; import { TimeStep } from "../Solver"; +const _ASSERT = typeof ASSERT === 'undefined' ? false : ASSERT; const _CONSTRUCTOR_FACTORY = typeof CONSTRUCTOR_FACTORY === 'undefined' ? false : CONSTRUCTOR_FACTORY; @@ -44,6 +45,18 @@ const _CONSTRUCTOR_FACTORY = typeof CONSTRUCTOR_FACTORY === 'undefined' ? false * game. */ export interface WheelJointOpt extends JointOpt { + /** + * Enable/disable the joint limit. + */ + enableLimit?: boolean; + /** + * The lower translation limit, usually in meters. + */ + lowerTranslation?: number; + /** + * The upper translation limit, usually in meters. + */ + upperTranslation?: number; /** * Enable/disable the joint motor. */ @@ -57,13 +70,13 @@ export interface WheelJointOpt extends JointOpt { */ motorSpeed?: number; /** - * Suspension frequency, zero indicates no suspension. + * Suspension stiffness. Typically in units N/m. */ - frequencyHz?: number; + stiffness?: number; /** - * Suspension damping ratio, one indicates critical damping. + * Suspension damping. Typically in units of N*s/m. */ - dampingRatio?: number; + damping?: number; } /** * Wheel joint definition. This requires defining a line of motion using an axis @@ -89,18 +102,22 @@ export interface WheelJointDef extends JointDef, WheelJointOpt { } const DEFAULTS = { + enableLimit : false, + lowerTranslation : 0.0, + upperTranslation : 0.0, enableMotor : false, maxMotorTorque : 0.0, motorSpeed : 0.0, - frequencyHz : 2.0, - dampingRatio : 0.7, + stiffness : 0.0, + damping : 0.0, }; /** * A wheel joint. This joint provides two degrees of freedom: translation along * an axis fixed in bodyA and rotation in the plane. In other words, it is a * point to line constraint with a rotational motor and a linear spring/damper. - * This joint is designed for vehicle suspensions. + * The spring/damper is initialized upon creation. This joint is designed for + * vehicle suspensions. */ export class WheelJoint extends Joint { static TYPE = 'wheel-joint' as const; @@ -114,16 +131,25 @@ export class WheelJoint extends Joint { /** @internal */ m_mass: number; /** @internal */ m_impulse: number; /** @internal */ m_motorMass: number; + /** @internal */ m_axialMass: number; /** @internal */ m_motorImpulse: number; /** @internal */ m_springMass: number; /** @internal */ m_springImpulse: number; + /** @internal */ m_lowerImpulse: number; + /** @internal */ m_upperImpulse: number; + /** @internal */ m_translation: number; + /** @internal */ m_lowerTranslation: number; + /** @internal */ m_upperTranslation: number; + /** @internal */ m_maxMotorTorque: number; /** @internal */ m_motorSpeed: number; + + /** @internal */ m_enableLimit: boolean; /** @internal */ m_enableMotor: boolean; - /** @internal */ m_frequencyHz: number; - /** @internal */ m_dampingRatio: number; + /** @internal */ m_stiffness: number; + /** @internal */ m_damping: number; /** @internal */ m_bias: number; /** @internal */ m_gamma: number; @@ -165,6 +191,13 @@ export class WheelJoint extends Joint { this.m_localXAxisA = Vec2.clone(axis ? bodyA.getLocalVector(axis) : def.localAxisA || def.localAxis || Vec2.neo(1.0, 0.0)); this.m_localYAxisA = Vec2.crossNumVec2(1.0, this.m_localXAxisA); + this.m_axialMass = 0.0; + this.m_lowerImpulse = 0.0; + this.m_upperImpulse = 0.0; + this.m_lowerTranslation = def.lowerTranslation; + this.m_upperTranslation = def.upperTranslation; + this.m_enableLimit = def.enableLimit; + this.m_mass = 0.0; this.m_impulse = 0.0; this.m_motorMass = 0.0; @@ -176,12 +209,12 @@ export class WheelJoint extends Joint { this.m_motorSpeed = def.motorSpeed; this.m_enableMotor = def.enableMotor; - this.m_frequencyHz = def.frequencyHz; - this.m_dampingRatio = def.dampingRatio; - this.m_bias = 0.0; this.m_gamma = 0.0; + this.m_stiffness = def.stiffness; + this.m_damping = def.damping; + // Linear constraint (point-to-line) // d = pB - pA = xB + rB - xA - rA // C = dot(ay, d) @@ -210,11 +243,16 @@ export class WheelJoint extends Joint { bodyB: this.m_bodyB, collideConnected: this.m_collideConnected, + lowerTranslation: this.m_lowerTranslation, + upperTranslation: this.m_upperTranslation, + enableLimit: this.m_enableLimit, + enableMotor: this.m_enableMotor, maxMotorTorque: this.m_maxMotorTorque, motorSpeed: this.m_motorSpeed, - frequencyHz: this.m_frequencyHz, - dampingRatio: this.m_dampingRatio, + + stiffness: this.m_stiffness, + damping: this.m_damping, localAnchorA: this.m_localAnchorA, localAnchorB: this.m_localAnchorB, @@ -303,6 +341,55 @@ export class WheelJoint extends Joint { return wB - wA; } + /** + * Is the joint limit enabled? + */ + isLimitEnabled(): boolean { + return this.m_enableLimit; + } + + /** + * Enable/disable the joint translation limit. + */ + enableLimit(flag: boolean): void { + if (flag == this.m_enableLimit) return; + this.m_bodyA.setAwake(true); + this.m_bodyB.setAwake(true); + this.m_enableLimit = flag; + this.m_lowerImpulse = 0.0; + this.m_upperImpulse = 0.0; + } + + /** + * Get the lower joint translation limit, usually in meters. + */ + getLowerLimit(): number { + return this.m_lowerTranslation; + } + + /** + * Get the upper joint translation limit, usually in meters. + */ + getUpperLimit(): number { + return this.m_upperTranslation; + } + + /** + * Set the joint translation limits, usually in meters. + */ + setLimits(lower: number, upper: number) { + _ASSERT && Math.assert(lower <= upper); + if (lower != this.m_lowerTranslation || upper != this.m_upperTranslation) { + this.m_bodyA.setAwake(true); + this.m_bodyB.setAwake(true); + this.m_lowerTranslation = lower; + this.m_upperTranslation = upper; + this.m_lowerImpulse = 0.0; + this.m_upperImpulse = 0.0; + } + } + + /** * Is the joint motor enabled? */ @@ -359,26 +446,25 @@ export class WheelJoint extends Joint { } /** - * Set/Get the spring frequency in hertz. Setting the frequency to zero disables - * the spring. + * Access spring stiffness */ - setSpringFrequencyHz(hz: number): void { - this.m_frequencyHz = hz; + setStiffness(stiffness: number): void { + this.m_stiffness = stiffness; } - getSpringFrequencyHz(): number { - return this.m_frequencyHz; + getStiffness(): number { + return this.m_stiffness; } /** - * Set/Get the spring damping ratio + * Access damping */ - setSpringDampingRatio(ratio: number): void { - this.m_dampingRatio = ratio; + setDamping(damping: number): void { + this.m_damping = damping; } - getSpringDampingRatio(): number { - return this.m_dampingRatio; + getDamping(): number { + return this.m_damping; } /** @@ -457,50 +543,49 @@ export class WheelJoint extends Joint { } // Spring constraint + this.m_ax = Rot.mulVec2(qA, this.m_localXAxisA); + this.m_sAx = Vec2.crossVec2Vec2(Vec2.add(d, rA), this.m_ax); + this.m_sBx = Vec2.crossVec2Vec2(rB, this.m_ax); + + const invMass = mA + mB + iA * this.m_sAx * this.m_sAx + iB * this.m_sBx * this.m_sBx; + if (invMass > 0.0) { + this.m_axialMass = 1.0 / invMass; + } else { + this.m_axialMass = 0.0; + } + this.m_springMass = 0.0; this.m_bias = 0.0; this.m_gamma = 0.0; - if (this.m_frequencyHz > 0.0) { - this.m_ax = Rot.mulVec2(qA, this.m_localXAxisA); - this.m_sAx = Vec2.crossVec2Vec2(Vec2.add(d, rA), this.m_ax); - this.m_sBx = Vec2.crossVec2Vec2(rB, this.m_ax); - - const invMass = mA + mB + iA * this.m_sAx * this.m_sAx + iB * this.m_sBx - * this.m_sBx; // float - - if (invMass > 0.0) { - this.m_springMass = 1.0 / invMass; - - const C = Vec2.dot(d, this.m_ax); // float + if (this.m_stiffness > 0.0 && invMass > 0.0) { + this.m_springMass = 1.0 / invMass; - // Frequency - const omega = 2.0 * Math.PI * this.m_frequencyHz; // float + const C = Vec2.dot(d, this.m_ax); - // Damping coefficient - const damp = 2.0 * this.m_springMass * this.m_dampingRatio * omega; // float - - // Spring stiffness - const k = this.m_springMass * omega * omega; // float - - // magic formulas - const h = step.dt; // float - this.m_gamma = h * (damp + h * k); - if (this.m_gamma > 0.0) { - this.m_gamma = 1.0 / this.m_gamma; - } + // magic formulas + const h = step.dt; + this.m_gamma = h * (this.m_damping + h * this.m_stiffness); + if (this.m_gamma > 0.0) { + this.m_gamma = 1.0 / this.m_gamma; + } - this.m_bias = C * h * k * this.m_gamma; + this.m_bias = C * h * this.m_stiffness * this.m_gamma; - this.m_springMass = invMass + this.m_gamma; - if (this.m_springMass > 0.0) { - this.m_springMass = 1.0 / this.m_springMass; - } + this.m_springMass = invMass + this.m_gamma; + if (this.m_springMass > 0.0) { + this.m_springMass = 1.0 / this.m_springMass; } } else { this.m_springImpulse = 0.0; } - // Rotational motor + if (this.m_enableLimit) { + this.m_translation = Vec2.dot(this.m_ax, d); + } else { + this.m_lowerImpulse = 0.0; + this.m_upperImpulse = 0.0; + } + if (this.m_enableMotor) { this.m_motorMass = iA + iB; if (this.m_motorMass > 0.0) { @@ -517,9 +602,10 @@ export class WheelJoint extends Joint { this.m_springImpulse *= step.dtRatio; this.m_motorImpulse *= step.dtRatio; - const P = Vec2.combine(this.m_impulse, this.m_ay, this.m_springImpulse, this.m_ax); - const LA = this.m_impulse * this.m_sAy + this.m_springImpulse * this.m_sAx + this.m_motorImpulse; - const LB = this.m_impulse * this.m_sBy + this.m_springImpulse * this.m_sBx + this.m_motorImpulse; + const axialImpulse = this.m_springImpulse + this.m_lowerImpulse - this.m_upperImpulse; + const P = Vec2.combine(this.m_impulse, this.m_ay, axialImpulse, this.m_ax); + const LA = this.m_impulse * this.m_sAy + axialImpulse * this.m_sAx + this.m_motorImpulse; + const LB = this.m_impulse * this.m_sBy + axialImpulse * this.m_sBx + this.m_motorImpulse; vA.subMul(this.m_invMassA, P); wA -= this.m_invIA * LA; @@ -531,6 +617,8 @@ export class WheelJoint extends Joint { this.m_impulse = 0.0; this.m_springImpulse = 0.0; this.m_motorImpulse = 0.0; + this.m_lowerImpulse = 0.0; + this.m_upperImpulse = 0.0; } this.m_bodyA.c_velocity.v.setVec2(vA); @@ -584,6 +672,48 @@ export class WheelJoint extends Joint { wB += iB * impulse; } + if (this.m_enableLimit) { + // Lower limit + { + const C = this.m_translation - this.m_lowerTranslation; + const Cdot = Vec2.dot(this.m_ax, Vec2.sub(vB, vA)) + this.m_sBx * wB - this.m_sAx * wA; + let impulse = -this.m_axialMass * (Cdot + Math.max(C, 0.0) * step.inv_dt); + const oldImpulse = this.m_lowerImpulse; + this.m_lowerImpulse = Math.max(this.m_lowerImpulse + impulse, 0.0); + impulse = this.m_lowerImpulse - oldImpulse; + + const P = Vec2.mulNumVec2(impulse, this.m_ax); + const LA = impulse * this.m_sAx; + const LB = impulse * this.m_sBx; + + vA.subMul(mA, P); + wA -= iA * LA; + vA.addMul(mB, P); + wB += iB * LB; + } + + // Upper limit + // Note: signs are flipped to keep C positive when the constraint is satisfied. + // This also keeps the impulse positive when the limit is active. + { + const C = this.m_upperTranslation - this.m_translation; + const Cdot = Vec2.dot(this.m_ax, Vec2.sub(vA, vB)) + this.m_sAx * wA - this.m_sBx * wB; + let impulse = -this.m_axialMass * (Cdot + Math.max(C, 0.0) * step.inv_dt); + const oldImpulse = this.m_upperImpulse; + this.m_upperImpulse = Math.max(this.m_upperImpulse + impulse, 0.0); + impulse = this.m_upperImpulse - oldImpulse; + + const P = Vec2.mulNumVec2(impulse, this.m_ax); + const LA = impulse * this.m_sAx; + const LB = impulse * this.m_sBx; + + vA.addMul(mA, P); + wA += iA * LA; + vA.subMul(mB, P); + wB -= iB * LB; + } + } + // Solve point to line constraint { const Cdot = Vec2.dot(this.m_ay, vB) - Vec2.dot(this.m_ay, vA) + this.m_sBy @@ -617,47 +747,98 @@ export class WheelJoint extends Joint { const cB = this.m_bodyB.c_position.c; let aB = this.m_bodyB.c_position.a; - const qA = Rot.neo(aA); - const qB = Rot.neo(aB); + let linearError = 0.0; + + if (this.m_enableLimit) { + const qA = Rot.neo(aA); + const qB = Rot.neo(aB); + + const rA = Rot.mulVec2(qA, Vec2.sub(this.m_localAnchorA, this.m_localCenterA)); + const rB = Rot.mulVec2(qB, Vec2.sub(this.m_localAnchorB, this.m_localCenterB)); + const d = Vec2.zero(); + d.addCombine(1, cB, 1, rB); + d.subCombine(1, cA, 1, rA); + + const ax = Rot.mulVec2(qA, this.m_localXAxisA); + const sAx = Vec2.crossVec2Vec2(Vec2.add(d, rA), this.m_ax); + const sBx = Vec2.crossVec2Vec2(rB, this.m_ax); + + let C = 0.0; + const translation = Vec2.dot(ax, d); + if (Math.abs(this.m_upperTranslation - this.m_lowerTranslation) < 2.0 * Settings.linearSlop) { + C = translation; + } else if (translation <= this.m_lowerTranslation) { + C = Math.min(translation - this.m_lowerTranslation, 0.0); + } else if (translation >= this.m_upperTranslation) { + C = Math.max(translation - this.m_upperTranslation, 0.0); + } - const rA = Rot.mulVec2(qA, Vec2.sub(this.m_localAnchorA, this.m_localCenterA)); - const rB = Rot.mulVec2(qB, Vec2.sub(this.m_localAnchorB, this.m_localCenterB)); - const d = Vec2.zero(); - d.addCombine(1, cB, 1, rB); - d.subCombine(1, cA, 1, rA); + if (C != 0.0) { + const invMass = this.m_invMassA + this.m_invMassB + this.m_invIA * sAx * sAx + this.m_invIB * sBx * sBx; + let impulse = 0.0; + if (invMass != 0.0) { + impulse = -C / invMass; + } - const ay = Rot.mulVec2(qA, this.m_localYAxisA); + const P = Vec2.mulNumVec2(impulse, ax); + const LA = impulse * sAx; + const LB = impulse * sBx; - const sAy = Vec2.crossVec2Vec2(Vec2.add(d, rA), ay); // float - const sBy = Vec2.crossVec2Vec2(rB, ay); // float + cA.subMul(this.m_invMassA, P); + aA -= this.m_invIA * LA; + cB.addMul(this.m_invMassB, P); + aB += this.m_invIB * LB; - const C = Vec2.dot(d, ay); // float + linearError = Math.abs(C); + } + } - const k = this.m_invMassA + this.m_invMassB + this.m_invIA * this.m_sAy - * this.m_sAy + this.m_invIB * this.m_sBy * this.m_sBy; // float + // Solve perpendicular constraint + { + const qA = Rot.neo(aA); + const qB = Rot.neo(aB); - let impulse; // float - if (k != 0.0) { - impulse = -C / k; - } else { - impulse = 0.0; - } + const rA = Rot.mulVec2(qA, Vec2.sub(this.m_localAnchorA, this.m_localCenterA)); + const rB = Rot.mulVec2(qB, Vec2.sub(this.m_localAnchorB, this.m_localCenterB)); + const d = Vec2.zero(); + d.addCombine(1, cB, 1, rB); + d.subCombine(1, cA, 1, rA); + + const ay = Rot.mulVec2(qA, this.m_localYAxisA); + + const sAy = Vec2.crossVec2Vec2(Vec2.add(d, rA), ay); // float + const sBy = Vec2.crossVec2Vec2(rB, ay); // float - const P = Vec2.mulNumVec2(impulse, ay); // Vec2 - const LA = impulse * sAy; // float - const LB = impulse * sBy; // float + const C = Vec2.dot(d, ay); // float - cA.subMul(this.m_invMassA, P); - aA -= this.m_invIA * LA; - cB.addMul(this.m_invMassB, P); - aB += this.m_invIB * LB; + const k = this.m_invMassA + this.m_invMassB + this.m_invIA * this.m_sAy + * this.m_sAy + this.m_invIB * this.m_sBy * this.m_sBy; // float + + let impulse; // float + if (k != 0.0) { + impulse = -C / k; + } else { + impulse = 0.0; + } + + const P = Vec2.mulNumVec2(impulse, ay); // Vec2 + const LA = impulse * sAy; // float + const LB = impulse * sBy; // float + + cA.subMul(this.m_invMassA, P); + aA -= this.m_invIA * LA; + cB.addMul(this.m_invMassB, P); + aB += this.m_invIB * LB; + + linearError = Math.max(linearError, Math.abs(C)); + } this.m_bodyA.c_position.c.setVec2(cA); this.m_bodyA.c_position.a = aA; this.m_bodyB.c_position.c.setVec2(cB); this.m_bodyB.c_position.a = aB; - return Math.abs(C) <= Settings.linearSlop; + return linearError <= Settings.linearSlop; } }