Skip to content

Commit

Permalink
Browse files Browse the repository at this point in the history
## [1.3.5] - 2024-10-04

### Added

* Motor Jacobians have access to the Jacobian header in the Solve methods now

### Changed

* Documentation updates
* Updated Burst dependency to version 1.8.18
* Updated Unity Test Framework dependency to version 1.4.5
* Updated Mathematics dependency to version 1.3.2
* Updated entities packages dependencies

### Fixed

* The "Use Spring" feature in the built-in `HingeJoint` now works correctly. Both the joint force values and the constraint relaxation parameters are set to the appropriate values in the underlying engine and the Unity Physics simulation behavior now closely matches the behavior in built-in physics.
* Fixed a case that could lead to invalid data in the impulse handling within the LinearLimitJacobian
* Limits in Hinge Joint authoring components, enabled via the "Use Limits" option, are now respected when the "Use Spring" option is also enabled.
  • Loading branch information
Unity Technologies committed Oct 4, 2024
1 parent 71daa25 commit d160800
Show file tree
Hide file tree
Showing 36 changed files with 1,741 additions and 1,096 deletions.
23 changes: 22 additions & 1 deletion CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,26 @@ uid: unity-physics-changelog

# Changelog

## [1.3.5] - 2024-10-04

### Added

* Motor Jacobians have access to the Jacobian header in the Solve methods now

### Changed

* Documentation updates
* Updated Burst dependency to version 1.8.18
* Updated Unity Test Framework dependency to version 1.4.5
* Updated Mathematics dependency to version 1.3.2
* Updated entities packages dependencies

### Fixed

* The "Use Spring" feature in the built-in `HingeJoint` now works correctly. Both the joint force values and the constraint relaxation parameters are set to the appropriate values in the underlying engine and the Unity Physics simulation behavior now closely matches the behavior in built-in physics.
* Fixed a case that could lead to invalid data in the impulse handling within the LinearLimitJacobian
* Limits in Hinge Joint authoring components, enabled via the "Use Limits" option, are now respected when the "Use Spring" option is also enabled.


## [1.3.2] - 2024-09-06

Expand All @@ -21,6 +41,7 @@ uid: unity-physics-changelog
* Fixed an issue with negative collider scales during baking. Negative scales in GameObjects are now correctly interpreted and can be used to correctly flip GameObjects together with their associated colliders.



## [1.3.0-pre.4] - 2024-07-17

### Added
Expand Down Expand Up @@ -143,7 +164,7 @@ uid: unity-physics-changelog

### Changed

