| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | using System; |
| | using System.Collections; |
| | using System.Collections.Generic; |
| | using System.Diagnostics.CodeAnalysis; |
| | using System.IO; |
| | using System.Linq; |
| | using System.Runtime.InteropServices; |
| | using System.Text; |
| | using System.Xml; |
| | using UnityEngine; |
| | using UnityEngine.Profiling; |
| |
|
| | namespace Mujoco { |
| |
|
| | public class PhysicsRuntimeException : Exception { |
| | public PhysicsRuntimeException(string message) : base(message) {} |
| | } |
| |
|
| | public class MjScene : MonoBehaviour { |
| |
|
| | public unsafe MujocoLib.mjModel_* Model = null; |
| | public unsafe MujocoLib.mjData_* Data = null; |
| |
|
| | |
| | |
| | public MjcfGenerationContext GenerationContext { |
| | get { |
| | if (_generationContext == null) { |
| | throw new InvalidOperationException( |
| | "This property can only be accessed from the scope of MjComponent.GenerateMjcf()."); |
| | } |
| | return _generationContext; |
| | } |
| | } |
| |
|
| | public static MjScene Instance { |
| | get { |
| | if (_instance == null) { |
| | var instances = FindObjectsOfType<MjScene>(); |
| | if (instances.Length >= 1) { |
| | throw new InvalidOperationException( |
| | "A MjScene singleton is created automatically, yet multiple instances exist."); |
| | } else { |
| | GameObject go = new GameObject("MjScene"); |
| | _instance = go.AddComponent<MjScene>(); |
| | } |
| | } |
| | return _instance; |
| | } |
| | } |
| |
|
| | public static bool InstanceExists { get => _instance != null; } |
| |
|
| | public void Awake() { |
| | if (_instance == null) { |
| | _instance = this; |
| | } else if (_instance != this) { |
| | throw new InvalidOperationException( |
| | "MjScene is a singleton, yet multiple instances found."); |
| | } |
| | } |
| |
|
| | private static MjScene _instance = null; |
| |
|
| | private List<MjComponent> _orderedComponents; |
| |
|
| | public event EventHandler<MjStepArgs> postInitEvent; |
| | public event EventHandler<MjStepArgs> preUpdateEvent; |
| | public event EventHandler<MjStepArgs> ctrlCallback; |
| | public event EventHandler<MjStepArgs> postUpdateEvent; |
| | public event EventHandler<MjStepArgs> preDestroyEvent; |
| |
|
| | protected unsafe void Start() { |
| | SceneRecreationAtLateUpdateRequested = false; |
| | CreateScene(); |
| | } |
| |
|
| | protected unsafe void OnDestroy() { |
| | DestroyScene(); |
| | } |
| |
|
| | protected unsafe void FixedUpdate() { |
| | preUpdateEvent?.Invoke(this, new MjStepArgs(Model, Data)); |
| | StepScene(); |
| | postUpdateEvent?.Invoke(this, new MjStepArgs(Model, Data)); |
| | } |
| |
|
| | public bool SceneRecreationAtLateUpdateRequested = false; |
| |
|
| | protected unsafe void LateUpdate() { |
| | if (SceneRecreationAtLateUpdateRequested) { |
| | RecreateScene(); |
| | SceneRecreationAtLateUpdateRequested = false; |
| | } |
| | } |
| |
|
| | |
| | |
| | |
| | |
| | |
| | |
| | private MjcfGenerationContext _generationContext; |
| |
|
| | |
| | public unsafe XmlDocument CreateScene(bool skipCompile=false) { |
| | if (_generationContext != null) { |
| | throw new InvalidOperationException( |
| | "The scene is currently being generated on another thread."); |
| | } |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | var hierarchyRoots = FindObjectsOfType<MjComponent>() |
| | .Where(component => MjHierarchyTool.FindParentComponent(component) == null) |
| | .Select(component => component.transform) |
| | .Distinct(); |
| | _orderedComponents = new List<MjComponent>(); |
| | foreach (var root in hierarchyRoots) { |
| | _orderedComponents.AddRange(MjHierarchyTool.LinearizeHierarchyBFS(root)); |
| | } |
| |
|
| | XmlDocument sceneMjcf = null; |
| | try { |
| | _generationContext = new MjcfGenerationContext(); |
| | sceneMjcf = GenerateSceneMjcf(_orderedComponents); |
| | } catch (Exception e) { |
| | _generationContext = null; |
| | Debug.LogException(e); |
| | #if UNITY_EDITOR |
| | UnityEditor.EditorApplication.isPlaying = false; |
| | #else |
| | Application.Quit(); |
| | #endif |
| | throw; |
| | } |
| | _generationContext = null; |
| |
|
| | |
| | var settings = MjGlobalSettings.Instance; |
| | if (settings && !string.IsNullOrEmpty(settings.DebugFileName)) { |
| | SaveToFile(sceneMjcf, Path.Combine(Application.temporaryCachePath, settings.DebugFileName)); |
| | } |
| |
|
| | if (!skipCompile) { |
| | |
| | CompileScene(sceneMjcf, _orderedComponents); |
| | } |
| | postInitEvent?.Invoke(this, new MjStepArgs(Model, Data)); |
| | return sceneMjcf; |
| | } |
| |
|
| | private unsafe void CompileScene( |
| | XmlDocument mjcf, IEnumerable<MjComponent> components) { |
| | Model = MjEngineTool.LoadModelFromString(mjcf.OuterXml); |
| | if (Model == null) { |
| | throw new NullReferenceException("Model loading failed, see other errors for root cause."); |
| | } else { |
| | Data = MujocoLib.mj_makeData(Model); |
| | } |
| | if (Data == null) { |
| | throw new NullReferenceException("Model loaded but mj_makeData failed."); |
| | } |
| |
|
| | |
| | foreach (var component in components) { |
| | component.BindToRuntime(Model, Data); |
| | } |
| | } |
| |
|
| | public unsafe void SyncUnityToMjState() { |
| | foreach (var component in _orderedComponents) { |
| | if (component != null && component.isActiveAndEnabled) { |
| | component.OnSyncState(Data); |
| | } |
| | } |
| | } |
| |
|
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | public unsafe void RecreateScene() { |
| | |
| | var joints = FindObjectsOfType<MjBaseJoint>(); |
| | var positions = new Dictionary<MjBaseJoint, double[]>(); |
| | var velocities = new Dictionary<MjBaseJoint, double[]>(); |
| | foreach (var joint in joints) { |
| | if (joint.QposAddress > -1) { |
| | switch (Model->jnt_type[joint.MujocoId]) { |
| | default: |
| | case (int)MujocoLib.mjtJoint.mjJNT_HINGE: |
| | case (int)MujocoLib.mjtJoint.mjJNT_SLIDE: |
| | positions[joint] = new double[] {Data->qpos[joint.QposAddress]}; |
| | velocities[joint] = new double[] {Data->qvel[joint.DofAddress]}; |
| | break; |
| | case (int)MujocoLib.mjtJoint.mjJNT_BALL: |
| | positions[joint] = new double[] { |
| | Data->qpos[joint.QposAddress], |
| | Data->qpos[joint.QposAddress+1], |
| | Data->qpos[joint.QposAddress+2], |
| | Data->qpos[joint.QposAddress+3]}; |
| | velocities[joint] = new double[] { |
| | Data->qvel[joint.DofAddress], |
| | Data->qvel[joint.DofAddress+1], |
| | Data->qvel[joint.DofAddress+2]}; |
| | break; |
| | case (int)MujocoLib.mjtJoint.mjJNT_FREE: |
| | positions[joint] = new double[] { |
| | Data->qpos[joint.QposAddress], |
| | Data->qpos[joint.QposAddress+1], |
| | Data->qpos[joint.QposAddress+2], |
| | Data->qpos[joint.QposAddress+3], |
| | Data->qpos[joint.QposAddress+4], |
| | Data->qpos[joint.QposAddress+5], |
| | Data->qpos[joint.QposAddress+6]}; |
| | velocities[joint] = new double[] { |
| | Data->qvel[joint.DofAddress], |
| | Data->qvel[joint.DofAddress+1], |
| | Data->qvel[joint.DofAddress+2], |
| | Data->qvel[joint.DofAddress+3], |
| | Data->qvel[joint.DofAddress+4], |
| | Data->qvel[joint.DofAddress+5]}; |
| | break; |
| | } |
| | } |
| | } |
| |
|
| | |
| | MujocoLib.mj_resetData(Model, Data); |
| | MujocoLib.mj_kinematics(Model, Data); |
| | SyncUnityToMjState(); |
| |
|
| | |
| | DestroyScene(); |
| | |
| | CreateScene(); |
| |
|
| | |
| | foreach (var joint in joints) { |
| | try { |
| | var position = positions[joint]; |
| | var velocity = velocities[joint]; |
| | switch (Model->jnt_type[joint.MujocoId]) { |
| | default: |
| | case (int)MujocoLib.mjtJoint.mjJNT_HINGE: |
| | case (int)MujocoLib.mjtJoint.mjJNT_SLIDE: |
| | Data->qpos[joint.QposAddress] = position[0]; |
| | Data->qvel[joint.DofAddress] = velocity[0]; |
| | break; |
| | case (int)MujocoLib.mjtJoint.mjJNT_BALL: |
| | Data->qpos[joint.QposAddress] = position[0]; |
| | Data->qpos[joint.QposAddress+1] = position[1]; |
| | Data->qpos[joint.QposAddress+2] = position[2]; |
| | Data->qpos[joint.QposAddress+3] = position[3]; |
| | Data->qvel[joint.DofAddress] = velocity[0]; |
| | Data->qvel[joint.DofAddress+1] = velocity[1]; |
| | Data->qvel[joint.DofAddress+2] = velocity[2]; |
| | break; |
| | case (int)MujocoLib.mjtJoint.mjJNT_FREE: |
| | Data->qpos[joint.QposAddress] = position[0]; |
| | Data->qpos[joint.QposAddress+1] = position[1]; |
| | Data->qpos[joint.QposAddress+2] = position[2]; |
| | Data->qpos[joint.QposAddress+3] = position[3]; |
| | Data->qpos[joint.QposAddress+4] = position[4]; |
| | Data->qpos[joint.QposAddress+5] = position[5]; |
| | Data->qpos[joint.QposAddress+6] = position[6]; |
| | Data->qvel[joint.DofAddress] = velocity[0]; |
| | Data->qvel[joint.DofAddress+1] = velocity[1]; |
| | Data->qvel[joint.DofAddress+2] = velocity[2]; |
| | Data->qvel[joint.DofAddress+3] = velocity[3]; |
| | Data->qvel[joint.DofAddress+4] = velocity[4]; |
| | Data->qvel[joint.DofAddress+5] = velocity[5]; |
| | break; |
| | } |
| | } catch {} |
| | } |
| | |
| | MujocoLib.mj_kinematics(Model, Data); |
| | SyncUnityToMjState(); |
| | } |
| |
|
| | |
| | public unsafe void DestroyScene() { |
| | preDestroyEvent?.Invoke(this, new MjStepArgs(Model, Data)); |
| | if (Model != null) { |
| | MujocoLib.mj_deleteModel(Model); |
| | Model = null; |
| | } |
| | if (Data != null) { |
| | MujocoLib.mj_deleteData(Data); |
| | Data = null; |
| | } |
| | } |
| |
|
| | |
| | public unsafe void StepScene() { |
| | if (Model == null || Data == null) { |
| | throw new NullReferenceException("Failed to create Mujoco runtime."); |
| | } |
| | Profiler.BeginSample("MjStep"); |
| | Profiler.BeginSample("MjStep.mj_step"); |
| | if (ctrlCallback != null){ |
| | MujocoLib.mj_step1(Model, Data); |
| | ctrlCallback?.Invoke(this, new MjStepArgs(Model, Data)); |
| | MujocoLib.mj_step2(Model, Data); |
| | } |
| | else { |
| | MujocoLib.mj_step(Model, Data); |
| | } |
| | Profiler.EndSample(); |
| | CheckForPhysicsException(); |
| |
|
| | Profiler.BeginSample("MjStep.OnSyncState"); |
| | SyncUnityToMjState(); |
| | Profiler.EndSample(); |
| | Profiler.EndSample(); |
| | } |
| |
|
| | private unsafe void CheckForPhysicsException() { |
| | if (Data->warning0.number > 0) { |
| | Data->warning0.number = 0; |
| | throw new PhysicsRuntimeException("INERTIA: (Near-) Singular inertia matrix."); |
| | } |
| | if (Data->warning1.number > 0) { |
| | Data->warning1.number = 0; |
| | throw new PhysicsRuntimeException($"CONTACTFULL: nconmax {Model->nconmax} isn't sufficient."); |
| | } |
| | if (Data->warning2.number > 0) { |
| | Data->warning2.number = 0; |
| | throw new PhysicsRuntimeException("CNSTRFULL: njmax {Model.njmax} isn't sufficient."); |
| | } |
| | if (Data->warning3.number > 0) { |
| | Data->warning3.number = 0; |
| | throw new PhysicsRuntimeException("VGEOMFULL: who constructed a mjvScene?!"); |
| | } |
| | if (Data->warning4.number > 0) { |
| | Data->warning4.number = 0; |
| | throw new PhysicsRuntimeException("BADQPOS: NaN/inf in qpos."); |
| | } |
| | if (Data->warning5.number > 0) { |
| | Data->warning5.number = 0; |
| | throw new PhysicsRuntimeException("BADQVEL: NaN/inf in qvel."); |
| | } |
| | if (Data->warning6.number > 0) { |
| | Data->warning6.number = 0; |
| | throw new PhysicsRuntimeException("BADQACC: NaN/inf in qacc."); |
| | } |
| | if (Data->warning7.number > 0) { |
| | Data->warning7.number = 0; |
| | throw new PhysicsRuntimeException("BADCTRL: NaN/inf in ctrl."); |
| | } |
| | } |
| |
|
| | |
| | private XmlDocument GenerateSceneMjcf(IEnumerable<MjComponent> components) { |
| | var doc = new XmlDocument(); |
| | var MjRoot = (XmlElement)doc.AppendChild(doc.CreateElement("mujoco")); |
| |
|
| | |
| | var worldMjcf = (XmlElement)MjRoot.AppendChild(doc.CreateElement("worldbody")); |
| | BuildHierarchicalMjcf( |
| | doc, |
| | components.Where(component => |
| | (component is MjBaseBody) || |
| | (component is MjInertial) || |
| | (component is MjBaseJoint) || |
| | (component is MjGeom) || |
| | (component is MjSite)), |
| | worldMjcf); |
| |
|
| | |
| | MjRoot.AppendChild(GenerateMjcfSection( |
| | doc, components.Where(component => component is MjExclude), "contact")); |
| |
|
| | MjRoot.AppendChild(GenerateMjcfSection( |
| | doc, components.Where(component => component is MjBaseTendon), "tendon")); |
| |
|
| | MjRoot.AppendChild(GenerateMjcfSection( |
| | doc, components.Where(component => component is MjBaseConstraint), "equality")); |
| |
|
| | MjRoot.AppendChild( |
| | GenerateMjcfSection(doc, |
| | components.Where(component => component is MjActuator) |
| | .OrderBy(component => component.transform.GetSiblingIndex()), |
| | "actuator")); |
| |
|
| | MjRoot.AppendChild( |
| | GenerateMjcfSection(doc, |
| | components.Where(component => component is MjBaseSensor) |
| | .OrderBy(component => component.transform.GetSiblingIndex()), |
| | "sensor")); |
| | |
| | _generationContext.GenerateMjcf(MjRoot); |
| | return doc; |
| | } |
| |
|
| | private XmlElement GenerateMjcfSection( |
| | XmlDocument doc, IEnumerable<MjComponent> components, string sectionName) { |
| | var section = doc.CreateElement(sectionName); |
| | foreach (var component in components) { |
| | var componentMjcf = component.GenerateMjcf(_generationContext.GenerateName(component), doc); |
| | section.AppendChild(componentMjcf); |
| | } |
| | return section; |
| | } |
| |
|
| | private void BuildHierarchicalMjcf( |
| | XmlDocument doc, IEnumerable<MjComponent> components, XmlElement worldMjcf) { |
| | var associations = new Dictionary<MjComponent, XmlElement>(); |
| |
|
| | |
| | foreach (var component in components) { |
| | var componentMjcf = component.GenerateMjcf( |
| | _generationContext.GenerateName(component), doc); |
| | |
| | |
| | associations.Add(component, componentMjcf); |
| | } |
| |
|
| | |
| | foreach (var component in components) { |
| | var componentMjcf = associations[component]; |
| | var parentComponent = MjHierarchyTool.FindParentComponent(component); |
| | if (parentComponent != null) { |
| | var parentComponentMjcf = associations[parentComponent]; |
| | parentComponentMjcf.AppendChild(componentMjcf); |
| | } else { |
| | worldMjcf.AppendChild(componentMjcf); |
| | } |
| | } |
| | } |
| |
|
| | |
| | private void SaveToFile(XmlDocument document, string filePath) { |
| | try { |
| | using (var stream = File.Open(filePath, FileMode.Create)) { |
| | using (var writer = new XmlTextWriter(stream, new UTF8Encoding(false))) { |
| | writer.Formatting = Formatting.Indented; |
| | document.WriteContentTo(writer); |
| | Debug.Log($"MJCF saved to {filePath}"); |
| | } |
| | } |
| | } catch (IOException ex) { |
| | Debug.LogWarning("Failed to save Xml to a file: " + ex.ToString(), this); |
| | } |
| | } |
| | } |
| |
|
| | public class MjStepArgs : EventArgs |
| | { |
| | public unsafe MjStepArgs(MujocoLib.mjModel_* model, MujocoLib.mjData_* data){ |
| | this.model = model; |
| | this.data = data; |
| | } |
| | public readonly unsafe MujocoLib.mjModel_* model; |
| | public readonly unsafe MujocoLib.mjData_* data; |
| | } |
| | } |
| |
|