public void ImportJointData_SpecificLimit_Succeeds()
        {
            var joint = new Joint(
                name: "custom_joint", type: "planar", parent: "base", child: "link",
                limit: new Joint.Limit(4, 5, 6, 7),
                dynamics: new Joint.Dynamics(8, 9));

            GameObject baseObject = new GameObject("base");
            GameObject linkObject = new GameObject("link");

            linkObject.transform.parent = baseObject.transform;

            UrdfJoint.Create(baseObject, UrdfJoint.JointTypes.Fixed);
            TestUrdfJointPlanar urdfJoint        = linkObject.AddComponent <TestUrdfJointPlanar>();
            ArticulationBody    articulationBody = linkObject.GetComponent <ArticulationBody>();

            urdfJoint.TestImportJointData(joint);

            Assert.AreEqual(ArticulationDofLock.LockedMotion, articulationBody.linearLockX);
            Assert.AreEqual(ArticulationDofLock.LimitedMotion, articulationBody.linearLockY);
            Assert.AreEqual(ArticulationDofLock.LimitedMotion, articulationBody.linearLockZ);

            Assert.AreEqual(4, articulationBody.xDrive.lowerLimit);
            Assert.AreEqual(4, articulationBody.yDrive.lowerLimit);
            Assert.AreEqual(4, articulationBody.zDrive.lowerLimit);
            Assert.AreEqual(5, articulationBody.xDrive.upperLimit);
            Assert.AreEqual(5, articulationBody.yDrive.upperLimit);
            Assert.AreEqual(5, articulationBody.zDrive.upperLimit);
            Assert.AreEqual(6, articulationBody.xDrive.forceLimit);
            Assert.AreEqual(6, articulationBody.yDrive.forceLimit);
            Assert.AreEqual(6, articulationBody.zDrive.forceLimit);
            Assert.AreEqual(7, articulationBody.maxLinearVelocity);

            Object.DestroyImmediate(baseObject);
        }
        public void ImportJointData_DefaultAxis_Succeeds(Joint.Axis axis, Quaternion expectedAnchorRotation)
        {
            var joint = new Joint(
                name: "custom_joint", type: "continuous", parent: "base", child: "link",
                axis: axis);

            GameObject baseObject = new GameObject("base");
            GameObject linkObject = new GameObject("link");

            linkObject.transform.parent = baseObject.transform;

            UrdfJoint.Create(baseObject, UrdfJoint.JointTypes.Fixed);
            TestUrdfJointPlanar urdfJoint        = linkObject.AddComponent <TestUrdfJointPlanar>();
            ArticulationBody    articulationBody = linkObject.GetComponent <ArticulationBody>();

            urdfJoint.TestImportJointData(joint);

            UnityEngine.Assertions.Assert.AreApproximatelyEqual(expectedAnchorRotation.w, articulationBody.anchorRotation.w);
            UnityEngine.Assertions.Assert.AreApproximatelyEqual(expectedAnchorRotation.x, articulationBody.anchorRotation.x);
            UnityEngine.Assertions.Assert.AreApproximatelyEqual(expectedAnchorRotation.y, articulationBody.anchorRotation.y);
            UnityEngine.Assertions.Assert.AreApproximatelyEqual(expectedAnchorRotation.z, articulationBody.anchorRotation.z);

            Object.DestroyImmediate(baseObject);
        }