* Update package `com.unity.mathematics` from `1.2.6` to `1.3.2` version.
* Update package `com.unity.mathematics` from `1.2.6` to `1.3.1` version.
* Analytics API update to `SceneSimulationAnalytics.cs` file.
* collider files renamed to `BoxCollider.cs`, `CapsuleCollider.cs`, `Collider.cs`, `MeshCollider.cs`, `SphereCollider.cs` and `TerrainCollider.cs`.
* The `EnsureUniqueColliderSystem` now runs first in the `BeforePhysicsSystemGroup` instead of after the `AfterPhysicsSystemGroup`. A system that instantiates prefabs using unique colliders during runtime should run in the `BeforePhysicsSystemGroup` to avoid a bug where colliders would not be unique during prefab instantiation.
Expand Down
1 change: 0 additions & 1 deletion Documentation~/design.md
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@ Unity Physics keeps data compatibility with the Havok Physics Integration (HPI)
|------------|----------------------------------------------------------------------------------------------------|
| Base | Containers and Math used throughout Unity.Physics. |
| Collision | Contains all code for collision detection and spatial queries. |
| DFG | Contains all code for DataFlowGraph that performs Collider and Ray Cast query on a CollisionWorld. |
| Dynamics | Contains all code for integration, constraint solving and world stepping. |
| ECS | Contains the components and systems for exposing Unity Physics to ECS. |
| Extensions | Optional components for characters, vehicles, debugging helpers etc. |
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ namespace Unity.Physics.Tests.Joints
/// Passing test does not necessarily mean good-looking joint behavior or stability for systems of multiple constraints, but the test
/// will catch a lot of basic mathematical errors in the solver.
/// </summary>
class JointTests
class JointStressTests
{
//
// Tiny simulation for a single body pair and joint, used by all of the tests
Expand Down
187 changes: 187 additions & 0 deletions Tests/PlayModeTests/Dynamics/Joint/JointVerificationTests.cs
Original file line number Diff line number Diff line change
@@ -0,0 +1,187 @@
using NUnit.Framework;
using Unity.Mathematics;
using UnityEngine;

namespace Unity.Physics.Tests.Joints
{
/// <summary>
/// Specific verification tests for specific joints, designed to ensure we obtain the expected physical behavior.
/// </summary>
[TestFixture]
class JointVerificationTests
{
PhysicsWorld m_World;
SimulationStepInput m_StepInput;
int m_DynamicBodyIndex;
int m_StaticBodyIndex;
int m_JointIndex;

void Simulate(PhysicsJoint physicsJoint, int numSteps = 480)
{
var joint = new Joint
{
BodyPair = new BodyIndexPair { BodyIndexA = m_DynamicBodyIndex, BodyIndexB = m_StaticBodyIndex },
AFromJoint = physicsJoint.BodyAFromJoint.AsMTransform(),
BFromJoint = physicsJoint.BodyBFromJoint.AsMTransform(),
Constraints = physicsJoint.m_Constraints,
};

var joints = m_World.DynamicsWorld.Joints;
joints[m_JointIndex] = joint;

var context = new SimulationContext();

context.Reset(m_StepInput);
for (var i = 0; i < numSteps; ++i)
{
Simulation.StepImmediate(m_StepInput, ref context);
#if DEBUG_PRINT_BODY_POSITION
if (i % 10 == 0)
Debug.Log(m_World.DynamicsWorld.MotionDatas[m_DynamicBodyIndex].WorldFromMotion.pos);
#endif
}
}

[TearDown]
public void TearDown()
{
m_World.Dispose();
}

[SetUp]
public void Setup()
{
m_World = new PhysicsWorld(1, 1, 1);

m_DynamicBodyIndex = 0;
m_StaticBodyIndex = 1;
m_JointIndex = 0;

// Simulation step input
m_StepInput = new SimulationStepInput()
{
World = m_World,
Gravity = new float3(0, -9.81f, 0),
NumSolverIterations = 4,
TimeStep = 1 / 60f,
SynchronizeCollisionWorld = false // we don't need any collisions in these tests
};

// position the dynamic and static bodies at origin
var body = new RigidBody
{
WorldFromBody = new RigidTransform(quaternion.identity, float3.zero),
Scale = 1.0f,
};

// mass properties of a unit sphere
var massProperties = MassProperties.UnitSphere;
var mass = 1.5f;

var velocity = new MotionVelocity
{
InverseInertia = math.rcp(massProperties.MassDistribution.InertiaTensor * mass),
InverseMass = math.rcp(mass),
GravityFactor = 1f
};

var bodies = m_World.CollisionWorld.Bodies;
bodies[m_DynamicBodyIndex] = body;
bodies[m_StaticBodyIndex] = body;

var motionDatas = m_World.MotionDatas;
motionDatas[m_DynamicBodyIndex] = MotionData.Zero;

var motionVelocities = m_World.MotionVelocities;
motionVelocities[m_DynamicBodyIndex] = velocity;
}

/// <summary>
/// Creates a spring joint between a dynamic and static body with a spring stiffness that should
/// result in a target equilibrium position of a given distance unit from the anchor point.
/// </summary>
[Test]
public void Spring_ReachesCorrectEquilibriumExtension([Values(0.3f, 0.5f, 0.8f, 1.0f)] float dampingRatio)
{
var equilibriumSpringExtension = 0.75f;
var dynMotionVelocity = m_World.DynamicsWorld.MotionVelocities[m_DynamicBodyIndex];
var mass = math.rcp(dynMotionVelocity.InverseMass);
var restoringForce = -m_StepInput.Gravity.y * mass;
var requiredStiffnessCoefficient = restoringForce / equilibriumSpringExtension;

// convert spring stiffness to spring frequency:
var springFrequency = JacobianUtilities.CalculateSpringFrequencyFromSpringConstant(requiredStiffnessCoefficient, mass);

var physicsJoint = PhysicsJoint.CreateLimitedDistance(float3.zero, float3.zero, new Math.FloatRange(0, 0), float.MaxValue,
springFrequency, dampingRatio);
Simulate(physicsJoint);

var dynMotionData = m_World.DynamicsWorld.MotionDatas[m_DynamicBodyIndex];
Assert.That(dynMotionData.WorldFromMotion.pos.y, Is.EqualTo(-equilibriumSpringExtension).Within(1e-3));
}

///<summary>
/// Creates a hinge joint with a locked spring and a distinct arm length,
/// and checks if the hinged body settles at the expected target angle.
/// </summary>
[Test]
public void Hinge_AngularSpring_ReachesCorrectEquilibriumAngle([Values(0.05f, 0.1f, 0.3f)] float dampingRatio)
{
var armLength = 0.5f;
var jointAnchor = new BodyFrame(new RigidTransform(quaternion.identity, new float3(0, 0, armLength)));

// Create hinge joint and set it up as an angular spring with target at 0 and a specific expected equilibrium angle
var equilibriumAngleInDegrees = 15.0f;
var equilibriumAngle = math.radians(equilibriumAngleInDegrees);
var targetAngle = 0.0f;

// Required restoring torque under the assumption that the body is at 1 distance unit away from
// the hinge joint anchor point.
var dynMotionVelocity = m_World.DynamicsWorld.MotionVelocities[m_DynamicBodyIndex];
var restoringTorque = armLength * -m_StepInput.Gravity.y * math.rcp(dynMotionVelocity.InverseMass) * math.sin(math.PIHALF - equilibriumAngle);

// spring stiffness to achieve the required restoring torque at the target angle
var requiredStiffnessCoefficient = restoringTorque / equilibriumAngle;

// convert spring stiffness to spring frequency:
var inertia = math.rcp(dynMotionVelocity.InverseInertia);
var springFrequency = JacobianUtilities.CalculateSpringFrequencyFromSpringConstant(requiredStiffnessCoefficient, inertia.x);

var rotationalMotor = PhysicsJoint.CreateRotationalMotor(jointAnchor, jointAnchor, targetAngle, float.MaxValue,
springFrequency, dampingRatio);
Simulate(rotationalMotor, 600);

// check that body is at expected angle
var dynMotionData = m_World.DynamicsWorld.MotionDatas[m_DynamicBodyIndex];
var dynRot = dynMotionData.WorldFromMotion.rot;
((Quaternion)dynRot).ToAngleAxis(out var angle, out var axis);
Assert.That((float3)axis, Is.PrettyCloseTo(new float3(-1, 0, 0)));
Assert.That(angle, Is.EqualTo(equilibriumAngleInDegrees).Within(1));
}

///<summary>
/// Creates a hinge joint with limits locked by a soft angular spring, and checks if the hinged body hits the limit.
/// </summary>
[Test]
public void Hinge_HitsLimit([Values(0.0f, 0.1f, 0.3f)] float dampingRatio, [Values(0.1f, 0.5f, 1f)] float springFrequency)
{
var armLength = 0.5f;
var jointAnchor = new BodyFrame(new RigidTransform(quaternion.identity, new float3(0, 0, armLength)));

// create hinge joint with limits
var limitAngleInDegrees = 10.0f;
var limitAngle = math.radians(limitAngleInDegrees);
var rotationalMotor = PhysicsJoint.CreateRotationalMotor(jointAnchor, jointAnchor, 0, new Math.FloatRange(-limitAngle, limitAngle), float.MaxValue,
springFrequency, dampingRatio);

Simulate(rotationalMotor, 600);

// check that body is at expected angle
var dynMotionData = m_World.DynamicsWorld.MotionDatas[m_DynamicBodyIndex];
var dynRot = dynMotionData.WorldFromMotion.rot;
((Quaternion)dynRot).ToAngleAxis(out var angle, out var axis);
Assert.That((float3)axis, Is.PrettyCloseTo(new float3(-1, 0, 0)));
Assert.That(angle, Is.EqualTo(limitAngleInDegrees).Within(1));
}
}
}

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ void TestSimulateAngularVelocityMotor_ConstantSpeed(string testName, Joint joint
var position0 = motionA.WorldFromMotion.pos;
var rotation0 = motionA.WorldFromMotion.rot;

MotorTestRunner.TestSimulateMotor(testName, ref jointData,
MotorTestRunner.TestSimulateMotor(testName, ref jointData, MotorTestRunner.JointType.AngularVelocityMotor,
ref velocityA, ref velocityB, ref motionA, ref motionB,
useGravity, maxImpulse, motorOrientation, numIterations, numSteps, numStabilizingSteps,
out float3 accumulateAngularVelocity, out float3 accumulateLinearVelocity);
Expand Down Expand Up @@ -145,7 +145,7 @@ void TestSimulateAngularVelocityMotor(string testName, Joint jointData,
var rotation0 = motionA.WorldFromMotion.rot;
var motorOrientation = math.normalizesafe(targetVelocity); //to only consider direction the motor is acting on

MotorTestRunner.TestSimulateMotor(testName, ref jointData,
MotorTestRunner.TestSimulateMotor(testName, ref jointData, MotorTestRunner.JointType.AngularVelocityMotor,
ref velocityA, ref velocityB, ref motionA, ref motionB,
useGravity, maxImpulse, motorOrientation, numIterations, numSteps, numStabilizingSteps,
out float3 accumulateAngularVelocity, out float3 accumulateLinearVelocity);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ void TestSimulateLinearVelocityMotor_ConstantSpeed(string testName, Joint jointD
var position0 = motionA.WorldFromMotion.pos;
var rotation0 = motionA.WorldFromMotion.rot;

MotorTestRunner.TestSimulateMotor(testName, ref jointData,
MotorTestRunner.TestSimulateMotor(testName, ref jointData, MotorTestRunner.JointType.LinearVelocityMotor,
ref velocityA, ref velocityB, ref motionA, ref motionB,
useGravity, maxImpulse, motorOrientation, numIterations, numSteps, numStabilizingSteps,
out float3 accumulateAngularVelocity, out float3 accumulateLinearVelocity);
Expand Down Expand Up @@ -160,7 +160,7 @@ void TestSimulateLinearVelocityMotor(string testName, Joint jointData,
var rotation0 = motionA.WorldFromMotion.rot;
var motorOrientation = math.normalizesafe(targetVelocity); //to only consider direction the motor is acting on

MotorTestRunner.TestSimulateMotor(testName, ref jointData,
MotorTestRunner.TestSimulateMotor(testName, ref jointData, MotorTestRunner.JointType.LinearVelocityMotor,
ref velocityA, ref velocityB, ref motionA, ref motionB,
useGravity, maxImpulse, motorOrientation, numIterations, numSteps, numStabilizingSteps,
out float3 accumulateAngularVelocity, out float3 accumulateLinearVelocity);
Expand Down
51 changes: 36 additions & 15 deletions Tests/PlayModeTests/Dynamics/Motor/MotorTestUtility.cs
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,10 @@ internal static void SetupMotionData(RigidTransform worldFromA, RigidTransform w

motionB = new MotionData //use default other than this position
{
WorldFromMotion = worldFromB
WorldFromMotion = worldFromB,
BodyFromMotion = RigidTransform.identity,
LinearDamping = 0.0f,
AngularDamping = 0.0f
};
}
}
Expand Down Expand Up @@ -236,10 +239,18 @@ internal unsafe static void SolveSingleJoint(Joint jointData, int numIterations,
Constraints = joint.m_Constraints
};

internal enum JointType
{
PositionMotor = 0,
RotationMotor = 1,
LinearVelocityMotor = 2,
AngularVelocityMotor = 3
}

// For the given test configuration and motor types, simulate the motor
// Returns: accumulated angular velocity, accumulated linear velocity, velocityA, velocityB, motionA, motionB
// Verifies 2 values: the impulse applied to the linear velocity, the impulse applied to the angular velocity
internal static void TestSimulateMotor(string testName, ref Joint jointData,
internal static void TestSimulateMotor(string testName, ref Joint jointData, JointType jointType,
ref MotionVelocity velocityA, ref MotionVelocity velocityB, ref MotionData motionA, ref MotionData motionB,
bool useGravity, float maxImpulse, float3 motorOrientation,
in int numIterations, in int numSteps, in int numStabilizingSteps,
Expand Down Expand Up @@ -275,19 +286,29 @@ internal static void TestSimulateMotor(string testName, ref Joint jointData,
SolveSingleJoint(jointData, numIterations, Timestep,
ref velocityA, ref velocityB, ref motionA, ref motionB, out NativeStream jacobians);

// Verify that the angular maxImpulse for the motor is never exceeded
var v1Ang = velocityA.AngularVelocity;
var motorImpulseAng = math.length((v1Ang - v0Ang) / velocityA.InverseInertia);
var impulseMarginAng = math.abs(motorImpulseAng) - maxImpulse;
failureMessage = $"{testName}: Angular Motor impulse {motorImpulseAng} exceeded maximum ({maxImpulse})";
Assert.LessOrEqual(impulseMarginAng, impulseThreshold, failureMessage);

// Verify that the linear maxImpulse for the motor is never exceeded, but only consider directions that the motor is acting on
var v1Lin = velocityA.LinearVelocity * motorOrientation;
var motorImpulseLin = math.length((v1Lin - v0Lin) / velocityA.InverseMass);
var impulseMarginLin = math.abs(motorImpulseLin) - maxImpulse;
failureMessage = $"{testName}: Linear Motor impulse {motorImpulseLin} exceeded maximum ({maxImpulse})";
Assert.LessOrEqual(impulseMarginLin, impulseThreshold, failureMessage);
if (jointType == JointType.AngularVelocityMotor || jointType == JointType.RotationMotor)
{
// Verify that the angular maxImpulse for the motor is never exceeded
var v1Ang = velocityA.AngularVelocity;
var undoApplyAngularImpulse = (v1Ang - v0Ang) / velocityA.InverseInertia;
var motorImpulse = math.lengthsq(undoApplyAngularImpulse);
var impulseMarginAng = motorImpulse - (maxImpulse * maxImpulse);
failureMessage =
$"{testName}: Angular Motor impulse {motorImpulse} exceeded maximum ({maxImpulse})";
Assert.LessOrEqual(impulseMarginAng, impulseThreshold, failureMessage);
}


if (jointType == JointType.LinearVelocityMotor || jointType == JointType.PositionMotor)
{
// Verify that the linear maxImpulse for the motor is never exceeded, but only consider directions
// that the motor is acting on
var v1Lin = velocityA.LinearVelocity * motorOrientation;
var motorImpulseLin = math.length((v1Lin - v0Lin) / velocityA.InverseMass);
var impulseMarginLin = math.abs(motorImpulseLin) - maxImpulse;
failureMessage = $"{testName}: Linear Motor impulse {motorImpulseLin} exceeded maximum ({maxImpulse})";
Assert.LessOrEqual(impulseMarginLin, impulseThreshold, failureMessage);
}

// Only start to accumulate after a stabilizing velocity has been achieved
if (iStep > numStabilizingSteps - 1)
Expand Down
2 changes: 1 addition & 1 deletion Tests/PlayModeTests/Dynamics/Motor/PositionMotorTests.cs
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ void TestSimulatePositionMotor(string testName, Joint jointData,
var rotation0 = motionA.WorldFromMotion.rot;
var motorOrientation = math.normalizesafe(targetPosition); //to only consider direction the motor is acting on

MotorTestRunner.TestSimulateMotor(testName, ref jointData,
MotorTestRunner.TestSimulateMotor(testName, ref jointData, MotorTestRunner.JointType.PositionMotor,
ref velocityA, ref velocityB, ref motionA, ref motionB,
useGravity, maxImpulse, motorOrientation, numIterations, numSteps, numStabilizingSteps,
out float3 accumulateAngularVelocity, out float3 accumulateLinearVelocity);
Expand Down
Loading

0 comments on commit d160800

Please sign in to comment.