diff --git a/.gitignore b/.gitignore index 5ae8c69c..624c50ba 100644 --- a/.gitignore +++ b/.gitignore @@ -114,3 +114,6 @@ tags # Persistent undo [._]*.un~ + +# UI +/UIElementsSchema \ No newline at end of file diff --git a/Assets/Scripts/CLOiSimPlugins/JointControlPlugin.cs b/Assets/Scripts/CLOiSimPlugins/JointControlPlugin.cs index 93300f20..9d1fcc74 100644 --- a/Assets/Scripts/CLOiSimPlugins/JointControlPlugin.cs +++ b/Assets/Scripts/CLOiSimPlugins/JointControlPlugin.cs @@ -5,9 +5,12 @@ */ using System.Collections.Generic; +using Any = cloisim.msgs.Any; +using messages = cloisim.msgs; public class JointControlPlugin : CLOiSimPlugin { + private List staticTfList = new List(); private List tfList = new List(); private SensorDevices.JointCommand jointCommand = null; private SensorDevices.JointState jointState = null; @@ -25,6 +28,11 @@ protected override void OnAwake() protected override void OnStart() { + if (RegisterServiceDevice(out var portService, "Info")) + { + AddThread(portService, ServiceThread); + } + if (RegisterRxDevice(out var portRx, "Rx")) { AddThread(portRx, ReceiverThread, jointCommand); @@ -52,22 +60,82 @@ private void LoadJoints() var updateRate = GetPluginParameters().GetValue("update_rate", 20); jointState.SetUpdateRate(updateRate); - if (GetPluginParameters().GetValues("joints/link", out var links)) + if (GetPluginParameters().GetValues("joints/joint", out var joints)) { - foreach (var linkName in links) + foreach (var jointName in joints) { - if (jointState != null) + // UnityEngine.Debug.Log("Joints loaded "+ jointName); + if (jointState.AddTargetJoint(jointName, out var targetLink, out var isStatic)) { - var parentFrameId = GetPluginParameters().GetAttributeInPath("joints/link[text()='" + linkName + "']", "parent_frame_id", "base_link"); + var tf = new TF(targetLink); - if (jointState.AddTarget(linkName, out var targetLink)) - { - var tf = new TF(targetLink, linkName, parentFrameId); + if (isStatic) + staticTfList.Add(tf); + else tfList.Add(tf); - // Debug.Log(link); - } } } } + // UnityEngine.Debug.Log("Joints loaded"); + } + + protected override void HandleCustomRequestMessage(in string requestType, in Any requestValue, ref DeviceMessage response) + { + switch (requestType) + { + case "request_static_transforms": + SetStaticTransformsResponse(ref response); + break; + + case "reset_odometry": + Reset(); + SetEmptyResponse(ref response); + break; + + default: + break; + } + } + + private void SetStaticTransformsResponse(ref DeviceMessage msRos2Info) + { + if (msRos2Info == null) + { + return; + } + + var ros2CommonInfo = new messages.Param(); + ros2CommonInfo.Name = "static_transforms"; + ros2CommonInfo.Value = new Any { Type = Any.ValueType.None }; + + foreach (var tf in staticTfList) + { + var ros2StaticTransformLink = new messages.Param(); + ros2StaticTransformLink.Name = "parent_frame_id"; + ros2StaticTransformLink.Value = new Any { Type = Any.ValueType.String, StringValue = tf.parentFrameId }; + + { + var tfPose = tf.GetPose(); + + var poseMessage = new messages.Pose(); + poseMessage.Position = new messages.Vector3d(); + poseMessage.Orientation = new messages.Quaternion(); + + poseMessage.Name = tf.childFrameId; + DeviceHelper.SetVector3d(poseMessage.Position, tfPose.position); + DeviceHelper.SetQuaternion(poseMessage.Orientation, tfPose.rotation); + + var ros2StaticTransformElement = new messages.Param(); + ros2StaticTransformElement.Name = "pose"; + ros2StaticTransformElement.Value = new Any { Type = Any.ValueType.Pose3d, Pose3dValue = poseMessage }; + + ros2StaticTransformLink.Childrens.Add(ros2StaticTransformElement); + // Debug.Log(poseMessage.Name + ", " + poseMessage.Position + ", " + poseMessage.Orientation); + } + + ros2CommonInfo.Childrens.Add(ros2StaticTransformLink); + } + + msRos2Info.SetMessage(ros2CommonInfo); } } \ No newline at end of file diff --git a/Assets/Scripts/CLOiSimPlugins/Modules/Base/CLOiSimPlugin.cs b/Assets/Scripts/CLOiSimPlugins/Modules/Base/CLOiSimPlugin.cs index 3f7a9ba5..4e1c73fb 100644 --- a/Assets/Scripts/CLOiSimPlugins/Modules/Base/CLOiSimPlugin.cs +++ b/Assets/Scripts/CLOiSimPlugins/Modules/Base/CLOiSimPlugin.cs @@ -15,7 +15,6 @@ enum Type { WORLD, GROUNDTRUTH, ELEVATOR, ACTOR, MICOM, JOINTCONTROL, GPS, IMU, void Reset(); } -[DefaultExecutionOrder(560)] public abstract partial class CLOiSimPlugin : MonoBehaviour, ICLOiSimPlugin { public ICLOiSimPlugin.Type type { get; protected set; } diff --git a/Assets/Scripts/CLOiSimPlugins/Modules/Base/TF.cs b/Assets/Scripts/CLOiSimPlugins/Modules/Base/TF.cs index 8b530615..a7d2404d 100644 --- a/Assets/Scripts/CLOiSimPlugins/Modules/Base/TF.cs +++ b/Assets/Scripts/CLOiSimPlugins/Modules/Base/TF.cs @@ -21,11 +21,21 @@ public TF(in SDF.Helper.Link link, in string childFrameId, in string parentFrame this.link = link; } + public TF(in SDF.Helper.Link link) + { + var parentFrame = link.JointParentLinkName; + var childFrame = link.JointChildLinkName; + this.parentFrameId = parentFrame.Replace("::", "_"); + this.childFrameId = childFrame.Replace("::", "_"); + this.link = link; + } + public Pose GetPose() { var tfLink = this.link; var tfPose = tfLink.GetPose(targetPoseFrame); + // Debug.Log(tfLink.Model.name + " <=>" + tfLink.RootModel.name); if (!tfLink.Model.Equals(tfLink.RootModel)) { var modelPose = tfLink.Model.GetPose(targetPoseFrame); @@ -34,14 +44,17 @@ public Pose GetPose() if (tfLink.JointAxis.Equals(Vector3.up) || tfLink.JointAxis.Equals(Vector3.down)) { tfPose.rotation *= Quaternion.AngleAxis(180, Vector3.right); + // Debug.Log(parentFrameId + "::" + childFrameId + "(" + tfLink.JointAxis + ") = " + modelPose.position + ", " + tfPose.position); } else if (tfLink.JointAxis.Equals(Vector3.forward) || tfLink.JointAxis.Equals(Vector3.back)) { // tfPose.rotation *= Quaternion.AngleAxis(180, Vector3.up); + // Debug.Log(parentFrameId + "::" + childFrameId + "(" + tfLink.JointAxis + ") = " + modelPose.position + ", " + tfPose.position); } else if (tfLink.JointAxis.Equals(Vector3.left) || tfLink.JointAxis.Equals(Vector3.right)) { // tfPose.rotation *= Quaternion.AngleAxis(180, Vector3.forward); + // Debug.Log(parentFrameId + "::" + childFrameId + "(" + tfLink.JointAxis + ") = " + modelPose.position + ", " + tfPose.position); } tfPose.position += modelPose.position; diff --git a/Assets/Scripts/Core/ObjectSpawning.cs b/Assets/Scripts/Core/ObjectSpawning.cs index 27f7fe97..c84dc2f6 100644 --- a/Assets/Scripts/Core/ObjectSpawning.cs +++ b/Assets/Scripts/Core/ObjectSpawning.cs @@ -219,6 +219,7 @@ private IEnumerator DeleteTargetObject(List targetObjectsTransform) if (targetObjectTransform.CompareTag("Props") || targetObjectTransform.CompareTag("Model")) { Destroy(targetObjectTransform.gameObject); + yield return new WaitForEndOfFrame(); } } diff --git a/Assets/Scripts/Devices/Camera.cs b/Assets/Scripts/Devices/Camera.cs index edcc8b15..a910ac2a 100644 --- a/Assets/Scripts/Devices/Camera.cs +++ b/Assets/Scripts/Devices/Camera.cs @@ -94,7 +94,7 @@ protected override void OnStart() protected virtual void SetupTexture() { - camSensor.clearFlags = CameraClearFlags.Nothing; + camSensor.clearFlags = CameraClearFlags.Skybox; camSensor.allowHDR = true; camSensor.depthTextureMode = DepthTextureMode.None; _universalCamData.requiresColorOption = CameraOverrideOption.On; @@ -174,7 +174,7 @@ private void SetupCamera() camSensor.renderingPath = RenderingPath.Forward; camSensor.allowMSAA = true; - camSensor.allowDynamicResolution = false; + camSensor.allowDynamicResolution = true; camSensor.useOcclusionCulling = true; camSensor.stereoTargetEye = StereoTargetEyeMask.None; camSensor.orthographic = false; @@ -192,7 +192,7 @@ private void SetupCamera() filterMode: FilterMode.Trilinear, wrapMode: TextureWrapMode.Clamp, dimension: TextureDimension.Tex2D, - msaaSamples: MSAASamples.MSAA2x, + msaaSamples: MSAASamples.MSAA4x, enableRandomWrite: false, useMipMap: true, autoGenerateMips: true, diff --git a/Assets/Scripts/Devices/Clock.cs b/Assets/Scripts/Devices/Clock.cs index ae4cb6cf..1127bfae 100644 --- a/Assets/Scripts/Devices/Clock.cs +++ b/Assets/Scripts/Devices/Clock.cs @@ -13,10 +13,10 @@ public class Clock : Device { private messages.WorldStatistics worldStat = null; -#region Filter times + #region Filter times private double prevSimTime = 0f; private double prevRealTime = 0f; -#endregion + #endregion private double restartedSimTime = 0; private double restartedRealTime = 0; @@ -24,7 +24,7 @@ public class Clock : Device private double currentSimTime = 0; private double currentRealTime = 0; -#region time in hms format + #region time in hms format public class HMS { private string _simTime = string.Empty; @@ -50,7 +50,7 @@ public void SetDiffTime(in TimeSpan ts) private void SetTimeString(ref string target, in TimeSpan ts) { - _tempSB.AppendFormat("{0}d {1}:{2}:{3}.{4}", ts.Days.ToString(), ts.Hours.ToString(), ts.Minutes.ToString(), ts.Seconds.ToString(), ts.Milliseconds.ToString()); + _tempSB.AppendFormat("{0}d {1:D2}:{2:D2}:{3:D2}.{4:D3}", ts.Days, ts.Hours, ts.Minutes, ts.Seconds, ts.Milliseconds); target = _tempSB.ToString(); _tempSB.Clear(); } @@ -63,7 +63,7 @@ private void SetTimeString(ref string target, in TimeSpan ts) private HMS hms = new HMS(); private int hmsUpdateIndex = 0; -#endregion + #endregion public double SimTime => currentSimTime; diff --git a/Assets/Scripts/Devices/JointCommand.cs b/Assets/Scripts/Devices/JointCommand.cs index 7354866c..ce097cb7 100644 --- a/Assets/Scripts/Devices/JointCommand.cs +++ b/Assets/Scripts/Devices/JointCommand.cs @@ -21,15 +21,18 @@ struct Command public Command(in Articulation joint, in float targetPosition, in float targetVelocity) { this.joint = joint; - this.targetPosition = 0; - this.targetVelocity = 0; + this.targetPosition = float.NaN; + this.targetVelocity = float.NaN; Set(targetPosition, targetVelocity); } public void Set(in float targetPosition, in float targetVelocity) { - this.targetPosition = targetPosition * (this.joint.IsRevoluteType() ? Mathf.Rad2Deg : 1); - this.targetVelocity = targetVelocity * (this.joint.IsRevoluteType() ? Mathf.Rad2Deg : 1); + if (targetPosition != float.NaN) + this.targetPosition = targetPosition * (this.joint.IsRevoluteType() ? Mathf.Rad2Deg : 1); + + if (targetVelocity != float.NaN) + this.targetVelocity = targetVelocity * (this.joint.IsRevoluteType() ? Mathf.Rad2Deg : 1); } } @@ -54,13 +57,24 @@ protected override void ProcessDevice() { if (PopDeviceMessage(out var jointCommand)) { - var linkName = jointCommand.Name; - var articulation = jointState.GetArticulation(linkName); - + var jointName = jointCommand.Name; + Debug.Log(jointName); + var articulation = jointState.GetArticulation(jointName); if (articulation != null) { - var targetPosition = (float)jointCommand.Position.Target; - var targetVelocity = (float)jointCommand.Velocity.Target; + var targetPosition = float.NaN; + if (jointCommand.Position != null) + { + targetPosition = (float)jointCommand.Position.Target; + Debug.Log("targetPosition=" + targetPosition); + } + + var targetVelocity = float.NaN; + if (jointCommand.Velocity != null) + { + targetVelocity = (float)jointCommand.Velocity.Target; + Debug.Log("targetVelocity=" + targetVelocity); + } var newCommand = new Command(articulation, targetPosition, targetVelocity); jointCommandQueue.Enqueue(newCommand); @@ -78,6 +92,7 @@ void FixedUpdate() while (jointCommandQueue.Count > 0) { var command = jointCommandQueue.Dequeue(); + // Debug.Log(command.targetVelocity + "," + command.targetPosition); command.joint.Drive(command.targetVelocity, command.targetPosition); } } diff --git a/Assets/Scripts/Devices/JointState.cs b/Assets/Scripts/Devices/JointState.cs index 88a4aa6e..c6113933 100644 --- a/Assets/Scripts/Devices/JointState.cs +++ b/Assets/Scripts/Devices/JointState.cs @@ -44,10 +44,13 @@ protected override void GenerateMessage() PushDeviceMessage(jointStateV); } - public bool AddTarget(in string targetLinkName, out SDF.Helper.Link link) + public bool AddTargetJoint(in string targetJointName, out SDF.Helper.Link link, out bool isStatic) { var childArticulationBodies = gameObject.GetComponentsInChildren(); var rootModelName = string.Empty; + link = null; + isStatic = false; + foreach (var childArticulationBody in childArticulationBodies) { // Debug.Log (childArticulationBody.name + " | " + childArticulationBody.transform.parent.name); @@ -57,33 +60,42 @@ public bool AddTarget(in string targetLinkName, out SDF.Helper.Link link) continue; } - var parentModelName = childArticulationBody.transform.parent.name; - var linkName = ((rootModelName.CompareTo(parentModelName) == 0) ? "" : parentModelName + "::") + childArticulationBody.name; - // Debug.Log("!!!!!!! " + linkName); - if (linkName.Equals(targetLinkName)) + var parentObject = childArticulationBody.transform.parent; + var parentModelName = parentObject.name; + // var linkName = ((!parentObject.CompareTag("Model") || rootModelName.CompareTo(parentModelName) == 0) ? "" : parentModelName + "::") + childArticulationBody.name; + var linkHelper = childArticulationBody.GetComponentInChildren(); + // Debug.Log("linkHelper.JointName " + linkHelper.JointName); + if (linkHelper.JointName.Equals(targetJointName)) { + // Debug.Log("AddTargetJoint " + targetJointName); + link = linkHelper; + if (childArticulationBody.jointType == ArticulationJointType.FixedJoint) + { + Debug.LogWarning("Skip to AddTargetJoint due to fixed joint: " + targetJointName); + isStatic = true; + return true; + } + var articulation = new Articulation(childArticulationBody); - articulation.SetDriveType(ArticulationDriveType.Force); var jointState = new messages.JointState(); - jointState.Name = targetLinkName; + jointState.Name = targetJointName; - articulationTable.Add(targetLinkName, new Tuple(articulation, jointState)); + articulationTable.Add(targetJointName, new Tuple(articulation, jointState)); jointStateV.JointStates.Add(jointState); - link = articulation.gameObject.GetComponentInChildren(); + // link = articulation.gameObject.GetComponentInChildren(); return true; } } - link = null; return false; } - public Articulation GetArticulation(in string targetLinkName) + public Articulation GetArticulation(in string targetJointName) { - return articulationTable.ContainsKey(targetLinkName) ? articulationTable[targetLinkName].Item1 : null; + return articulationTable.ContainsKey(targetJointName) ? articulationTable[targetJointName].Item1 : null; } void FixedUpdate() diff --git a/Assets/Scripts/Devices/Lidar.cs b/Assets/Scripts/Devices/Lidar.cs index cbce0c34..dc382738 100644 --- a/Assets/Scripts/Devices/Lidar.cs +++ b/Assets/Scripts/Devices/Lidar.cs @@ -66,7 +66,7 @@ public AsyncLaserWork(in int dataIndex, in AsyncGPUReadbackRequest request) this.request = request; } } - private List _asyncWorkList = new List(); + private AsyncLaserWork[] _asyncWorkList; private DepthData.CamBuffer[] _depthCamBuffers; private LaserData.LaserCamData[] _laserCamData; private LaserData.LaserDataOutput[] _laserDataOutput; @@ -198,10 +198,10 @@ private void SetupLaserCamera() slices: 1, depthBufferBits: DepthBits.None, colorFormat: GraphicsFormat.R8G8B8A8_UNorm, - filterMode: FilterMode.Trilinear, + filterMode: FilterMode.Bilinear, wrapMode: TextureWrapMode.Clamp, dimension: TextureDimension.Tex2D, - msaaSamples: MSAASamples.MSAA2x, + msaaSamples: MSAASamples.MSAA4x, enableRandomWrite: false, useMipMap: true, autoGenerateMips: true, @@ -263,8 +263,9 @@ private void SetupLaserCameraData() var isEven = (numberOfLaserCamData % 2 == 0) ? true : false; _parallelOptions = new ParallelOptions { MaxDegreeOfParallelism = numberOfLaserCamData }; - _laserCamData = new LaserData.LaserCamData[numberOfLaserCamData]; + _asyncWorkList = new AsyncLaserWork[numberOfLaserCamData]; _depthCamBuffers = new DepthData.CamBuffer[numberOfLaserCamData]; + _laserCamData = new LaserData.LaserCamData[numberOfLaserCamData]; _laserDataOutput = new LaserData.LaserDataOutput[numberOfLaserCamData]; var targetDepthRT = laserCam.targetTexture; @@ -324,10 +325,9 @@ private void LaserCameraWorker() { laserCam.Render(); var readbackRequest = AsyncGPUReadback.Request(laserCam.targetTexture, 0, GraphicsFormat.R8G8B8A8_UNorm, OnCompleteAsyncReadback); - lock (_asyncWorkList) - { - _asyncWorkList.Add(new AsyncLaserWork(dataIndex, readbackRequest)); - } + + if (_asyncWorkList.Length == numberOfLaserCamData) + _asyncWorkList[dataIndex] = new AsyncLaserWork(dataIndex, readbackRequest); } laserCam.enabled = false; @@ -345,7 +345,7 @@ protected void OnCompleteAsyncReadback(AsyncGPUReadbackRequest request) } else if (request.done) { - for (var i = 0; i < _asyncWorkList.Count; i++) + for (var i = 0; i < _asyncWorkList.Length; i++) { var asyncWork = _asyncWorkList[i]; if (asyncWork.request.Equals(request)) @@ -379,11 +379,6 @@ protected void OnCompleteAsyncReadback(AsyncGPUReadbackRequest request) } depthCamBuffer.Deallocate(); - - lock (_asyncWorkList) - { - _asyncWorkList.Remove(asyncWork); - } break; } } diff --git a/Assets/Scripts/Devices/Modules/Articulation.cs b/Assets/Scripts/Devices/Modules/Articulation.cs index 1333f6bf..acb5d01d 100644 --- a/Assets/Scripts/Devices/Modules/Articulation.cs +++ b/Assets/Scripts/Devices/Modules/Articulation.cs @@ -8,12 +8,10 @@ public class Articulation { - private ArticulationDriveType _driveType = ArticulationDriveType.Force; private ArticulationBody _jointBody = null; private ArticulationJointType _jointType = ArticulationJointType.FixedJoint; public ArticulationJointType Type => _jointType; - public GameObject gameObject => _jointBody.gameObject; public Articulation(in ArticulationBody jointBody) { @@ -38,11 +36,6 @@ public void Reset() } } - public void SetDriveType(in ArticulationDriveType type) - { - this._driveType = type; - } - public bool IsRevoluteType() { return (Type == ArticulationJointType.RevoluteJoint || Type == ArticulationJointType.SphericalJoint) ? true : false; @@ -97,9 +90,46 @@ public float GetEffort() return F; } + /// angular velocity in degrees per second OR target position + public void Drive(in float target, ArticulationDriveType driveType = ArticulationDriveType.Velocity) + { + if (_jointBody == null) + { + Debug.LogWarning("ArticulationBody is empty, please set target body first"); + return; + } + + if (target == float.NaN) + { + Debug.LogWarning("Invalid Value: target is NaN"); + return; + } + + // Arccording to document(https://docs.unity3d.com/2020.3/Documentation/ScriptReference/ArticulationDrive.html) + // F = stiffness * (currentPosition - target) - damping * (currentVelocity - targetVelocity). + var drive = GetDrive(); + + drive.driveType = driveType; + + switch (driveType) + { + case ArticulationDriveType.Target: + drive.target = target; + break; + case ArticulationDriveType.Velocity: + drive.targetVelocity = target; + break; + default: + Debug.LogWarning("ArticulationDriveType should be Target/Velocity"); + return; + } + + SetDrive(drive); + } + /// angular velocity in degrees per second. /// target position - public void Drive(in float targetVelocity, in float target = 0) + public void Drive(in float targetVelocity, in float targetPosition) { if (_jointBody == null) { @@ -107,18 +137,53 @@ public void Drive(in float targetVelocity, in float target = 0) return; } + if (targetVelocity == float.NaN && targetPosition == float.NaN) + { + Debug.LogWarning("Invalid Value: targetVelocity or targetPosition is NaN"); + return; + } + // Arccording to document(https://docs.unity3d.com/2020.3/Documentation/ScriptReference/ArticulationDrive.html) // F = stiffness * (currentPosition - target) - damping * (currentVelocity - targetVelocity). var drive = GetDrive(); - drive.driveType = _driveType; - - if (_driveType == ArticulationDriveType.Force) + if (!float.IsNaN(targetVelocity) && !float.IsNaN(targetPosition)) { - drive.target = target; + drive.driveType = ArticulationDriveType.Force; + // Debug.LogWarningFormat("targetVelocity={0} or targetPosition={1} Type={2}", targetVelocity, targetPosition, drive.driveType); } + else if (float.IsNaN(targetVelocity) && !float.IsNaN(targetPosition)) + { + drive.driveType = ArticulationDriveType.Target; + } + else if (!float.IsNaN(targetVelocity) && float.IsNaN(targetPosition)) + { + drive.driveType = ArticulationDriveType.Velocity; + } + else + { + Debug.LogError("Invalid targetVelocity and targetPosition: Both NaN"); + return; + } + + // Debug.LogWarningFormat("targetVelocity={0} targetPosition={1} Type={2}", targetVelocity, targetPosition, drive.driveType); - drive.targetVelocity = targetVelocity; + switch (drive.driveType) + { + case ArticulationDriveType.Force: + drive.target = targetPosition; + drive.targetVelocity = targetVelocity; + break; + case ArticulationDriveType.Target: + drive.target = targetPosition; + break; + case ArticulationDriveType.Velocity: + drive.targetVelocity = targetVelocity; + break; + default: + Debug.LogWarning("ArticulationDriveType should be Target, Velocity or Force"); + return; + } SetDrive(drive); } diff --git a/Assets/Scripts/Devices/Modules/Base/DeviceHelper.cs b/Assets/Scripts/Devices/Modules/Base/DeviceHelper.cs index 485aedd2..629bb403 100644 --- a/Assets/Scripts/Devices/Modules/Base/DeviceHelper.cs +++ b/Assets/Scripts/Devices/Modules/Base/DeviceHelper.cs @@ -143,7 +143,7 @@ public static Vector3 Position(in Vector3 position) public static Quaternion Rotation(in Quaternion rotation) { - return new Quaternion(-rotation.z, -rotation.x, rotation.y, -rotation.w); + return new Quaternion(-rotation.z, rotation.x, -rotation.y, rotation.w); } public static Vector3 Reverse(in Vector3 value) diff --git a/Assets/Scripts/Devices/Modules/Motor.cs b/Assets/Scripts/Devices/Modules/Motor.cs index ac2bced6..3b997bdf 100644 --- a/Assets/Scripts/Devices/Modules/Motor.cs +++ b/Assets/Scripts/Devices/Modules/Motor.cs @@ -5,7 +5,6 @@ */ using UnityEngine; -using UnityEngine.Assertions.Comparers; public class Motor : Articulation { @@ -122,12 +121,6 @@ public float Compensate() public Motor(in GameObject gameObject) : base(gameObject) { - if (!IsRevoluteType()) - { - Debug.LogWarningFormat("joint type({0}) is not 'revolute'!!", Type); - } - - SetDriveType(ArticulationDriveType.Velocity); } public void SetPID(in float pFactor, in float iFactor, in float dFactor) @@ -173,6 +166,12 @@ public void SetVelocityTarget(in float targetAngularVelocity) public void Update(in float duration) { + if (!IsRevoluteType()) + { + // Debug.LogWarningFormat("joint type({0}) is not 'revolute'!!", Type); + return; + } + _currentMotorVelocity = GetMotorVelocity(duration); // Debug.LogFormat("joint vel({0}) accel({1}) force({2}) friction({3}) pos({4})", // Body.jointVelocity[0], Body.jointAcceleration[0], Body.jointForce[0], Body.jointFriction, Body.jointPosition[0]); @@ -208,7 +207,7 @@ public void Update(in float duration) public void Stop() { SetJointVelocity(0); - Drive(0, 0); + Drive(0); _pidControl.Reset(); _rapidControl.SetDirectionSwitched(false); diff --git a/Assets/Scripts/Main.cs b/Assets/Scripts/Main.cs index bcc07143..bb6df317 100644 --- a/Assets/Scripts/Main.cs +++ b/Assets/Scripts/Main.cs @@ -11,7 +11,6 @@ using UnityEngine.Rendering; using UnityEngine.SceneManagement; using UnityEngine.UI; -using System.Runtime.InteropServices; [DefaultExecutionOrder(30)] public class Main : MonoBehaviour diff --git a/Assets/Scripts/Tools/SDF/Helper/Base.cs b/Assets/Scripts/Tools/SDF/Helper/Base.cs index 7bda681e..75aa8522 100644 --- a/Assets/Scripts/Tools/SDF/Helper/Base.cs +++ b/Assets/Scripts/Tools/SDF/Helper/Base.cs @@ -10,13 +10,13 @@ namespace SDF { namespace Helper { - public class Base: UE.MonoBehaviour + public class Base : UE.MonoBehaviour { private PoseControl poseControl = null; private bool isFirstChild = false; - public bool IsFirstChild => isFirstChild; + public bool IsFirstChild => isFirstChild; // root model protected void Awake() { diff --git a/Assets/Scripts/Tools/SDF/Helper/Link.cs b/Assets/Scripts/Tools/SDF/Helper/Link.cs index 5365e87c..76f343c7 100644 --- a/Assets/Scripts/Tools/SDF/Helper/Link.cs +++ b/Assets/Scripts/Tools/SDF/Helper/Link.cs @@ -25,11 +25,34 @@ public class Link : Base public bool useGravity = false; private UE.ArticulationBody _artBody = null; + + private string jointName = string.Empty; + private string jointParentLinkName = string.Empty; + private string jointChildLinkName = string.Empty; + private UE.Vector3 jointAxis = UE.Vector3.zero; private UE.Vector3 jointAxis2 = UE.Vector3.zero; private List collisionContacts = new List(); + public string JointName + { + get => this.jointName; + set => this.jointName = value; + } + + public string JointParentLinkName + { + get => this.jointParentLinkName; + set => this.jointParentLinkName = value; + } + + public string JointChildLinkName + { + get => this.jointChildLinkName; + set => this.jointChildLinkName = value; + } + public UE.Vector3 JointAxis { get => this.jointAxis; diff --git a/Assets/Scripts/Tools/SDF/Implement/Implement.Collision.cs b/Assets/Scripts/Tools/SDF/Implement/Implement.Collision.cs index 1bebf47c..879052e0 100644 --- a/Assets/Scripts/Tools/SDF/Implement/Implement.Collision.cs +++ b/Assets/Scripts/Tools/SDF/Implement/Implement.Collision.cs @@ -23,10 +23,10 @@ public class Collision private static VHACD.Parameters VHACDParams = new VHACD.Parameters() { - m_resolution = 25000, + m_resolution = 30000, m_concavity = 0.001, - m_planeDownsampling = 6, - m_convexhullDownsampling = 6, + m_planeDownsampling = 2, + m_convexhullDownsampling = 2, m_alpha = 0.1, m_beta = 0.05, m_pca = 0, diff --git a/Assets/Scripts/Tools/SDF/Implement/Implement.Joint.cs b/Assets/Scripts/Tools/SDF/Implement/Implement.Joint.cs index 33878483..e116cca0 100644 --- a/Assets/Scripts/Tools/SDF/Implement/Implement.Joint.cs +++ b/Assets/Scripts/Tools/SDF/Implement/Implement.Joint.cs @@ -16,12 +16,24 @@ public static UE.Pose SetArticulationBodyRelationship(in SDF.Joint joint, UE.Tra { var modelTransformParent = linkParent.parent; var modelTransformChild = linkChild.parent; + var modelHelperChild = modelTransformChild.GetComponent(); var linkHelperParent = linkParent.GetComponent(); var linkHelperChild = linkChild.GetComponent(); + var linkParentArticulationBody = linkParent.GetComponent(); + if (linkParentArticulationBody == null) + { + UE.Debug.LogWarningFormat("LinkParent({0}) has no ArticulationBody -> create empty one", linkParent.name); + linkParentArticulationBody = Import.Loader.CreateArticulationBody(linkParent); + } + var anchorPose = new UE.Pose(); + + // link to link within same model + // model to model + // model is root model if (linkHelperChild.Model.Equals(linkHelperParent.Model) || modelTransformChild.Equals(modelTransformParent) || modelHelperChild.IsFirstChild) @@ -30,7 +42,8 @@ public static UE.Pose SetArticulationBodyRelationship(in SDF.Joint joint, UE.Tra // Set anchor pose anchorPose.position = linkChild.localPosition; - anchorPose.rotation = linkChild.localRotation; + anchorPose.rotation = UE.Quaternion.Inverse(linkChild.localRotation) * linkParentArticulationBody.anchorRotation; + // UE.Debug.LogWarningFormat("Linking1 ({0}) => ({1})", linkChild.name, linkParent.name); } else { @@ -38,7 +51,8 @@ public static UE.Pose SetArticulationBodyRelationship(in SDF.Joint joint, UE.Tra // Set anchor pose anchorPose.position = modelTransformChild.localPosition; - anchorPose.rotation = modelTransformChild.localRotation; + anchorPose.rotation = UE.Quaternion.Inverse(modelTransformChild.localRotation); + // UE.Debug.LogWarningFormat("Linking2 ({0}) => ({1})", modelTransformChild.name, linkParent.name); } var jointPosition = SDF2Unity.GetPosition(joint.Pose.Pos); @@ -51,18 +65,19 @@ public static UE.Pose SetArticulationBodyRelationship(in SDF.Joint joint, UE.Tra public static void SetArticulationBodyAnchor(in UE.ArticulationBody body, in UE.Pose parentAnchor) { - body.matchAnchors = true; body.anchorPosition = UE.Vector3.zero; - body.anchorRotation = UE.Quaternion.identity; - body.parentAnchorPosition = parentAnchor.position; - body.parentAnchorRotation = parentAnchor.rotation; + body.anchorRotation = parentAnchor.rotation; + + // TODO: Consider parentAnchor + // body.parentAnchorPosition = parentAnchor.position; // TODO: matchAnchors is set to true + // body.parentAnchorRotation = parentAnchor.rotation; // TODO: matchAnchors is set to true } public static void MakeRevolute(in UE.ArticulationBody body, in SDF.Axis axis) { body.jointType = UE.ArticulationJointType.SphericalJoint; - body.linearDamping = 0.05f; - body.angularDamping = 0.05f; + body.linearDamping = 0.05f; // TODO : value to find + body.angularDamping = 0.05f; // TODO : value to find body.jointFriction = (axis.dynamics != null) ? (float)axis.dynamics.friction : 0; @@ -123,6 +138,10 @@ public static void MakeRevolute(in UE.ArticulationBody body, in SDF.Axis axis) body.swingYLock = UE.ArticulationDofLock.LockedMotion; body.swingZLock = (axis.limit.Use()) ? UE.ArticulationDofLock.LimitedMotion : UE.ArticulationDofLock.FreeMotion; } + else + { + UE.Debug.LogWarning("MakeRevolute - Wrong axis, " + body.transform.parent.name + "::" + body.name + " = " + jointAxis); + } } public static void MakeRevolute2(in UE.ArticulationBody body, in SDF.Axis axis1, in SDF.Axis axis2) @@ -166,13 +185,17 @@ public static void MakeRevolute2(in UE.ArticulationBody body, in SDF.Axis axis1, body.zDrive = drive; body.swingZLock = (axis2.limit.Use()) ? UE.ArticulationDofLock.LimitedMotion : UE.ArticulationDofLock.FreeMotion; } + else + { + UE.Debug.LogWarning("MakeRevolute2 - Wrong axis, " + body.transform.parent.name + "::" + body.name + " = " + joint2Axis); + } } public static void MakeFixed(in UE.ArticulationBody body) { body.jointType = UE.ArticulationJointType.FixedJoint; - body.linearDamping = 0.05f; - body.angularDamping = 0.05f; + body.linearDamping = 0.00f; + body.angularDamping = 0.00f; body.jointFriction = 0; } @@ -190,7 +213,8 @@ public static void MakeBall(in UE.ArticulationBody body) public static void MakePrismatic(in UE.ArticulationBody body, in SDF.Axis axis, in SDF.Pose pose) { body.jointType = UE.ArticulationJointType.PrismaticJoint; - body.parentAnchorRotation *= SDF2Unity.GetRotation(pose.Rot); + body.anchorRotation *= SDF2Unity.GetRotation(pose.Rot); + // body.parentAnchorRotation *= SDF2Unity.GetRotation(pose.Rot); // TODO: matchAnchors is set to true body.linearDamping = 0.05f; body.angularDamping = 0.05f; @@ -264,12 +288,16 @@ public static void MakePrismatic(in UE.ArticulationBody body, in SDF.Axis axis, body.linearLockY = UE.ArticulationDofLock.LockedMotion; body.linearLockZ = (axis.limit.Use()) ? UE.ArticulationDofLock.LimitedMotion : UE.ArticulationDofLock.FreeMotion; } + else + { + UE.Debug.LogWarning("MakePrismatic - Wrong axis, " + body.transform.parent.name + "::" + body.name + " = " + jointAxis); + } } private static void ReverseArticulationBodyAxis(in UE.ArticulationBody body, in UE.Vector3 euler) { body.anchorRotation *= UE.Quaternion.Euler(euler * 180); - body.parentAnchorRotation *= UE.Quaternion.Euler(euler * 180); + // body.parentAnchorRotation *= UE.Quaternion.Euler(euler * 180); // TODO: matchAnchors is set to true } private static void SetRevoluteArticulationDriveLimit(ref UE.ArticulationDrive drive, in SDF.Axis.Limit limit) diff --git a/Assets/Scripts/Tools/SDF/Import/Import.Base.common.cs b/Assets/Scripts/Tools/SDF/Import/Import.Base.common.cs new file mode 100644 index 00000000..8d5ca237 --- /dev/null +++ b/Assets/Scripts/Tools/SDF/Import/Import.Base.common.cs @@ -0,0 +1,114 @@ +/* + * Copyright (c) 2021 LG Electronics Inc. + * + * SPDX-License-Identifier: MIT + */ + +using System.Reflection; +using System; + +namespace SDF +{ + namespace Import + { + public partial class Base + { + protected virtual Object ImportWorld(in World world) + { + PrintNotImported(MethodBase.GetCurrentMethod().Name, world.Name); + return null; + } + + protected virtual void ImportPlugin(in Plugin plugin, in Object parentObject) + { + PrintNotImported(MethodBase.GetCurrentMethod().Name, plugin.Name); + } + + protected virtual void ImportJoint(in Joint joint, in Object parentObject) + { + PrintNotImported(MethodBase.GetCurrentMethod().Name, joint.Name); + } + + protected virtual Object ImportSensor(in Sensor sensor, in Object parentObject) + { + PrintNotImported(MethodBase.GetCurrentMethod().Name, sensor.Name); + return null; + } + + protected virtual Object ImportVisual(in Visual visual, in Object parentObject) + { + PrintNotImported(MethodBase.GetCurrentMethod().Name, visual.Name); + return null; + } + + protected virtual void AfterImportVisual(in SDF.Visual visual, in System.Object targetObject) + { + PrintNotImported(MethodBase.GetCurrentMethod().Name, visual.Name); + } + + protected virtual Object ImportCollision(in Collision collision, in Object parentObject) + { + PrintNotImported(MethodBase.GetCurrentMethod().Name, collision.Name); + return null; + } + + protected virtual void AfterImportCollision(in Collision collision, in Object targetObject) + { + PrintNotImported(MethodBase.GetCurrentMethod().Name, collision.Name); + } + + protected virtual Object ImportLink(in Link link, in Object parentObject) + { + PrintNotImported(MethodBase.GetCurrentMethod().Name, link.Name); + return null; + } + + protected virtual void AfterImportLink(in Link link, in Object targetObject) + { + PrintNotImported(MethodBase.GetCurrentMethod().Name, link.Name); + } + + protected virtual Object ImportModel(in Model model, in Object parentObject) + { + PrintNotImported(MethodBase.GetCurrentMethod().Name, model.Name); + return null; + } + + protected virtual System.Object ImportActor(in Actor actor) + { + PrintNotImported(MethodBase.GetCurrentMethod().Name, actor.Name); + return null; + } + + protected virtual void AfterImportModel(in Model model, in Object targetObject) + { + PrintNotImported(MethodBase.GetCurrentMethod().Name, model.Name); + } + + protected virtual void ImportGeometry(in Geometry geometry, in Object parentObject) + { + PrintNotImported(MethodBase.GetCurrentMethod().Name, geometry.Name); + } + + protected virtual void ImportMaterial(in Material sdfMaterial, in Object parentObject) + { + PrintNotImported(MethodBase.GetCurrentMethod().Name, sdfMaterial.Name); + } + + protected virtual void ImportLight(in Light light) + { + PrintNotImported(MethodBase.GetCurrentMethod().Name, light.Name); + } + + private void PrintNotImported(in string methodName, in string name) + { + Console.Error.WriteLine("[{0}][{1}] Not Imported yet", methodName, name); + } + + private void PrintNotImported(in string methodName) + { + Console.Error.WriteLine("[{0}] Not Imported yet", methodName); + } + } + } +} diff --git a/Assets/Scripts/Tools/SDF/Import/Import.Base.common.cs.meta b/Assets/Scripts/Tools/SDF/Import/Import.Base.common.cs.meta new file mode 100644 index 00000000..af88d950 --- /dev/null +++ b/Assets/Scripts/Tools/SDF/Import/Import.Base.common.cs.meta @@ -0,0 +1,11 @@ +fileFormatVersion: 2 +guid: 7422ee9418771b814b46b392e52f5103 +MonoImporter: + externalObjects: {} + serializedVersion: 2 + defaultReferences: [] + executionOrder: 0 + icon: {instanceID: 0} + userData: + assetBundleName: + assetBundleVariant: diff --git a/Assets/Scripts/Tools/SDF/Import/Import.Base.cs b/Assets/Scripts/Tools/SDF/Import/Import.Base.cs index 13cd8ad6..a4ea7e97 100644 --- a/Assets/Scripts/Tools/SDF/Import/Import.Base.cs +++ b/Assets/Scripts/Tools/SDF/Import/Import.Base.cs @@ -5,7 +5,7 @@ */ using System.Collections.Generic; -using System.Reflection; +using System.Threading; using System; namespace SDF @@ -16,93 +16,6 @@ public partial class Base { private Dictionary jointObjectList = new Dictionary(); - protected virtual Object ImportWorld(in World world) - { - PrintNotImported(MethodBase.GetCurrentMethod().Name, world.Name); - return null; - } - - protected virtual void ImportPlugin(in Plugin plugin, in Object parentObject) - { - PrintNotImported(MethodBase.GetCurrentMethod().Name, plugin.Name); - } - - protected virtual void ImportJoint(in Joint joint, in Object parentObject) - { - PrintNotImported(MethodBase.GetCurrentMethod().Name, joint.Name); - } - - protected virtual Object ImportSensor(in Sensor sensor, in Object parentObject) - { - PrintNotImported(MethodBase.GetCurrentMethod().Name, sensor.Name); - return null; - } - - protected virtual Object ImportVisual(in Visual visual, in Object parentObject) - { - PrintNotImported(MethodBase.GetCurrentMethod().Name, visual.Name); - return null; - } - - protected virtual void AfterImportVisual(in SDF.Visual visual, in System.Object targetObject) - { - PrintNotImported(MethodBase.GetCurrentMethod().Name, visual.Name); - } - - protected virtual Object ImportCollision(in Collision collision, in Object parentObject) - { - PrintNotImported(MethodBase.GetCurrentMethod().Name, collision.Name); - return null; - } - - protected virtual void AfterImportCollision(in Collision collision, in Object targetObject) - { - PrintNotImported(MethodBase.GetCurrentMethod().Name, collision.Name); - } - - protected virtual Object ImportLink(in Link link, in Object parentObject) - { - PrintNotImported(MethodBase.GetCurrentMethod().Name, link.Name); - return null; - } - - protected virtual void AfterImportLink(in Link link, in Object targetObject) - { - PrintNotImported(MethodBase.GetCurrentMethod().Name, link.Name); - } - - protected virtual Object ImportModel(in Model model, in Object parentObject) - { - PrintNotImported(MethodBase.GetCurrentMethod().Name, model.Name); - return null; - } - - protected virtual System.Object ImportActor(in Actor actor) - { - PrintNotImported(MethodBase.GetCurrentMethod().Name, actor.Name); - return null; - } - - protected virtual void AfterImportModel(in Model model, in Object targetObject) - { - PrintNotImported(MethodBase.GetCurrentMethod().Name, model.Name); - } - - protected virtual void ImportGeometry(in Geometry geometry, in Object parentObject) - { - PrintNotImported(MethodBase.GetCurrentMethod().Name, geometry.Name); - } - - protected virtual void ImportMaterial(in Material sdfMaterial, in Object parentObject) - { - PrintNotImported(MethodBase.GetCurrentMethod().Name, sdfMaterial.Name); - } - - protected virtual void ImportLight(in Light light) - { - PrintNotImported(MethodBase.GetCurrentMethod().Name, light.Name); - } - private void ImportVisuals(IReadOnlyList items, in Object parentObject) { foreach (var item in items) @@ -192,6 +105,7 @@ protected void ImportModels(IReadOnlyList items, in Object parentObject = AfterImportModel(item, createdObject); ImportJoints(item.GetJoints(), createdObject); + ImportPlugins(item.GetPlugins(), createdObject); } } @@ -218,23 +132,29 @@ public IEnumerator StartImport(World world) { // Console.WriteLine("Import Models({0})/Links/Joints", world.GetModels().Count); jointObjectList.Clear(); + var worldObject = ImportWorld(world); - ImportModels(world.GetModels()); ImportActors(world.GetActors()); - ImportPlugins(world.GetPlugins(), worldObject); + yield return null; + + ImportModels(world.GetModels()); foreach (var jointObject in jointObjectList) { ImportJoint(jointObject.Key, jointObject.Value); } yield return null; + + ImportPlugins(world.GetPlugins(), worldObject); + yield return null; } public IEnumerator StartImport(Model model) { jointObjectList.Clear(); - var tempModels = new List(){model}; + var tempModels = new List() { model }; + ImportModels(tempModels); foreach (var jointObject in jointObjectList) @@ -243,16 +163,6 @@ public IEnumerator StartImport(Model model) } yield return null; } - - private void PrintNotImported(in string methodName, in string name) - { - Console.Error.WriteLine("[{0}][{1}] Not Imported yet", methodName, name); - } - - private void PrintNotImported(in string methodName) - { - Console.Error.WriteLine("[{0}] Not Imported yet", methodName); - } } } } diff --git a/Assets/Scripts/Tools/SDF/Import/Import.Joint.cs b/Assets/Scripts/Tools/SDF/Import/Import.Joint.cs index c84658ad..a10b88df 100644 --- a/Assets/Scripts/Tools/SDF/Import/Import.Joint.cs +++ b/Assets/Scripts/Tools/SDF/Import/Import.Joint.cs @@ -99,7 +99,8 @@ protected override void ImportJoint(in Joint joint, in System.Object parentObjec if (articulationBodyChild == null) { - Debug.LogWarning("Articulation Body is NULL, will create an articulation body for linking, parent: " + linkObjectParent.name + ", child: " + linkObjectChild.name); + Debug.LogWarningFormat("Link Child has NO Articulation Body, will create an articulation body for linking, parent({0}) child({1})", + linkObjectParent.name, linkObjectChild.name); articulationBodyChild = CreateArticulationBody(linkObjectChild.gameObject); } @@ -151,8 +152,14 @@ protected override void ImportJoint(in Joint joint, in System.Object parentObjec { var axisSpringReference = 0f; var axis2SpringReference = 0f; + + linkHelper.JointName = joint.Name; + linkHelper.JointParentLinkName = joint.ParentLinkName; + linkHelper.JointChildLinkName = joint.ChildLinkName; + if (joint.Axis != null) { + // articulationBodyChild linkHelper.JointAxis = SDF2Unity.GetAxis(joint.Axis.xyz); if (joint.Axis.dynamics != null) { @@ -168,7 +175,7 @@ protected override void ImportJoint(in Joint joint, in System.Object parentObjec linkHelper.JointAxis2 = SDF2Unity.GetAxis(joint.Axis2.xyz); if (joint.Axis2.dynamics != null) { - axis2SpringReference = SDF2Unity.CurveOrientation((float)joint.Axis2.dynamics.spring_reference); + axis2SpringReference = SDF2Unity.CurveOrientation((float)joint.Axis2.dynamics.spring_reference); } } diff --git a/Assets/Scripts/Tools/SDF/Import/Import.Link.cs b/Assets/Scripts/Tools/SDF/Import/Import.Link.cs index ae891620..89c94bb2 100644 --- a/Assets/Scripts/Tools/SDF/Import/Import.Link.cs +++ b/Assets/Scripts/Tools/SDF/Import/Import.Link.cs @@ -80,6 +80,11 @@ protected override void AfterImportLink(in SDF.Link link, in System.Object targe } } + public static UE.ArticulationBody CreateArticulationBody(in UE.Transform linkObjectTransform, in Inertial inertial = null) + { + return CreateArticulationBody(linkObjectTransform.gameObject, inertial); + } + private static UE.ArticulationBody CreateArticulationBody(in UE.GameObject linkObject, in Inertial inertial = null) { if (linkObject == null) @@ -89,8 +94,21 @@ private static UE.ArticulationBody CreateArticulationBody(in UE.GameObject linkO } var linkHelper = linkObject.GetComponent(); + var colliders = linkObject.GetComponentsInChildren(); + + // handling mesh collider + foreach (var collider in colliders) + { + var meshCollider = collider as UE.MeshCollider; + + if (meshCollider != null) + { + meshCollider.convex = true; + } + } var articulationBody = linkObject.AddComponent(); + articulationBody.velocity = UE.Vector3.zero; articulationBody.angularVelocity = UE.Vector3.zero; articulationBody.useGravity = (linkHelper == null) ? false : linkHelper.useGravity; @@ -106,6 +124,10 @@ private static UE.ArticulationBody CreateArticulationBody(in UE.GameObject linkO articulationBody.jointType = UE.ArticulationJointType.FixedJoint; articulationBody.Sleep(); + articulationBody.matchAnchors = true; + articulationBody.anchorPosition = UE.Vector3.zero; + articulationBody.anchorRotation = UE.Quaternion.identity; + if (inertial == null) { articulationBody.ResetCenterOfMass(); @@ -120,7 +142,6 @@ private static UE.ArticulationBody CreateArticulationBody(in UE.GameObject linkO // Debug.Log(linkObject.name + " => Center Of Mass: " + articulationBody.centerOfMass.ToString("F6") + ", intertia: " + articulationBody.inertiaTensor.ToString("F6") + ", " + articulationBody.inertiaTensorRotation.ToString("F6")); } - var colliders = linkObject.GetComponentsInChildren(); if (colliders.Length > 0) { if (inertial?.inertia != null) @@ -134,17 +155,6 @@ private static UE.ArticulationBody CreateArticulationBody(in UE.GameObject linkO articulationBody.ResetInertiaTensor(); articulationBody.automaticInertiaTensor = true; } - - // handling mesh collider - foreach (var collider in colliders) - { - var meshCollider = collider as UE.MeshCollider; - - if (meshCollider != null) - { - meshCollider.convex = true; - } - } } else { diff --git a/Assets/Scripts/Tools/SDF/Import/Import.Model.cs b/Assets/Scripts/Tools/SDF/Import/Import.Model.cs index 0c08f899..566cd74a 100644 --- a/Assets/Scripts/Tools/SDF/Import/Import.Model.cs +++ b/Assets/Scripts/Tools/SDF/Import/Import.Model.cs @@ -31,6 +31,7 @@ private void CreateRootArticulationBody(in UE.GameObject targetObject) articulationBody.linearDamping = 0; articulationBody.angularDamping = 0; #if true + // TODO: consider to set intertia value manually articulationBody.automaticCenterOfMass = true; articulationBody.automaticInertiaTensor = true; #else diff --git a/Assets/Scripts/Tools/SDF/Import/Import.World.cs b/Assets/Scripts/Tools/SDF/Import/Import.World.cs index e473a354..74253fe1 100644 --- a/Assets/Scripts/Tools/SDF/Import/Import.World.cs +++ b/Assets/Scripts/Tools/SDF/Import/Import.World.cs @@ -4,6 +4,7 @@ * SPDX-License-Identifier: MIT */ + namespace SDF { namespace Import diff --git a/Assets/Scripts/Tools/SDF/Parser/Pose.cs b/Assets/Scripts/Tools/SDF/Parser/Pose.cs index f8f6ffb9..1885d8dd 100644 --- a/Assets/Scripts/Tools/SDF/Parser/Pose.cs +++ b/Assets/Scripts/Tools/SDF/Parser/Pose.cs @@ -15,8 +15,8 @@ public class Vector2 private static string regex_num_pattern = "[^.0-9Ee+-]"; protected static readonly Regex regex_num = new Regex(regex_num_pattern); - private T _x; - private T _y; + protected T _x; + protected T _y; public Vector2() : this(default(T), default(T)) @@ -75,6 +75,11 @@ public void FromString(in string value) Set(tmp[0], tmp[1]); } } + + public override string ToString() + { + return $"Vector2({_x}, {_y})"; + } } public class Vector3 : Vector2 @@ -131,6 +136,11 @@ public void Set(string x, string y, string z) Set(tmp[0], tmp[1], tmp[2]); } } + + public override string ToString() + { + return $"Vector3({_x}, {_y}, {_z})"; + } } public class Quaternion @@ -254,6 +264,11 @@ public void FromString(in string value) } } + public override string ToString() + { + return $"Quaternion({_w}, {_x}, {_y}, {_z})"; + } + private void ConvertEuler2Quaternion() { var roll = Convert.ToDouble(euler.X); @@ -422,5 +437,10 @@ public void FromString(in string value) _rot.Set(tmp[3], tmp[4], tmp[5]); } } + + public override string ToString() + { + return $"Pose({_pos.ToString()}, {_rot.ToString()})"; + } } } \ No newline at end of file diff --git a/Assets/Scripts/Tools/SDF/Parser/Root.cs b/Assets/Scripts/Tools/SDF/Parser/Root.cs index e9fe54d1..3180e80d 100644 --- a/Assets/Scripts/Tools/SDF/Parser/Root.cs +++ b/Assets/Scripts/Tools/SDF/Parser/Root.cs @@ -18,7 +18,7 @@ public class Root // {Model Name, (Model Config Name, Model Path, Model File)} public Dictionary> resourceModelTable = new Dictionary>(); - private readonly string[] sdfVersions = {"1.9", "1.8", "1.7", "1.6", "1.5", "1.4", "1.3", "1.2", string.Empty}; + private readonly string[] sdfVersions = { "1.9", "1.8", "1.7", "1.6", "1.5", "1.4", "1.3", "1.2", string.Empty }; private XmlDocument doc = new XmlDocument(); @@ -114,7 +114,7 @@ public bool DoParse(out Model model, in string modelFullPath, in string modelFil model = new Model(modelNode); modelFound = true; - var infoMessage = model.Name + " Model(" + modelFileName + ") is loaded."; + var infoMessage = model.Name + " Model(" + modelFileName + ") is loaded."; // logger.SetShowOnDisplayOnce(); logger.Write(infoMessage); } @@ -186,7 +186,7 @@ public void UpdateResourceModelTable() } catch (XmlException e) { - Console.Write("Failed to Load model file(" + modelConfig + ") - " + e.Message); + Console.Write("Failed to Load model file(" + modelConfig + ") - " + e.Message); continue; } diff --git a/Assets/Scripts/Tools/SDF/Util/SDF2Unity.cs b/Assets/Scripts/Tools/SDF/Util/SDF2Unity.cs index c47415dd..b4c44b48 100644 --- a/Assets/Scripts/Tools/SDF/Util/SDF2Unity.cs +++ b/Assets/Scripts/Tools/SDF/Util/SDF2Unity.cs @@ -18,6 +18,9 @@ public static Vector3 GetScalar(in double x, in double y, in double z) return new Vector3(Mathf.Abs((float)y), Mathf.Abs((float)z), Mathf.Abs((float)x)); } + /// right handed system x + /// right handed system y + /// right handed system z public static Vector3 GetPosition(in double x, in double y, in double z) { return new Vector3(-(float)y, (float)z, (float)x); @@ -53,6 +56,10 @@ public static Quaternion GetRotation(in SDF.Quaternion value) return (value == null) ? Quaternion.identity : GetRotation(value.W, value.X, value.Y, value.Z); } + /// right handed system w + /// right handed system x + /// right handed system y + /// right handed system z public static Quaternion GetRotation(in double w, in double x, in double y, in double z) { return new Quaternion((float)y, (float)-z, (float)-x, (float)w); diff --git a/Assets/Scripts/UI/AddModel.cs b/Assets/Scripts/UI/AddModel.cs index 397ab9fe..61a86aea 100644 --- a/Assets/Scripts/UI/AddModel.cs +++ b/Assets/Scripts/UI/AddModel.cs @@ -78,7 +78,7 @@ public void SetAddingModelForDeploy(in Transform targetTransform) // Debug.Log(totalBound.extents + " " + totalBound.center + " " + totalBound.size); // Debug.Log(totalBound.extents.y + " " + totalBound.center.y + " " + totalBound.size.y); - articulationBodyDeployOffset.y = totalBound.extents.y + DeployOffset; + articulationBodyDeployOffset.y = totalBound.min.y + DeployOffset; _modelHelper = targetObject.GetComponent(); } diff --git a/Assets/VSCode.meta b/Assets/VSCode.meta new file mode 100644 index 00000000..5901557d --- /dev/null +++ b/Assets/VSCode.meta @@ -0,0 +1,8 @@ +fileFormatVersion: 2 +guid: beedca8c30bfae42c8e3c0f8f6837b4e +folderAsset: yes +DefaultImporter: + externalObjects: {} + userData: + assetBundleName: + assetBundleVariant: diff --git a/Assets/VSCode/HOWTO.pdf b/Assets/VSCode/HOWTO.pdf new file mode 100644 index 00000000..a94dd3f2 Binary files /dev/null and b/Assets/VSCode/HOWTO.pdf differ diff --git a/Assets/VSCode/HOWTO.pdf.meta b/Assets/VSCode/HOWTO.pdf.meta new file mode 100644 index 00000000..53b138f8 --- /dev/null +++ b/Assets/VSCode/HOWTO.pdf.meta @@ -0,0 +1,8 @@ +fileFormatVersion: 2 +guid: 9519be3d5789b4c5ca14e07b375d6884 +timeCreated: 1444651605 +licenseType: Store +DefaultImporter: + userData: + assetBundleName: + assetBundleVariant: diff --git a/Assets/VSCode/LICENSE b/Assets/VSCode/LICENSE new file mode 100644 index 00000000..13b5259a --- /dev/null +++ b/Assets/VSCode/LICENSE @@ -0,0 +1,22 @@ +The MIT License (MIT) + +Copyright (c) 2016 dotBunny Inc. + +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. + diff --git a/Assets/VSCode/LICENSE.meta b/Assets/VSCode/LICENSE.meta new file mode 100644 index 00000000..a24433e2 --- /dev/null +++ b/Assets/VSCode/LICENSE.meta @@ -0,0 +1,8 @@ +fileFormatVersion: 2 +guid: edc517f07ba5e4cf9984f8753de7388f +timeCreated: 1444651605 +licenseType: Store +DefaultImporter: + userData: + assetBundleName: + assetBundleVariant: diff --git a/Assets/VSCode/Plugins.meta b/Assets/VSCode/Plugins.meta new file mode 100644 index 00000000..71559cf3 --- /dev/null +++ b/Assets/VSCode/Plugins.meta @@ -0,0 +1,9 @@ +fileFormatVersion: 2 +guid: 0d0aa2ea87e4246f3b7fd58b757ff82c +folderAsset: yes +timeCreated: 1444652904 +licenseType: Store +DefaultImporter: + userData: + assetBundleName: + assetBundleVariant: diff --git a/Assets/VSCode/Plugins/Editor.meta b/Assets/VSCode/Plugins/Editor.meta new file mode 100644 index 00000000..b44f6815 --- /dev/null +++ b/Assets/VSCode/Plugins/Editor.meta @@ -0,0 +1,9 @@ +fileFormatVersion: 2 +guid: 47b6573edc17b4b19b6f06515ff01748 +folderAsset: yes +timeCreated: 1444652910 +licenseType: Store +DefaultImporter: + userData: + assetBundleName: + assetBundleVariant: diff --git a/Assets/VSCode/Plugins/Editor/VSCode.cs b/Assets/VSCode/Plugins/Editor/VSCode.cs new file mode 100644 index 00000000..c0c2604e --- /dev/null +++ b/Assets/VSCode/Plugins/Editor/VSCode.cs @@ -0,0 +1,1445 @@ +/* + * Unity VSCode Support + * + * Seamless support for Microsoft Visual Studio Code in Unity + * + * Version: + * 2.9 + * + * Authors: + * Matthew Davey + */ +namespace dotBunny.Unity +{ + using System; + using System.IO; + using System.Text.RegularExpressions; + using UnityEditor; + using UnityEngine; + + [InitializeOnLoad] + public static class VSCode + { + /// + /// Current Version Number + /// + public const float Version = 2.9f; + + /// + /// Current Version Code + /// + public const string VersionCode = "-RELEASE"; + + /// + /// Additional File Extensions + /// + public const string FileExtensions = ".ts, .bjs, .javascript, .json, .html, .shader, .template"; + + /// + /// Download URL for Unity Debbuger + /// + public const string UnityDebuggerURL = "https://unity.gallery.vsassets.io/_apis/public/gallery/publisher/unity/extension/unity-debug/latest/assetbyname/Microsoft.VisualStudio.Services.VSIXPackage"; + + // Used to keep Unity from crashing when the editor is quit + static bool alreadyFixedPreferences; + + #region Properties + + /// + /// Path to VSCode executable + public static string CodePath + { + get + { + string current = EditorPrefs.GetString("VSCode_CodePath", ""); + if (current == "" || !VSCodeExists(current)) + { + //Value not set, set to "" or current path is invalid, try to autodetect it + //If autodetect fails, a error will be printed and the default value set + EditorPrefs.SetString("VSCode_CodePath", AutodetectCodePath()); + //If its not installed or the install folder isn't a "normal" one, + //AutodetectCodePath will print a error message to the Unity Console + } + return EditorPrefs.GetString("VSCode_CodePath", current); + } + set + { + EditorPrefs.SetString("VSCode_CodePath", value); + } + } + + /// + /// Get Program Files Path + /// + /// The platforms "Program Files" path. + static string ProgramFilesx86() + { + return Environment.GetEnvironmentVariable("ProgramFiles(x86)"); + } + + /// + /// Get Program Files Path + /// + /// The platforms "Program Files" path. + static string ProgramFiles() + { + return Environment.GetEnvironmentVariable("ProgramFiles"); + } + + + /// + /// Should debug information be displayed in the Unity terminal? + /// + public static bool Debug + { + get + { + return EditorPrefs.GetBool("VSCode_Debug", false); + } + set + { + EditorPrefs.SetBool("VSCode_Debug", value); + } + } + + /// + /// Is the Visual Studio Code Integration Enabled? + /// + /// + /// We do not want to automatically turn it on, for in larger projects not everyone is using VSCode + /// + public static bool Enabled + { + get + { + return EditorPrefs.GetBool("VSCode_Enabled", false); + } + set + { + // When turning the plugin on, we should remove all the previous project files + if (!Enabled && value) + { + ClearProjectFiles(); + } + EditorPrefs.SetBool("VSCode_Enabled", value); + } + } + public static bool UseUnityDebugger + { + get + { + return EditorPrefs.GetBool("VSCode_UseUnityDebugger", false); + } + set + { + if (value != UseUnityDebugger) + { + + // Set value + EditorPrefs.SetBool("VSCode_UseUnityDebugger", value); + + // Do not write the launch JSON file because the debugger uses its own + if (value) + { + WriteLaunchFile = false; + } + + // Update launch file + UpdateLaunchFile(); + } + } + } + + /// + /// When opening a project in Unity, should it automatically open in VS Code. + /// + public static bool AutoOpenEnabled + { + get + { + return EditorPrefs.GetBool("VSCode_AutoOpenEnabled", false); + } + set + { + EditorPrefs.SetBool("VSCode_AutoOpenEnabled", value); + } + } + + /// + /// Should the launch.json file be written? + /// + /// + /// Useful to disable if someone has their own custom one rigged up + /// + public static bool WriteLaunchFile + { + get + { + return EditorPrefs.GetBool("VSCode_WriteLaunchFile", true); + } + set + { + EditorPrefs.SetBool("VSCode_WriteLaunchFile", value); + } + } + + /// + /// Should the plugin automatically update itself. + /// + static bool AutomaticUpdates + { + get + { + return EditorPrefs.GetBool("VSCode_AutomaticUpdates", false); + } + set + { + EditorPrefs.SetBool("VSCode_AutomaticUpdates", value); + } + } + + static float GitHubVersion + { + get + { + return EditorPrefs.GetFloat("VSCode_GitHubVersion", Version); + } + set + { + EditorPrefs.SetFloat("VSCode_GitHubVersion", value); + } + } + + /// + /// When was the last time that the plugin was updated? + /// + static DateTime LastUpdate + { + get + { + // Feature creation date. + DateTime lastTime = new DateTime(2015, 10, 8); + + if (EditorPrefs.HasKey("VSCode_LastUpdate")) + { + DateTime.TryParse(EditorPrefs.GetString("VSCode_LastUpdate"), out lastTime); + } + return lastTime; + } + set + { + EditorPrefs.SetString("VSCode_LastUpdate", value.ToString()); + } + } + + /// + /// Quick reference to the VSCode launch settings file + /// + static string LaunchPath + { + get + { + return SettingsFolder + System.IO.Path.DirectorySeparatorChar + "launch.json"; + } + } + + /// + /// Should the parent of the unity project be used as the workspace directory. + /// + /// + /// Usefull if you have your unity project as a sub-directory. + /// + static bool UseParentWorkspace + { + get + { + return EditorPrefs.GetBool("VSCode_UseParentWorkspace", false); + } + set + { + EditorPrefs.SetBool("VSCode_UseParentWorkspace", value); + } + } + + /// + /// The full path to the Unity project. + /// + static string UnityProjectPath + { + get + { + return System.IO.Path.GetDirectoryName(UnityEngine.Application.dataPath); + } + } + + /// + /// The full path to the workspace. + /// + static string WorkspacePath + { + get + { + return UseParentWorkspace ? + Directory.GetParent(UnityProjectPath).FullName : + UnityProjectPath; + } + } + + /// + /// Should the script editor be reverted when quiting Unity. + /// + /// + /// Useful for environments where you do not use VSCode for everything. + /// + static bool RevertExternalScriptEditorOnExit + { + get + { + return EditorPrefs.GetBool("VSCode_RevertScriptEditorOnExit", true); + } + set + { + EditorPrefs.SetBool("VSCode_RevertScriptEditorOnExit", value); + } + } + + /// + /// Quick reference to the VSCode settings folder + /// + static string SettingsFolder + { + get + { + return WorkspacePath + System.IO.Path.DirectorySeparatorChar + ".vscode"; + } + } + + static string SettingsPath + { + + get + { + return SettingsFolder + System.IO.Path.DirectorySeparatorChar + "settings.json"; + } + } + + static int UpdateTime + { + get + { + return EditorPrefs.GetInt("VSCode_UpdateTime", 7); + } + set + { + EditorPrefs.SetInt("VSCode_UpdateTime", value); + } + } + + #endregion + + /// + /// Integration Constructor + /// + static VSCode() + { + if (Enabled) + { + UpdateUnityPreferences(true); + UpdateLaunchFile(); + + // Add Update Check + DateTime targetDate = LastUpdate.AddDays(UpdateTime); + if (DateTime.Now >= targetDate && AutomaticUpdates) + { + CheckForUpdate(); + } + + // Open VS Code automatically when project is loaded + if (AutoOpenEnabled) + { + CheckForAutoOpen(); + } + + } + + // Event for when script is reloaded + System.AppDomain.CurrentDomain.DomainUnload += System_AppDomain_CurrentDomain_DomainUnload; + } + static void System_AppDomain_CurrentDomain_DomainUnload(object sender, System.EventArgs e) + { + if (Enabled && RevertExternalScriptEditorOnExit) + { + UpdateUnityPreferences(false); + } + } + + + #region Public Members + + /// + /// Force Unity To Write Project File + /// + /// + /// Reflection! + /// + public static void SyncSolution() + { + System.Type T = System.Type.GetType("UnityEditor.SyncVS,UnityEditor"); + System.Reflection.MethodInfo SyncSolution = T.GetMethod("SyncSolution", System.Reflection.BindingFlags.Public | System.Reflection.BindingFlags.Static); + SyncSolution.Invoke(null, null); + + } + + /// + /// Update the solution files so that they work with VS Code + /// + public static void UpdateSolution() + { + // No need to process if we are not enabled + if (!VSCode.Enabled) + { + return; + } + + if (VSCode.Debug) + { + UnityEngine.Debug.Log("[VSCode] Updating Solution & Project Files"); + } + + var currentDirectory = Directory.GetCurrentDirectory(); + var solutionFiles = Directory.GetFiles(currentDirectory, "*.sln"); + var projectFiles = Directory.GetFiles(currentDirectory, "*.csproj"); + + foreach (var filePath in solutionFiles) + { + string content = File.ReadAllText(filePath); + content = ScrubSolutionContent(content); + + File.WriteAllText(filePath, content); + + ScrubFile(filePath); + } + + foreach (var filePath in projectFiles) + { + string content = File.ReadAllText(filePath); + content = ScrubProjectContent(content); + + File.WriteAllText(filePath, content); + + ScrubFile(filePath); + } + + } + + #endregion + + #region Private Members + + /// + /// Try to find automatically the installation of VSCode + /// + static string AutodetectCodePath() + { + string[] possiblePaths = +#if UNITY_EDITOR_OSX + { + "/Applications/Visual Studio Code.app", + "/Applications/Visual Studio Code - Insiders.app" + }; +#elif UNITY_EDITOR_WIN + { + ProgramFiles() + Path.DirectorySeparatorChar + "Microsoft VS Code" + + Path.DirectorySeparatorChar + "bin" + Path.DirectorySeparatorChar + "code.cmd", + ProgramFiles() + Path.DirectorySeparatorChar + "Microsoft VS Code Insiders" + + Path.DirectorySeparatorChar + "bin" + Path.DirectorySeparatorChar + "code-insiders.cmd", + ProgramFilesx86() + Path.DirectorySeparatorChar + "Microsoft VS Code" + + Path.DirectorySeparatorChar + "bin" + Path.DirectorySeparatorChar + "code.cmd", + ProgramFilesx86() + Path.DirectorySeparatorChar + "Microsoft VS Code Insiders" + + Path.DirectorySeparatorChar + "bin" + Path.DirectorySeparatorChar + "code-insiders.cmd" + }; +#else + { + "/usr/bin/code", + "/usr/bin/code-insiders", + "/bin/code", + "/usr/local/bin/code", + "/var/lib/flatpak/exports/bin/com.visualstudio.code", + "/snap/bin/code", + "/snap/bin/code-insiders" + }; +#endif + for (int i = 0; i < possiblePaths.Length; i++) + { + if (VSCodeExists(possiblePaths[i])) + { + return possiblePaths[i]; + } + } + PrintNotFound(possiblePaths[0]); + return possiblePaths[0]; //returns the default one, printing a warning message 'executable not found' + } + + /// + /// Call VSCode with arguments + /// + static void CallVSCode(string args) + { + System.Diagnostics.Process proc = new System.Diagnostics.Process(); + if (!VSCodeExists(CodePath)) + { + PrintNotFound(CodePath); + return; + } + +#if UNITY_EDITOR_OSX + proc.StartInfo.FileName = "open"; + + // Check the path to see if there is "Insiders" + if (CodePath.Contains("Insiders")) + { + proc.StartInfo.Arguments = " -n -b \"com.microsoft.VSCodeInsiders\" --args " + args.Replace(@"\", @"\\"); + } + else + { + proc.StartInfo.Arguments = " -n -b \"com.microsoft.VSCode\" --args " + args.Replace(@"\", @"\\"); + } + + proc.StartInfo.UseShellExecute = false; +#elif UNITY_EDITOR_WIN + proc.StartInfo.FileName = CodePath; + proc.StartInfo.Arguments = args; + proc.StartInfo.UseShellExecute = false; +#else + proc.StartInfo.FileName = CodePath; + proc.StartInfo.Arguments = args.Replace(@"\", @"\\"); + proc.StartInfo.UseShellExecute = false; +#endif + proc.StartInfo.WindowStyle = System.Diagnostics.ProcessWindowStyle.Hidden; + proc.StartInfo.CreateNoWindow = true; + proc.StartInfo.RedirectStandardOutput = true; + proc.Start(); + } + + /// + /// Check for Updates with GitHub + /// + static void CheckForUpdate() + { + var fileContent = string.Empty; + + EditorUtility.DisplayProgressBar("VSCode", "Checking for updates ...", 0.5f); + + // Because were not a runtime framework, lets just use the simplest way of doing this + try + { + using (var webClient = new System.Net.WebClient()) + { + fileContent = webClient.DownloadString("https://raw.githubusercontent.com/dotBunny/VSCode/master/Plugins/Editor/VSCode.cs"); + } + } + catch (Exception e) + { + if (Debug) + { + UnityEngine.Debug.Log("[VSCode] " + e.Message); + + } + + // Don't go any further if there is an error + return; + } + finally + { + EditorUtility.ClearProgressBar(); + } + + // Set the last update time + LastUpdate = DateTime.Now; + + // Fix for oddity in downlo + if (fileContent.Substring(0, 2) != "/*") + { + int startPosition = fileContent.IndexOf("/*", StringComparison.CurrentCultureIgnoreCase); + + // Jump over junk characters + fileContent = fileContent.Substring(startPosition); + } + + string[] fileExploded = fileContent.Split('\n'); + if (fileExploded.Length > 7) + { + float github = Version; + if (float.TryParse(fileExploded[6].Replace("*", "").Trim(), out github)) + { + GitHubVersion = github; + } + + + if (github > Version) + { + var GUIDs = AssetDatabase.FindAssets("t:Script VSCode"); + var path = Application.dataPath.Substring(0, Application.dataPath.Length - "/Assets".Length) + System.IO.Path.DirectorySeparatorChar + + AssetDatabase.GUIDToAssetPath(GUIDs[0]).Replace('/', System.IO.Path.DirectorySeparatorChar); + + if (EditorUtility.DisplayDialog("VSCode Update", "A newer version of the VSCode plugin is available, would you like to update your version?", "Yes", "No")) + { + // Always make sure the file is writable + System.IO.FileInfo fileInfo = new System.IO.FileInfo(path); + fileInfo.IsReadOnly = false; + + // Write update file + File.WriteAllText(path, fileContent); + + // Force update on text file + AssetDatabase.ImportAsset(AssetDatabase.GUIDToAssetPath(GUIDs[0]), ImportAssetOptions.ForceUpdate); + } + + } + } + } + + /// + /// Checks whether it should auto-open VSCode + /// + /// + /// VSCode() gets called on Launch and Run, through IntializeOnLoad + /// https://docs.unity3d.com/ScriptReference/InitializeOnLoadAttribute.html + /// To make sure it only opens VSCode when Unity (re)launches (i.e. opens a project), + /// we compare the launch time, which we calculate using EditorApplication.timeSinceStartup. + /// + static void CheckForAutoOpen() + { + double timeInSeconds = (DateTime.UtcNow - new DateTime(1970, 1, 1)).TotalSeconds; + int unityLaunchTimeInSeconds = (int)(timeInSeconds - EditorApplication.timeSinceStartup); + int prevUnityLaunchTime = EditorPrefs.GetInt("VSCode_UnityLaunchTime", 0); + // If launch time has changed, then Unity was re-opened + if (unityLaunchTimeInSeconds > prevUnityLaunchTime) + { + // Launch VSCode + VSCode.MenuOpenProject(); + // Save new launch time + EditorPrefs.SetInt("VSCode_UnityLaunchTime", unityLaunchTimeInSeconds); + } + } + + /// + /// Clear out any existing project files and lingering stuff that might cause problems + /// + static void ClearProjectFiles() + { + var currentDirectory = Directory.GetCurrentDirectory(); + var solutionFiles = Directory.GetFiles(currentDirectory, "*.sln"); + var projectFiles = Directory.GetFiles(currentDirectory, "*.csproj"); + var unityProjectFiles = Directory.GetFiles(currentDirectory, "*.unityproj"); + + foreach (string solutionFile in solutionFiles) + { + File.Delete(solutionFile); + } + foreach (string projectFile in projectFiles) + { + File.Delete(projectFile); + } + foreach (string unityProjectFile in unityProjectFiles) + { + File.Delete(unityProjectFile); + } + + // Replace with our clean files (only in Unity 5) +#if !UNITY_4_0 && !UNITY_4_1 && !UNITY_4_2 && !UNITY_4_3 && !UNITY_4_5 && !UNITY_4_6 && !UNITY_4_7 + SyncSolution(); +#endif + } + + /// + /// Force Unity Preferences Window To Read From Settings + /// + static void FixUnityPreferences() + { + // I want that window, please and thank you + System.Type T = System.Type.GetType("UnityEditor.PreferencesWindow,UnityEditor"); + + if (EditorWindow.focusedWindow == null) + return; + + // Only run this when the editor window is visible (cause its what screwed us up) + if (EditorWindow.focusedWindow.GetType() == T) + { + var window = EditorWindow.GetWindow(T, true, "Unity Preferences"); + + + if (window == null) + { + if (Debug) + { + UnityEngine.Debug.Log("[VSCode] No Preferences Window Found (really?)"); + } + return; + } + + var invokerType = window.GetType(); + var invokerMethod = invokerType.GetMethod("ReadPreferences", + System.Reflection.BindingFlags.NonPublic | System.Reflection.BindingFlags.Instance); + + if (invokerMethod != null) + { + invokerMethod.Invoke(window, null); + } + else if (Debug) + { + UnityEngine.Debug.Log("[VSCode] No Reflection Method Found For Preferences"); + } + } + } + + /// + /// Determine what port Unity is listening for on Windows + /// + static int GetDebugPort() + { +#if UNITY_EDITOR_WIN + System.Diagnostics.Process process = new System.Diagnostics.Process(); + process.StartInfo.FileName = "netstat"; + process.StartInfo.Arguments = "-a -n -o -p TCP"; + process.StartInfo.UseShellExecute = false; + process.StartInfo.RedirectStandardOutput = true; + process.Start(); + + string output = process.StandardOutput.ReadToEnd(); + string[] lines = output.Split('\n'); + + process.WaitForExit(); + + foreach (string line in lines) + { + string[] tokens = Regex.Split(line, "\\s+"); + if (tokens.Length > 4) + { + int test = -1; + int.TryParse(tokens[5], out test); + + if (test > 1023) + { + try + { + var p = System.Diagnostics.Process.GetProcessById(test); + if (p.ProcessName == "Unity") + { + return test; + } + } + catch + { + + } + } + } + } +#else + System.Diagnostics.Process process = new System.Diagnostics.Process(); + process.StartInfo.FileName = "lsof"; + process.StartInfo.Arguments = "-c /^Unity$/ -i 4tcp -a"; + process.StartInfo.UseShellExecute = false; + process.StartInfo.RedirectStandardOutput = true; + process.Start(); + + // Not thread safe (yet!) + string output = process.StandardOutput.ReadToEnd(); + string[] lines = output.Split('\n'); + + process.WaitForExit(); + + foreach (string line in lines) + { + int port = -1; + if (line.StartsWith("Unity")) + { + string[] portions = line.Split(new string[] { "TCP *:" }, System.StringSplitOptions.None); + if (portions.Length >= 2) + { + Regex digitsOnly = new Regex(@"[^\d]"); + string cleanPort = digitsOnly.Replace(portions[1], ""); + if (int.TryParse(cleanPort, out port)) + { + if (port > -1) + { + return port; + } + } + } + } + } +#endif + return -1; + } + + /// + /// Manually install the original Unity Debuger + /// + /// + /// This should auto update to the latest. + /// + static void InstallUnityDebugger() + { + EditorUtility.DisplayProgressBar("VSCode", "Downloading Unity Debugger ...", 0.1f); + byte[] fileContent; + + try + { + using (var webClient = new System.Net.WebClient()) + { + fileContent = webClient.DownloadData(UnityDebuggerURL); + } + } + catch (Exception e) + { + if (Debug) + { + UnityEngine.Debug.Log("[VSCode] " + e.Message); + } + // Don't go any further if there is an error + return; + } + finally + { + EditorUtility.ClearProgressBar(); + } + + // Do we have a file to install? + if (fileContent != null) + { + string fileName = System.IO.Path.GetTempPath() + Guid.NewGuid().ToString() + ".vsix"; + File.WriteAllBytes(fileName, fileContent); + + CallVSCode(fileName); + } + + } + + // HACK: This is in until Unity can figure out why MD keeps opening even though a different program is selected. + [MenuItem("Assets/Open C# Project In Code", false, 1000)] + static void MenuOpenProject() + { + // Force the project files to be sync + SyncSolution(); + + // Load Project + CallVSCode("\"" + WorkspacePath + "\""); + } + + /// + /// Print a error message to the Unity Console about not finding the code executable + /// + static void PrintNotFound(string path) + { + UnityEngine.Debug.LogError("[VSCode] Code executable in '" + path + "' not found. Check your" + + "Visual Studio Code installation and insert the correct path in the Preferences menu."); + } + + [MenuItem("Assets/Open C# Project In Code", true, 1000)] + static bool ValidateMenuOpenProject() + { + return Enabled; + } + + /// + /// VS Code Integration Preferences Item + /// + /// + /// Contains all 3 toggles: Enable/Disable; Debug On/Off; Writing Launch File On/Off + /// + [PreferenceItem("VSCode")] + static void VSCodePreferencesItem() + { + if (EditorApplication.isCompiling) + { + EditorGUILayout.HelpBox("Please wait for Unity to finish compiling. \nIf the window doesn't refresh, simply click on the window or move it around to cause a repaint to happen.", MessageType.Warning); + return; + } + EditorGUILayout.BeginVertical(); + + var developmentInfo = "Support development of this plugin, follow @reapazor and @dotbunny on Twitter."; + var versionInfo = string.Format("{0:0.00}", Version) + VersionCode + ", GitHub version @ " + string.Format("{0:0.00}", GitHubVersion); + EditorGUILayout.HelpBox(developmentInfo + " --- [ " + versionInfo + " ]", MessageType.None); + + EditorGUI.BeginChangeCheck(); + + // Need the VS Code executable + EditorGUILayout.BeginHorizontal(); + EditorGUILayout.LabelField("VS Code Path", GUILayout.Width(75)); +#if UNITY_5_3_OR_NEWER + CodePath = EditorGUILayout.DelayedTextField(CodePath, GUILayout.ExpandWidth(true)); +#else + CodePath = EditorGUILayout.TextField(CodePath, GUILayout.ExpandWidth(true)); +#endif + GUI.SetNextControlName("PathSetButton"); + if (GUILayout.Button("...", GUILayout.Height(14), GUILayout.Width(20))) + { + GUI.FocusControl("PathSetButton"); + string path = EditorUtility.OpenFilePanel("Visual Studio Code Executable", "", ""); + if (path.Length != 0 && File.Exists(path) || Directory.Exists(path)) + { + CodePath = path; + } + } + EditorGUILayout.EndHorizontal(); + EditorGUILayout.Space(); + + Enabled = EditorGUILayout.Toggle(new GUIContent("Enable Integration", "Should the integration work its magic for you?"), Enabled); + + UseUnityDebugger = EditorGUILayout.Toggle(new GUIContent("Use Unity Debugger", "Should the integration integrate with Unity's VSCode Extension (must be installed)."), UseUnityDebugger); + + AutoOpenEnabled = EditorGUILayout.Toggle(new GUIContent("Enable Auto Open", "When opening a project in Unity, should it automatically open in VS Code?"), AutoOpenEnabled); + + EditorGUILayout.Space(); + RevertExternalScriptEditorOnExit = EditorGUILayout.Toggle(new GUIContent("Revert Script Editor On Unload", "Should the external script editor setting be reverted to its previous setting on project unload? This is useful if you do not use Code with all your projects."), RevertExternalScriptEditorOnExit); + + EditorGUILayout.Space(); + UseParentWorkspace = EditorGUILayout.Toggle(new GUIContent("Parent as workspace", "Should the parent of the project be used as the workspace directory? Usefull if you have the Unity project in a subdirectory."), UseParentWorkspace); + + Debug = EditorGUILayout.Toggle(new GUIContent("Output Messages To Console", "Should informational messages be sent to Unity's Console?"), Debug); + + WriteLaunchFile = EditorGUILayout.Toggle(new GUIContent("Always Write Launch File", "Always write the launch.json settings when entering play mode?"), WriteLaunchFile); + + EditorGUILayout.Space(); + + AutomaticUpdates = EditorGUILayout.Toggle(new GUIContent("Automatic Updates", "Should the plugin automatically update itself?"), AutomaticUpdates); + + UpdateTime = EditorGUILayout.IntSlider(new GUIContent("Update Timer (Days)", "After how many days should updates be checked for?"), UpdateTime, 1, 31); + + EditorGUILayout.Space(); + EditorGUILayout.Space(); + + if (EditorGUI.EndChangeCheck()) + { + UpdateUnityPreferences(Enabled); + + // TODO: Force Unity To Reload Preferences + // This seems to be a hick up / issue + if (VSCode.Debug) + { + if (Enabled) + { + UnityEngine.Debug.Log("[VSCode] Integration Enabled"); + } + else + { + UnityEngine.Debug.Log("[VSCode] Integration Disabled"); + } + } + } + + if (GUILayout.Button(new GUIContent("Force Update", "Check for updates to the plugin, right NOW!"))) + { + CheckForUpdate(); + EditorGUILayout.EndVertical(); + return; + } + if (GUILayout.Button(new GUIContent("Write Workspace Settings", "Output a default set of workspace settings for VSCode to use, ignoring many different types of files."))) + { + WriteWorkspaceSettings(); + EditorGUILayout.EndVertical(); + return; + } + EditorGUILayout.Space(); + + if (UseUnityDebugger) + { + EditorGUILayout.HelpBox("In order for the \"Use Unity Debuggger\" option to function above, you need to have installed the Unity Debugger Extension for Visual Studio Code.", MessageType.Warning); + if (GUILayout.Button(new GUIContent("Install Unity Debugger", "Install the Unity Debugger Extension into Code"))) + { + InstallUnityDebugger(); + EditorGUILayout.EndVertical(); + return; + } + } + + EditorGUILayout.EndVertical(); + } + + /// + /// Asset Open Callback (from Unity) + /// + /// + /// Called when Unity is about to open an asset. + /// + [UnityEditor.Callbacks.OnOpenAssetAttribute()] + static bool OnOpenedAsset(int instanceID, int line) + { + // bail out if we are not using VSCode + if (!Enabled) + { + return false; + } + + // current path without the asset folder + string appPath = UnityProjectPath; + + // determine asset that has been double clicked in the project view + UnityEngine.Object selected = EditorUtility.InstanceIDToObject(instanceID); + + // additional file extensions + string selectedFilePath = AssetDatabase.GetAssetPath(selected); + string selectedFileExt = Path.GetExtension(selectedFilePath); + if (selectedFileExt == null) + { + selectedFileExt = String.Empty; + } + if (!String.IsNullOrEmpty(selectedFileExt)) + { + selectedFileExt = selectedFileExt.ToLower(); + } + + // open supported object types + if (selected.GetType().ToString() == "UnityEditor.MonoScript" || + selected.GetType().ToString() == "UnityEngine.Shader" || + VSCode.FileExtensions.IndexOf(selectedFileExt, StringComparison.OrdinalIgnoreCase) >= 0) + { + string completeFilepath = appPath + Path.DirectorySeparatorChar + AssetDatabase.GetAssetPath(selected); + + string args = null; + if (line == -1) + { + args = "\"" + WorkspacePath + "\" \"" + completeFilepath + "\" -r"; + } + else + { + args = "\"" + WorkspacePath + "\" -g \"" + completeFilepath + ":" + line.ToString() + "\" -r"; + } + // call 'open' + CallVSCode(args); + + return true; + } + + // Didnt find a code file? let Unity figure it out + return false; + + } + + /// + /// Executed when the Editor's playmode changes allowing for capture of required data + /// +#if UNITY_2017_2_OR_NEWER + static void OnPlaymodeStateChanged(UnityEditor.PlayModeStateChange state) +#else + static void OnPlaymodeStateChanged() +#endif + { + if (UnityEngine.Application.isPlaying && EditorApplication.isPlayingOrWillChangePlaymode) + { + UpdateLaunchFile(); + } + } + + /// + /// Detect when scripts are reloaded and relink playmode detection + /// + [UnityEditor.Callbacks.DidReloadScripts()] + static void OnScriptReload() + { +#if UNITY_2017_2_OR_NEWER + EditorApplication.playModeStateChanged -= OnPlaymodeStateChanged; + EditorApplication.playModeStateChanged += OnPlaymodeStateChanged; +#else + EditorApplication.playmodeStateChanged -= OnPlaymodeStateChanged; + EditorApplication.playmodeStateChanged += OnPlaymodeStateChanged; +#endif + } + + /// + /// Remove extra/erroneous lines from a file. + static void ScrubFile(string path) + { + string[] lines = File.ReadAllLines(path); + System.Collections.Generic.List newLines = new System.Collections.Generic.List(); + for (int i = 0; i < lines.Length; i++) + { + // Check Empty + if (string.IsNullOrEmpty(lines[i].Trim()) || lines[i].Trim() == "\t" || lines[i].Trim() == "\t\t") + { + + } + else + { + newLines.Add(lines[i]); + } + } + File.WriteAllLines(path, newLines.ToArray()); + } + + /// + /// Remove extra/erroneous data from project file (content). + /// + static string ScrubProjectContent(string content) + { + if (content.Length == 0) + return ""; + +#if !UNITY_EDITOR_WIN + // Moved to 3.5, 2.0 is legacy. + if (content.IndexOf("v3.5") != -1) + { + content = Regex.Replace(content, "v3.5", "v2.0"); + } +#endif + + string targetPath = "";// "Temp" + Path.DirectorySeparatorChar + "bin" + Path.DirectorySeparatorChar + "Debug" + Path.DirectorySeparatorChar + ""; //OutputPath + string langVersion = "default"; + + + bool found = true; + int location = 0; + string addedOptions = ""; + int startLocation = -1; + int endLocation = -1; + int endLength = 0; + + while (found) + { + startLocation = -1; + endLocation = -1; + endLength = 0; + addedOptions = ""; + startLocation = content.IndexOf("", startLocation); + endLength = (endLocation - startLocation); + + + if (endLocation == -1) + { + found = false; + continue; + } + else + { + found = true; + location = endLocation; + } + + if (content.Substring(startLocation, endLength).IndexOf("") == -1) + { + addedOptions += "\n\r\t" + targetPath + "\n\r"; + } + + if (content.Substring(startLocation, endLength).IndexOf("") == -1) + { + addedOptions += "\n\r\t" + langVersion + "\n\r"; + } + + if (!string.IsNullOrEmpty(addedOptions)) + { + content = content.Substring(0, endLocation) + addedOptions + content.Substring(endLocation); + } + } + else + { + found = false; + } + } + + return content; + } + + /// + /// Remove extra/erroneous data from solution file (content). + /// + static string ScrubSolutionContent(string content) + { + // Replace Solution Version + content = content.Replace( + "Microsoft Visual Studio Solution File, Format Version 11.00\r\n# Visual Studio 2008\r\n", + "\r\nMicrosoft Visual Studio Solution File, Format Version 12.00\r\n# Visual Studio 2012"); + + // Remove Solution Properties (Unity Junk) + int startIndex = content.IndexOf("GlobalSection(SolutionProperties) = preSolution"); + if (startIndex != -1) + { + int endIndex = content.IndexOf("EndGlobalSection", startIndex); + content = content.Substring(0, startIndex) + content.Substring(endIndex + 16); + } + + return content; + } + + /// + /// Update Visual Studio Code Launch file + /// + static void UpdateLaunchFile() + { + if (!VSCode.Enabled) + { + return; + } + else if (VSCode.UseUnityDebugger) + { + if (!Directory.Exists(VSCode.SettingsFolder)) + System.IO.Directory.CreateDirectory(VSCode.SettingsFolder); + + // Write out proper formatted JSON (hence no more SimpleJSON here) + string fileContent = "{\n\t\"version\": \"0.2.0\",\n\t\"configurations\": [\n\t\t{\n\t\t\t\"name\": \"Unity Editor\",\n\t\t\t\"type\": \"unity\",\n\t\t\t\"request\": \"launch\"\n\t\t},\n\t\t{\n\t\t\t\"name\": \"Windows Player\",\n\t\t\t\"type\": \"unity\",\n\t\t\t\"request\": \"launch\"\n\t\t},\n\t\t{\n\t\t\t\"name\": \"OSX Player\",\n\t\t\t\"type\": \"unity\",\n\t\t\t\"request\": \"launch\"\n\t\t},\n\t\t{\n\t\t\t\"name\": \"Linux Player\",\n\t\t\t\"type\": \"unity\",\n\t\t\t\"request\": \"launch\"\n\t\t},\n\t\t{\n\t\t\t\"name\": \"iOS Player\",\n\t\t\t\"type\": \"unity\",\n\t\t\t\"request\": \"launch\"\n\t\t},\n\t\t{\n\t\t\t\"name\": \"Android Player\",\n\t\t\t\"type\": \"unity\",\n\t\t\t\"request\": \"launch\"\n\n\t\t}\n\t]\n}"; + File.WriteAllText(VSCode.LaunchPath, fileContent); + } + else if (VSCode.WriteLaunchFile) + { + int port = GetDebugPort(); + if (port > -1) + { + if (!Directory.Exists(VSCode.SettingsFolder)) + System.IO.Directory.CreateDirectory(VSCode.SettingsFolder); + + // Write out proper formatted JSON (hence no more SimpleJSON here) + string fileContent = "{\n\t\"version\":\"0.2.0\",\n\t\"configurations\":[ \n\t\t{\n\t\t\t\"name\":\"Unity\",\n\t\t\t\"type\":\"mono\",\n\t\t\t\"request\":\"attach\",\n\t\t\t\"address\":\"localhost\",\n\t\t\t\"port\":" + port + "\n\t\t}\n\t]\n}"; + File.WriteAllText(VSCode.LaunchPath, fileContent); + + if (VSCode.Debug) + { + UnityEngine.Debug.Log("[VSCode] Debug Port Found (" + port + ")"); + } + } + else + { + if (VSCode.Debug) + { + UnityEngine.Debug.LogWarning("[VSCode] Unable to determine debug port."); + } + } + } + } + + /// + /// Update Unity Editor Preferences + /// + /// Should we turn on this party! + static void UpdateUnityPreferences(bool enabled) + { + if (enabled) + { + // App + if (EditorPrefs.GetString("kScriptsDefaultApp") != CodePath) + { + EditorPrefs.SetString("VSCode_PreviousApp", EditorPrefs.GetString("kScriptsDefaultApp")); + } + EditorPrefs.SetString("kScriptsDefaultApp", CodePath); + + // Arguments + if (EditorPrefs.GetString("kScriptEditorArgs") != "-r -g `$(File):$(Line)`") + { + EditorPrefs.SetString("VSCode_PreviousArgs", EditorPrefs.GetString("kScriptEditorArgs")); + } + + EditorPrefs.SetString("kScriptEditorArgs", "-r -g `$(File):$(Line)`"); + EditorPrefs.SetString("kScriptEditorArgs" + CodePath, "-r -g `$(File):$(Line)`"); + + + // MonoDevelop Solution + if (EditorPrefs.GetBool("kMonoDevelopSolutionProperties", false)) + { + EditorPrefs.SetBool("VSCode_PreviousMD", true); + } + EditorPrefs.SetBool("kMonoDevelopSolutionProperties", false); + + // Support Unity Proj (JS) + if (EditorPrefs.GetBool("kExternalEditorSupportsUnityProj", false)) + { + EditorPrefs.SetBool("VSCode_PreviousUnityProj", true); + } + EditorPrefs.SetBool("kExternalEditorSupportsUnityProj", false); + + if (!EditorPrefs.GetBool("AllowAttachedDebuggingOfEditor", false)) + { + EditorPrefs.SetBool("VSCode_PreviousAttach", false); + } + EditorPrefs.SetBool("AllowAttachedDebuggingOfEditor", true); + + } + else + { + // Restore previous app + if (!string.IsNullOrEmpty(EditorPrefs.GetString("VSCode_PreviousApp"))) + { + EditorPrefs.SetString("kScriptsDefaultApp", EditorPrefs.GetString("VSCode_PreviousApp")); + } + + // Restore previous args + if (!string.IsNullOrEmpty(EditorPrefs.GetString("VSCode_PreviousArgs"))) + { + EditorPrefs.SetString("kScriptEditorArgs", EditorPrefs.GetString("VSCode_PreviousArgs")); + } + + // Restore MD setting + if (EditorPrefs.GetBool("VSCode_PreviousMD", false)) + { + EditorPrefs.SetBool("kMonoDevelopSolutionProperties", true); + } + + // Restore MD setting + if (EditorPrefs.GetBool("VSCode_PreviousUnityProj", false)) + { + EditorPrefs.SetBool("kExternalEditorSupportsUnityProj", true); + } + + // Always leave editor attaching on, I know, it solves the problem of needing to restart for this + // to actually work + EditorPrefs.SetBool("AllowAttachedDebuggingOfEditor", true); + } + + if (!alreadyFixedPreferences) + { + alreadyFixedPreferences = true; + FixUnityPreferences(); + } + } + + /// + /// Determines if the current path to the code executable is valid or not (exists) + /// + static bool VSCodeExists(string curPath) + { +#if UNITY_EDITOR_OSX + return System.IO.Directory.Exists(curPath); +#else + System.IO.FileInfo code = new System.IO.FileInfo(curPath); + return code.Exists; +#endif + } + + /// + /// Write Default Workspace Settings + /// + static void WriteWorkspaceSettings() + { + if (Debug) + { + UnityEngine.Debug.Log("[VSCode] Workspace Settings Written"); + } + + if (!Directory.Exists(VSCode.SettingsFolder)) + { + System.IO.Directory.CreateDirectory(VSCode.SettingsFolder); + } + + string exclusions = + // Associations + "{\n" + + "\t\"files.associations\":\n" + + "\t{\n" + + "\t\t\"*.bjs\":\"javascript\",\n" + + "\t\t\"*.javascript\":\"javascript\"\n" + + "\t},\n" + + "\t\"files.exclude\":\n" + + "\t{\n" + + // Hidden Files + "\t\t\"**/.DS_Store\":true,\n" + + "\t\t\"**/.git\":true,\n" + + "\t\t\"**/.gitignore\":true,\n" + + "\t\t\"**/.gitattributes\":true,\n" + + "\t\t\"**/.gitmodules\":true,\n" + + "\t\t\"**/.svn\":true,\n" + + + // Compressed Files + "\t\t\"**/*.zip\":true,\n" + + "\t\t\"**/*.gz\":true,\n" + + "\t\t\"**/*.7z\":true,\n" + + + // Project Files + "\t\t\"**/*.booproj\":true,\n" + + "\t\t\"**/*.pidb\":true,\n" + + "\t\t\"**/*.suo\":true,\n" + + "\t\t\"**/*.user\":true,\n" + + "\t\t\"**/*.userprefs\":true,\n" + + "\t\t\"**/*.unityproj\":true,\n" + + "\t\t\"**/*.dll\":true,\n" + + "\t\t\"**/*.exe\":true,\n" + + + // Media Files + "\t\t\"**/*.pdf\":true,\n" + + + // Video + "\t\t\"**/*.mp4\":true,\n" + + + // Audio + "\t\t\"**/*.mid\":true,\n" + + "\t\t\"**/*.midi\":true,\n" + + "\t\t\"**/*.wav\":true,\n" + + "\t\t\"**/*.mp3\":true,\n" + + "\t\t\"**/*.ogg\":true,\n" + + + // Textures + "\t\t\"**/*.gif\":true,\n" + + "\t\t\"**/*.ico\":true,\n" + + "\t\t\"**/*.jpg\":true,\n" + + "\t\t\"**/*.jpeg\":true,\n" + + "\t\t\"**/*.png\":true,\n" + + "\t\t\"**/*.psd\":true,\n" + + "\t\t\"**/*.tga\":true,\n" + + "\t\t\"**/*.tif\":true,\n" + + "\t\t\"**/*.tiff\":true,\n" + + "\t\t\"**/*.hdr\":true,\n" + + "\t\t\"**/*.exr\":true,\n" + + + // Models + "\t\t\"**/*.3ds\":true,\n" + + "\t\t\"**/*.3DS\":true,\n" + + "\t\t\"**/*.fbx\":true,\n" + + "\t\t\"**/*.FBX\":true,\n" + + "\t\t\"**/*.lxo\":true,\n" + + "\t\t\"**/*.LXO\":true,\n" + + "\t\t\"**/*.ma\":true,\n" + + "\t\t\"**/*.MA\":true,\n" + + "\t\t\"**/*.obj\":true,\n" + + "\t\t\"**/*.OBJ\":true,\n" + + + // Unity File Types + "\t\t\"**/*.asset\":true,\n" + + "\t\t\"**/*.cubemap\":true,\n" + + "\t\t\"**/*.flare\":true,\n" + + "\t\t\"**/*.mat\":true,\n" + + "\t\t\"**/*.meta\":true,\n" + + "\t\t\"**/*.prefab\":true,\n" + + "\t\t\"**/*.unity\":true,\n" + + "\t\t\"**/*.anim\":true,\n" + + "\t\t\"**/*.controller\":true,\n" + + + // Folders + "\t\t\"build/\":true,\n" + + "\t\t\"Build/\":true,\n" + + "\t\t\"Library/\":true,\n" + + "\t\t\"library/\":true,\n" + + "\t\t\"obj/\":true,\n" + + "\t\t\"Obj/\":true,\n" + + "\t\t\"ProjectSettings/\":true,\r" + + "\t\t\"temp/\":true,\n" + + "\t\t\"Temp/\":true\n" + + "\t}\n" + + "}"; + + // Dont like the replace but it fixes the issue with the JSON + File.WriteAllText(VSCode.SettingsPath, exclusions); + } + + #endregion + } + + /// + /// VSCode Asset AssetPostprocessor + /// This will ensure any time that the project files are generated the VSCode versions will be made + /// + /// Undocumented Event + public class VSCodeAssetPostprocessor : AssetPostprocessor + { + /// + /// On documented, project generation event callback + /// + private static void OnGeneratedCSProjectFiles() + { + // Force execution of VSCode update + VSCode.UpdateSolution(); + } + } +} diff --git a/Assets/VSCode/Plugins/Editor/VSCode.cs.meta b/Assets/VSCode/Plugins/Editor/VSCode.cs.meta new file mode 100644 index 00000000..d2c039f0 --- /dev/null +++ b/Assets/VSCode/Plugins/Editor/VSCode.cs.meta @@ -0,0 +1,12 @@ +fileFormatVersion: 2 +guid: c34beeaf0d4cf44c49f1039006a08591 +timeCreated: 1444653497 +licenseType: Store +MonoImporter: + serializedVersion: 2 + defaultReferences: [] + executionOrder: 0 + icon: {instanceID: 0} + userData: + assetBundleName: + assetBundleVariant: diff --git a/Assets/VSCode/README.md b/Assets/VSCode/README.md new file mode 100644 index 00000000..3e4df0ce --- /dev/null +++ b/Assets/VSCode/README.md @@ -0,0 +1,37 @@ +# VSCode +> Seamless Visual Studio Code Integration in Unity - As seen in the [Visual Studio Code documentation!](https://code.visualstudio.com/Docs/runtimes/unity) + +### Requirements +##### Unity > 4.5 && Unity < 5.5 +I am not sure exactly where in the 4.x cycle some of the features I'm using were introduced, but I'm guessing its around the 4.5+ mark. I've checked with the latest 4.5.0f6 release. Unity has also committed to having full support for Code when Unity 5.5 drops. So at that point all bets are off for the usefulness of this plugin. Like our MonoDevelop.Unity plugin of past, Unity catches up eventually. + +#####Visual Studio Code 0.10.1+ +Get the [latest version](https://code.visualstudio.com), or have a look at the past releases of the VSCode [plugin](https://github.com/dotBunny/VSCode/releases/tag/1.6.5) for support for your version. + +######Mono +A good number of people have needed to install Mono in order for many of the issues with OmniSharp to be resolved. +I would suggest installing the latest package available at the [Mono Project](http://www.mono-project.com/download/). Don't worry it will not mess with Unity. + +### Installation +It is important to make sure that the `VSCode.cs` file is placed under an `Editor` folder in the project. An example of this arrangement would be placing the file in `/Assets/Plugins/Editor/VSCode.cs`. By default it has its own folder structure which does this for you. + +### Unity Asset Store Package +A UAS packaged version of the plugin is [available](http://u3d.as/jmM) for your consumption. + +### Usage +Once the VSCode file is in place, simply navigate your way to the `Unity Preferences` and select `VSCode` and check the `Enable Integration` option. + +That's it! Your ready to go! + +OK, so maybe some people need a little video explaining some of the finer details of how to use the plugin. So I shot a [quick video](https://vimeo.com/dotbunny/vscode) that highlights the ups and the downs (like Unity hanging after debugging sometimes) for people to watch. Please note this video is from a previous version of the plugin where things are in the menu, this has changed since then. + +### Platform Support +I use the plugin every day on a Mac (so it's battle tested there), and occasionally test it on a Windows VM. As for the recently announced Linux support, it should work just like the Mac version. I'll get around to installing the Linux editor sometime in the near future. + +The Windows version of Visual Studio Code currently does not support debugging Mono, and will just throw a warning if you try to do it. The "Code" team is aware of this limitation, and we'll leave it at that. + +### Automatic Update +With version 2.0 of the plugin, I've introduced a feature where it will auto-update itself if allowed. This should make things a lot easier in the future. + +### Support +Please provide feedback through the GitHub [Issue](https://github.com/dotBunny/VSCode/issues) system. diff --git a/Packages/packages-lock.json b/Packages/packages-lock.json index 4cdfa09d..6492ad2c 100644 --- a/Packages/packages-lock.json +++ b/Packages/packages-lock.json @@ -10,7 +10,7 @@ "url": "https://packages.unity.com" }, "com.unity.burst": { - "version": "1.8.7", + "version": "1.8.8", "depth": 1, "source": "registry", "dependencies": { diff --git a/ProjectSettings/EditorSettings.asset b/ProjectSettings/EditorSettings.asset index 2a760fd3..cdbb97f1 100644 --- a/ProjectSettings/EditorSettings.asset +++ b/ProjectSettings/EditorSettings.asset @@ -3,13 +3,14 @@ --- !u!159 &1 EditorSettings: m_ObjectHideFlags: 0 - serializedVersion: 11 + serializedVersion: 12 m_SerializationMode: 2 m_LineEndingsForNewScripts: 0 m_DefaultBehaviorMode: 0 m_PrefabRegularEnvironment: {fileID: 0} m_PrefabUIEnvironment: {fileID: 0} m_SpritePackerMode: 0 + m_SpritePackerCacheSize: 10 m_SpritePackerPaddingPower: 1 m_Bc7TextureCompressor: 0 m_EtcTextureCompressorBehavior: 1 @@ -20,19 +21,20 @@ EditorSettings: m_ProjectGenerationRootNamespace: m_EnableTextureStreamingInEditMode: 1 m_EnableTextureStreamingInPlayMode: 1 + m_EnableEditorAsyncCPUTextureLoading: 0 m_AsyncShaderCompilation: 1 - m_CachingShaderPreprocessor: 1 m_PrefabModeAllowAutoSave: 1 m_EnterPlayModeOptionsEnabled: 0 m_EnterPlayModeOptions: 3 m_GameObjectNamingDigits: 1 m_GameObjectNamingScheme: 0 m_AssetNamingUsesSpace: 1 + m_InspectorUseIMGUIDefaultInspector: 0 m_UseLegacyProbeSampleCount: 1 m_SerializeInlineMappingsOnOneLine: 0 m_DisableCookiesInLightmapper: 1 m_AssetPipelineMode: 1 - m_RefreshImportMode: 0 + m_RefreshImportMode: 1 m_CacheServerMode: 0 m_CacheServerEndpoint: m_CacheServerNamespacePrefix: default @@ -42,3 +44,4 @@ EditorSettings: m_CacheServerEnableTls: 0 m_CacheServerValidationMode: 2 m_CacheServerDownloadBatchSize: 128 + m_EnableEnlightenBakedGI: 0 diff --git a/ProjectSettings/ProjectSettings.asset b/ProjectSettings/ProjectSettings.asset index afc27fb3..5a8f333b 100644 --- a/ProjectSettings/ProjectSettings.asset +++ b/ProjectSettings/ProjectSettings.asset @@ -86,6 +86,7 @@ PlayerSettings: hideHomeButton: 0 submitAnalytics: 1 usePlayerLog: 1 + dedicatedServerOptimizations: 0 bakeCollisionMeshes: 1 forceSingleInstance: 0 useFlipModelSwapchain: 1 @@ -125,6 +126,7 @@ PlayerSettings: switchNVNMaxPublicTextureIDCount: 0 switchNVNMaxPublicSamplerIDCount: 0 switchNVNGraphicsFirmwareMemory: 32 + switchMaxWorkerMultiple: 8 stadiaPresentMode: 0 stadiaTargetFramerate: 0 vulkanNumSwapchainBuffers: 3 @@ -133,7 +135,7 @@ PlayerSettings: vulkanEnableLateAcquireNextImage: 0 vulkanEnableCommandBufferRecycling: 1 loadStoreDebugModeEnabled: 0 - bundleVersion: 4.0.0 + bundleVersion: 4.1.0 preloadedAssets: [] metroInputSource: 0 wsaTransparentSwapchain: 0 @@ -380,6 +382,7 @@ PlayerSettings: switchSocketConcurrencyLimit: 14 switchScreenResolutionBehavior: 2 switchUseCPUProfiler: 0 + switchEnableFileSystemTrace: 0 switchUseGOLDLinker: 0 switchLTOSetting: 0 switchApplicationID: 0x01004b9000490000 diff --git a/ProjectSettings/ProjectVersion.txt b/ProjectSettings/ProjectVersion.txt index 78a77889..88bb9cf9 100644 --- a/ProjectSettings/ProjectVersion.txt +++ b/ProjectSettings/ProjectVersion.txt @@ -1,2 +1,2 @@ -m_EditorVersion: 2022.3.7f1 -m_EditorVersionWithRevision: 2022.3.7f1 (b16b3b16c7a0) +m_EditorVersion: 2022.3.10f1 +m_EditorVersionWithRevision: 2022.3.10f1 (ff3792e53c62) diff --git a/README.md b/README.md index 85b22bfd..d6c0abab 100644 --- a/README.md +++ b/README.md @@ -34,6 +34,7 @@ Here are the list of items that is implemented(marked) or planned to be implemen - [X] Joint models - [X] 2-Wheeled Motor driving - [X] Joint control + - [ ] Joint Pose - [X] Sensor models - [X] LiDAR Sensor - [X] 2D @@ -66,6 +67,8 @@ Here are the list of items that is implemented(marked) or planned to be implemen Plus, [SDF](http://sdformat.org/spec?ver=1.6) file basically targeting and supporting version 1.6 and works on the essential elements such as ``, ``, ``, ``, ``, etc. It does not support optional elmenets like ``, `