From 3b491a8939736b9724fa738c51634aac251f28e2 Mon Sep 17 00:00:00 2001 From: Jonathan Embley-Riches Date: Mon, 8 Jun 2026 14:15:08 +0100 Subject: [PATCH 1/5] codegen: replace hand-rolled mjsX plumbing with snapshot-driven generator URLab's MuJoCo component layer used to hand-roll its mjsX import, spec-write, and view-bind code per class. This commit replaces that with a snapshot-driven generator under Scripts/codegen/. Pipeline: - codegen_rules.json is the editorial source of truth; it points at four JSON snapshots (MJCF schema, mjsX struct fields + mjs_setTo signatures, mjxmacro pointer tables, libclang AST scrape). - generate_ue_components.py reads rules + snapshots and emits UE C++ between explicit CODEGEN_*_START/END markers. - regen_all.py orchestrates snapshot rebuilds + the codegen pass. - URLab.Build.cs invokes generate_ue_components.py --check on every editor compile, so hand-edits inside marker regions surface as build failures rather than silent drift. Components moved to codegen ownership: Geom (+ 8 primitive subclasses via banner-mode overwrite), Site (+ 5 type subclasses), Joint (+ Hinge / Slide / Ball / Free), Body, Frame, Inertial, Camera, Sensor (+ 28 subtypes via auto-emitted type switch + TagToType map), Actuator (+ 9 subtypes via subtype_setto), Equality (+ 7 subtypes via multi_uclass + objtype_dispatch), Tendon, ContactPair, ContactExclude, Keyframe, Flexcomp, plus all seven view structs in MjBind.h and MjGeom's FinalType resolution block. Synthetic struct emission (whole file): FMjOptionGenerated (replaces FMuJoCoOptions), FMjStatistic, six FMjVisualX structs, FMjsCompilerOptions, FMjsSpec, MjOptionEnums (EMjIntegrator / Cone / Solver), MjArticulationRegistry. Spec-write helpers extracted to consolidate emission sites: MjSetDoubleVec, MjSetString, RegisterAllOf. Rule shapes introduced: fully_emitted (gated by an audit diagnostic on overwrite), objtype_dispatch (equality), geom_final_type, extra_constructor, bind_override, mjs_data_packed_attrs (slot ranges in mjsEquality.data), target_collations, subtype_setto, synthetic_categories, generated_enums, value_map_from_enum, unit_conversion (per-attr per-Type op, e.g. joint cm/deg storage), vec3_convert: y_negate (joint.axis handedness). Vendored mjspecmacro.h is pinned via sync_vendored.py + _VENDORED_FROM.md manifest and folded into mjxmacro_snapshot at build time. Test surface: ~95 pytest cases cover emission shapes, snapshot parsers, and drift internals. URLab automation expands to 207 cases; all green. docs/guides/codegen_contributors.md documents the rules shape, the snapshots, the drift gate, and the --check / --strict flags. --- Scripts/build_and_test.ps1 | 18 + Scripts/codegen/_vendored/_VENDORED_FROM.md | 17 + Scripts/codegen/_vendored/__init__.py | 12 + Scripts/codegen/_vendored/ast_nodes.py | 147 + Scripts/codegen/_vendored/mjspecmacro.h | 603 + Scripts/codegen/build_introspect_snapshot.py | 305 + Scripts/codegen/build_mjcf_schema_snapshot.py | 220 +- Scripts/codegen/build_mjspec_snapshot.py | 81 +- Scripts/codegen/build_mjxmacro_snapshot.py | 62 +- Scripts/codegen/codegen_rules.json | 567 +- Scripts/codegen/generate_ue_components.py | 1959 +- Scripts/codegen/regen_all.py | 7 +- .../snapshots/introspect_snapshot.json | 26279 ++++++++++++++++ .../snapshots}/mjcf_schema_snapshot.json | 396 +- .../snapshots}/mjspec_snapshot.json | 327 + .../snapshots}/mjxmacro_snapshot.json | 1673 +- Scripts/codegen/sync_vendored.py | 165 + Scripts/codegen/tests/conftest.py | 4 +- Scripts/codegen/tests/test_dry_run.py | 2 +- Scripts/codegen/tests/test_enum_scrape.py | 156 + .../codegen/tests/test_introspect_snapshot.py | 72 + .../codegen/tests/test_mjxmacro_snapshot.py | 128 + Scripts/codegen/tests/test_new_rule_shapes.py | 375 + .../tests/test_phase2c_capabilities.py | 192 + Scripts/codegen/tests/test_regen_no_diff.py | 39 + .../tests/test_sensor_per_type_extractor.py | 199 + .../codegen/tests/test_setto_introspection.py | 2 +- .../codegen/tests/test_subclass_emission.py | 2 +- Scripts/codegen/tests/test_sync_vendored.py | 71 + .../tests/test_synthetic_categories.py | 221 + Scripts/codegen/tests/test_view_struct.py | 56 + .../Components/Actuators/MjActuator.cpp | 64 +- .../MuJoCo/Components/Bodies/MjBody.cpp | 42 +- .../MuJoCo/Components/Bodies/MjFrame.cpp | 2 +- .../Components/Constraints/MjEquality.cpp | 6 +- .../MuJoCo/Components/Geometry/MjGeom.cpp | 58 +- .../MuJoCo/Components/Geometry/MjSite.cpp | 19 +- .../Components/Geometry/Primitives/MjBox.cpp | 6 +- .../Geometry/Primitives/MjCapsule.cpp | 4 +- .../Geometry/Primitives/MjCylinder.cpp | 4 +- .../Geometry/Primitives/MjEllipsoid.cpp | 4 +- .../Geometry/Primitives/MjPlane.cpp | 4 +- .../Components/Geometry/Primitives/MjSdf.cpp | 4 +- .../Geometry/Primitives/MjSphere.cpp | 2 +- .../MuJoCo/Components/Joints/MjBallJoint.cpp | 38 +- .../MuJoCo/Components/Joints/MjHingeJoint.cpp | 38 +- .../MuJoCo/Components/Joints/MjJoint.cpp | 94 +- .../MuJoCo/Components/Joints/MjSlideJoint.cpp | 38 +- .../Components/Keyframes/MjKeyframe.cpp | 53 +- .../Components/Physics/MjContactExclude.cpp | 25 +- .../Components/Physics/MjContactPair.cpp | 35 +- .../MuJoCo/Components/Physics/MjInertial.cpp | 3 - .../QuickConvert/AMjHeightfieldActor.cpp | 3 +- .../QuickConvert/MjQuickConvertComponent.cpp | 6 +- .../Components/Sensors/MjAccelerometer.cpp | 36 +- .../Sensors/MjActuatorFrcSensor.cpp | 36 +- .../Sensors/MjActuatorPosSensor.cpp | 36 +- .../Sensors/MjActuatorVelSensor.cpp | 36 +- .../Components/Sensors/MjBallAngVelSensor.cpp | 36 +- .../Components/Sensors/MjBallQuatSensor.cpp | 36 +- .../Sensors/MjCamProjectionSensor.cpp | 36 +- .../MuJoCo/Components/Sensors/MjCamera.cpp | 9 +- .../Components/Sensors/MjClockSensor.cpp | 36 +- .../Components/Sensors/MjContactSensor.cpp | 36 +- .../Components/Sensors/MjEKineticSensor.cpp | 36 +- .../Components/Sensors/MjEPotentialSensor.cpp | 36 +- .../Components/Sensors/MjForceSensor.cpp | 36 +- .../Sensors/MjFrameAngAccSensor.cpp | 36 +- .../Sensors/MjFrameAngVelSensor.cpp | 36 +- .../Sensors/MjFrameLinAccSensor.cpp | 36 +- .../Sensors/MjFrameLinVelSensor.cpp | 36 +- .../Components/Sensors/MjFramePosSensor.cpp | 36 +- .../Components/Sensors/MjFrameQuatSensor.cpp | 36 +- .../Components/Sensors/MjFrameXAxisSensor.cpp | 36 +- .../Components/Sensors/MjFrameYAxisSensor.cpp | 36 +- .../Components/Sensors/MjFrameZAxisSensor.cpp | 36 +- .../Components/Sensors/MjGeomDistSensor.cpp | 36 +- .../Components/Sensors/MjGeomFromToSensor.cpp | 36 +- .../Components/Sensors/MjGeomNormalSensor.cpp | 36 +- .../MuJoCo/Components/Sensors/MjGyro.cpp | 36 +- .../Components/Sensors/MjInsideSiteSensor.cpp | 36 +- .../Sensors/MjJointActFrcSensor.cpp | 36 +- .../Sensors/MjJointLimitFrcSensor.cpp | 36 +- .../Sensors/MjJointLimitPosSensor.cpp | 36 +- .../Sensors/MjJointLimitVelSensor.cpp | 36 +- .../Components/Sensors/MjJointVelSensor.cpp | 36 +- .../Components/Sensors/MjMagnetometer.cpp | 36 +- .../Components/Sensors/MjPluginSensor.cpp | 4 +- .../Sensors/MjRangeFinderSensor.cpp | 36 +- .../MuJoCo/Components/Sensors/MjSensor.cpp | 364 +- .../Sensors/MjSubtreeAngMomSensor.cpp | 36 +- .../Components/Sensors/MjSubtreeComSensor.cpp | 36 +- .../Sensors/MjSubtreeLinVelSensor.cpp | 36 +- .../Sensors/MjTendonActFrcSensor.cpp | 36 +- .../Sensors/MjTendonLimitFrcSensor.cpp | 36 +- .../Sensors/MjTendonLimitPosSensor.cpp | 36 +- .../Sensors/MjTendonLimitVelSensor.cpp | 36 +- .../Components/Sensors/MjTendonPosSensor.cpp | 36 +- .../Components/Sensors/MjTendonVelSensor.cpp | 36 +- .../Components/Sensors/MjTorqueSensor.cpp | 36 +- .../Components/Sensors/MjTouchSensor.cpp | 36 +- .../Components/Sensors/MjUserSensor.cpp | 4 +- .../Components/Sensors/MjVelocimeter.cpp | 36 +- .../MuJoCo/Components/Tendons/MjTendon.cpp | 51 +- .../Private/MuJoCo/Core/MjArticulation.cpp | 267 +- .../Private/MuJoCo/Core/MjDebugVisualizer.cpp | 4 +- .../Private/MuJoCo/Core/MjSimOptions.cpp | 142 - .../MuJoCo/Core/Spec/MjSpecWrapper.cpp | 2 +- .../MuJoCo/Generated/MjOptionGenerated.cpp | 79 + .../Generated/MjOptionGeneratedExtras.cpp | 46 + .../Private/MuJoCo/Input/MjPerturbation.cpp | 4 +- .../MuJoCo/Utils/MjOrientationUtils.cpp | 258 +- Source/URLab/Private/MuJoCo/Utils/MjUtils.cpp | 10 +- .../MuJoCo/Components/Actuators/MjActuator.h | 125 +- .../Components/Actuators/MjAdhesionActuator.h | 4 +- .../Components/Actuators/MjCylinderActuator.h | 16 +- .../Components/Actuators/MjDamperActuator.h | 4 +- .../Components/Actuators/MjDcMotorActuator.h | 36 +- .../Components/Actuators/MjGeneralActuator.h | 4 +- .../Actuators/MjIntVelocityActuator.h | 16 +- .../Components/Actuators/MjMuscleActuator.h | 40 +- .../Components/Actuators/MjPositionActuator.h | 20 +- .../Components/Actuators/MjVelocityActuator.h | 4 +- .../Public/MuJoCo/Components/Bodies/MjBody.h | 44 +- .../Public/MuJoCo/Components/Bodies/MjFrame.h | 12 +- .../Components/Constraints/MjEquality.h | 36 +- .../MuJoCo/Components/Defaults/MjDefault.h | 12 +- .../MuJoCo/Components/Deformable/MjFlexcomp.h | 80 +- .../MuJoCo/Components/Geometry/MjGeom.h | 96 +- .../MuJoCo/Components/Geometry/MjSite.h | 30 +- .../Geometry/Primitives/MjEllipsoid.h | 2 +- .../Components/Geometry/Primitives/MjPlane.h | 2 +- .../Components/Geometry/Primitives/MjSdf.h | 2 +- .../MuJoCo/Components/Joints/MjBallJoint.h | 25 +- .../MuJoCo/Components/Joints/MjHingeJoint.h | 25 +- .../Public/MuJoCo/Components/Joints/MjJoint.h | 111 +- .../MuJoCo/Components/Joints/MjSlideJoint.h | 25 +- .../MuJoCo/Components/Keyframes/MjKeyframe.h | 28 +- .../Public/MuJoCo/Components/MjComponent.h | 48 +- .../Components/Physics/MjContactExclude.h | 16 +- .../MuJoCo/Components/Physics/MjContactPair.h | 44 +- .../MuJoCo/Components/Physics/MjInertial.h | 26 +- .../Components/Sensors/MjAccelerometer.h | 25 +- .../Components/Sensors/MjActuatorFrcSensor.h | 25 +- .../Components/Sensors/MjActuatorPosSensor.h | 25 +- .../Components/Sensors/MjActuatorVelSensor.h | 25 +- .../Components/Sensors/MjBallAngVelSensor.h | 25 +- .../Components/Sensors/MjBallQuatSensor.h | 25 +- .../Sensors/MjCamProjectionSensor.h | 25 +- .../MuJoCo/Components/Sensors/MjCamera.h | 48 +- .../MuJoCo/Components/Sensors/MjClockSensor.h | 25 +- .../Components/Sensors/MjContactSensor.h | 25 +- .../Components/Sensors/MjEKineticSensor.h | 25 +- .../Components/Sensors/MjEPotentialSensor.h | 25 +- .../MuJoCo/Components/Sensors/MjForceSensor.h | 25 +- .../Components/Sensors/MjFrameAngAccSensor.h | 25 +- .../Components/Sensors/MjFrameAngVelSensor.h | 25 +- .../Components/Sensors/MjFrameLinAccSensor.h | 25 +- .../Components/Sensors/MjFrameLinVelSensor.h | 25 +- .../Components/Sensors/MjFramePosSensor.h | 25 +- .../Components/Sensors/MjFrameQuatSensor.h | 25 +- .../Components/Sensors/MjFrameXAxisSensor.h | 25 +- .../Components/Sensors/MjFrameYAxisSensor.h | 25 +- .../Components/Sensors/MjFrameZAxisSensor.h | 25 +- .../Components/Sensors/MjGeomDistSensor.h | 25 +- .../Components/Sensors/MjGeomFromToSensor.h | 25 +- .../Components/Sensors/MjGeomNormalSensor.h | 25 +- .../Public/MuJoCo/Components/Sensors/MjGyro.h | 25 +- .../Components/Sensors/MjInsideSiteSensor.h | 25 +- .../Components/Sensors/MjJointActFrcSensor.h | 25 +- .../Sensors/MjJointLimitFrcSensor.h | 25 +- .../Sensors/MjJointLimitPosSensor.h | 25 +- .../Sensors/MjJointLimitVelSensor.h | 25 +- .../Components/Sensors/MjJointVelSensor.h | 25 +- .../Components/Sensors/MjMagnetometer.h | 25 +- .../Components/Sensors/MjPluginSensor.h | 2 +- .../Components/Sensors/MjRangeFinderSensor.h | 25 +- .../MuJoCo/Components/Sensors/MjSensor.h | 30 +- .../Sensors/MjSubtreeAngMomSensor.h | 25 +- .../Components/Sensors/MjSubtreeComSensor.h | 25 +- .../Sensors/MjSubtreeLinVelSensor.h | 25 +- .../Components/Sensors/MjTendonActFrcSensor.h | 25 +- .../Sensors/MjTendonLimitFrcSensor.h | 25 +- .../Sensors/MjTendonLimitPosSensor.h | 25 +- .../Sensors/MjTendonLimitVelSensor.h | 25 +- .../Components/Sensors/MjTendonPosSensor.h | 25 +- .../Components/Sensors/MjTendonVelSensor.h | 25 +- .../Components/Sensors/MjTorqueSensor.h | 25 +- .../MuJoCo/Components/Sensors/MjTouchSensor.h | 25 +- .../MuJoCo/Components/Sensors/MjUserSensor.h | 2 +- .../MuJoCo/Components/Sensors/MjVelocimeter.h | 25 +- .../MuJoCo/Components/Tendons/MjTendon.h | 107 +- .../URLab/Public/MuJoCo/Core/MjArticulation.h | 56 +- .../Public/MuJoCo/Core/MjPhysicsEngine.h | 4 +- .../URLab/Public/MuJoCo/Core/MjSimOptions.h | 214 - .../MuJoCo/Generated/MjArticulationRegistry.h | 61 + .../Public/MuJoCo/Generated/MjOptionEnums.h | 56 + .../MuJoCo/Generated/MjOptionGenerated.h | 221 + .../Public/MuJoCo/Generated/MjStatistic.h | 81 + .../Public/MuJoCo/Generated/MjVisualGlobal.h | 135 + .../MuJoCo/Generated/MjVisualHeadlight.h | 78 + .../Public/MuJoCo/Generated/MjVisualMap.h | 135 + .../Public/MuJoCo/Generated/MjVisualQuality.h | 79 + .../Public/MuJoCo/Generated/MjVisualRgba.h | 294 + .../Public/MuJoCo/Generated/MjVisualScale.h | 163 + .../MuJoCo/Generated/MjsCompilerOptions.h | 149 + .../URLab/Public/MuJoCo/Generated/MjsSpec.h | 149 + .../URLab/Public/MuJoCo/Generated/README.md | 57 + Source/URLab/Public/MuJoCo/Utils/MjBind.h | 781 +- .../Public/MuJoCo/Utils/MjOrientationUtils.h | 13 - Source/URLab/Public/MuJoCo/Utils/MjUtils.h | 65 + Source/URLab/RobotBuilder.py | 78 - .../MjComponentDetailCustomizations.cpp | 159 +- .../Private/MujocoGenerationAction.cpp | 2 +- .../Private/Tests/MjBindingPathProbeTest.cpp | 266 + .../Private/Tests/MjBindingTest.cpp | 2 +- .../Private/Tests/MjPhysicsTests.cpp | 1 + .../Private/Tests/MjSchemaForTests.h | 4 +- Source/URLabEditor/Private/URLabEditor.cpp | 73 +- .../Public/MjComponentDetailCustomizations.h | 93 +- docs/guides/codegen_contributors.md | 108 + 221 files changed, 39428 insertions(+), 4169 deletions(-) create mode 100644 Scripts/codegen/_vendored/_VENDORED_FROM.md create mode 100644 Scripts/codegen/_vendored/__init__.py create mode 100644 Scripts/codegen/_vendored/ast_nodes.py create mode 100644 Scripts/codegen/_vendored/mjspecmacro.h create mode 100644 Scripts/codegen/build_introspect_snapshot.py create mode 100644 Scripts/codegen/snapshots/introspect_snapshot.json rename Scripts/{ => codegen/snapshots}/mjcf_schema_snapshot.json (56%) rename Scripts/{ => codegen/snapshots}/mjspec_snapshot.json (60%) rename Scripts/{ => codegen/snapshots}/mjxmacro_snapshot.json (69%) create mode 100644 Scripts/codegen/sync_vendored.py create mode 100644 Scripts/codegen/tests/test_enum_scrape.py create mode 100644 Scripts/codegen/tests/test_introspect_snapshot.py create mode 100644 Scripts/codegen/tests/test_mjxmacro_snapshot.py create mode 100644 Scripts/codegen/tests/test_new_rule_shapes.py create mode 100644 Scripts/codegen/tests/test_phase2c_capabilities.py create mode 100644 Scripts/codegen/tests/test_regen_no_diff.py create mode 100644 Scripts/codegen/tests/test_sensor_per_type_extractor.py create mode 100644 Scripts/codegen/tests/test_sync_vendored.py create mode 100644 Scripts/codegen/tests/test_synthetic_categories.py delete mode 100644 Source/URLab/Private/MuJoCo/Core/MjSimOptions.cpp create mode 100644 Source/URLab/Private/MuJoCo/Generated/MjOptionGenerated.cpp create mode 100644 Source/URLab/Private/MuJoCo/Generated/MjOptionGeneratedExtras.cpp delete mode 100644 Source/URLab/Public/MuJoCo/Core/MjSimOptions.h create mode 100644 Source/URLab/Public/MuJoCo/Generated/MjArticulationRegistry.h create mode 100644 Source/URLab/Public/MuJoCo/Generated/MjOptionEnums.h create mode 100644 Source/URLab/Public/MuJoCo/Generated/MjOptionGenerated.h create mode 100644 Source/URLab/Public/MuJoCo/Generated/MjStatistic.h create mode 100644 Source/URLab/Public/MuJoCo/Generated/MjVisualGlobal.h create mode 100644 Source/URLab/Public/MuJoCo/Generated/MjVisualHeadlight.h create mode 100644 Source/URLab/Public/MuJoCo/Generated/MjVisualMap.h create mode 100644 Source/URLab/Public/MuJoCo/Generated/MjVisualQuality.h create mode 100644 Source/URLab/Public/MuJoCo/Generated/MjVisualRgba.h create mode 100644 Source/URLab/Public/MuJoCo/Generated/MjVisualScale.h create mode 100644 Source/URLab/Public/MuJoCo/Generated/MjsCompilerOptions.h create mode 100644 Source/URLab/Public/MuJoCo/Generated/MjsSpec.h create mode 100644 Source/URLab/Public/MuJoCo/Generated/README.md delete mode 100644 Source/URLab/RobotBuilder.py create mode 100644 Source/URLabEditor/Private/Tests/MjBindingPathProbeTest.cpp create mode 100644 docs/guides/codegen_contributors.md diff --git a/Scripts/build_and_test.ps1 b/Scripts/build_and_test.ps1 index b986829..29cc343 100644 --- a/Scripts/build_and_test.ps1 +++ b/Scripts/build_and_test.ps1 @@ -66,6 +66,24 @@ $cmd = Join-Path $Engine 'Engine\Binaries\Win64\UnrealEditor-Cmd.exe' if (-not (Test-Path $bat)) { Write-Error "Build.bat not found: $bat"; exit 3 } if (-not (Test-Path $cmd)) { Write-Error "UnrealEditor-Cmd not found: $cmd"; exit 3 } +# --- Codegen drift gate ---------------------------------------------------- +# Phase 5 (D7 follow-up): refuse to build if codegen output drifted from +# the committed Source/. Catches the D4-class bug where hand-edits to +# CODEGEN-managed regions slip past the emitters. Skip silently if Python +# isn't on PATH (offline / CI without Python) — the gate is best-effort +# locally; CI enforces it strictly. +$pluginRoot = Split-Path -Parent $PSScriptRoot +$generator = Join-Path $pluginRoot 'Scripts/codegen/generate_ue_components.py' +$py = (Get-Command python -ErrorAction SilentlyContinue) +if ($py -and (Test-Path $generator)) { + Write-Host '>>> Codegen drift gate: python generate_ue_components.py --check' + & $py.Source $generator --check + if ($LASTEXITCODE -ne 0) { + Write-Error "Codegen drift detected. Re-run 'python Scripts/codegen/generate_ue_components.py' to regenerate, then re-run this script." + exit 4 + } +} + # Truncate the test log up-front so a build failure (or any early exit # before UnrealEditor-Cmd writes to it) doesn't leave the SHA-256 in the # summary pointing at a previous run's file. diff --git a/Scripts/codegen/_vendored/_VENDORED_FROM.md b/Scripts/codegen/_vendored/_VENDORED_FROM.md new file mode 100644 index 0000000..e24f132 --- /dev/null +++ b/Scripts/codegen/_vendored/_VENDORED_FROM.md @@ -0,0 +1,17 @@ +# Vendored sources + +`sync_vendored.py` reads this manifest and rewrites it deterministically +on every run (stable column order, sorted by `local_dest`). Re-running on +the same upstream SHA produces zero diff — keeps the manifest out of +merge-conflict territory. + +To bump a vendored file, edit its `upstream_sha` (or replace with `main` +for an unpinned re-fetch), then run: + +``` +python Scripts/codegen/sync_vendored.py +``` + +| file | upstream_url | upstream_sha | retrieved_date | license | local_dest | +| ---- | ------------ | ------------ | -------------- | ------- | ---------- | +| mjspecmacro.h | https://raw.githubusercontent.com/google-deepmind/mujoco/{sha}/include/mujoco/mjspecmacro.h | main | 2026-05-29 | Apache-2.0 | Scripts/codegen/_vendored/mjspecmacro.h | diff --git a/Scripts/codegen/_vendored/__init__.py b/Scripts/codegen/_vendored/__init__.py new file mode 100644 index 0000000..388c395 --- /dev/null +++ b/Scripts/codegen/_vendored/__init__.py @@ -0,0 +1,12 @@ +# Copyright (c) 2026 Jonathan Embley-Riches. All rights reserved. +""" +Vendored third-party source files needed by URLab codegen. + +Files here are auto-fetched by ``Scripts/codegen/sync_vendored.py`` from +the URLs listed in ``_VENDORED_FROM.md``. Edit those source URLs / SHAs +in the manifest; the script downloads + writes them verbatim. + +DO NOT edit the .h / .cc files in this directory by hand — they get +clobbered on the next ``sync_vendored.py`` run. URLab-side changes go +in the codegen modules that consume them. +""" diff --git a/Scripts/codegen/_vendored/ast_nodes.py b/Scripts/codegen/_vendored/ast_nodes.py new file mode 100644 index 0000000..614ff55 --- /dev/null +++ b/Scripts/codegen/_vendored/ast_nodes.py @@ -0,0 +1,147 @@ +# Copyright (c) 2026 Jonathan Embley-Riches. All rights reserved. +""" +Lightweight AST-node dataclasses used by ``build_introspect_snapshot.py`` +to project clang.cindex AST cursors into a serialisable shape. + +URLab-side rather than pulled from upstream because (a) the upstream +``clang.cindex`` types don't pickle cleanly across libclang versions and +(b) the snapshot only needs a small subset of node info. Keeping the +projection in one place means the schema is auditable from JSON, and +test fixtures can be hand-built without needing a real libclang install. +""" + +from __future__ import annotations + +from dataclasses import dataclass, field, asdict +from typing import Any, Dict, List, Optional + + +@dataclass +class CFunctionParam: + name: str + c_type: str + array_dim: Optional[int] = None # None for scalar / pointer + + def to_dict(self) -> Dict[str, Any]: + return asdict(self) + + +@dataclass +class CFunction: + name: str + return_type: str + params: List[CFunctionParam] = field(default_factory=list) + doc: str = "" + file: str = "" # source path + line: int = 0 + + def to_dict(self) -> Dict[str, Any]: + return { + "name": self.name, + "return_type": self.return_type, + "params": [p.to_dict() for p in self.params], + "doc": self.doc, + "file": self.file, + "line": self.line, + } + + +@dataclass +class CEnumMember: + name: str + value: int + doc: str = "" + + +@dataclass +class CEnum: + name: str + members: List[CEnumMember] = field(default_factory=list) + underlying_type: Optional[str] = None + doc: str = "" + file: str = "" + line: int = 0 + + def to_dict(self) -> Dict[str, Any]: + return { + "name": self.name, + "members": {m.name: m.value for m in self.members}, + "member_docs": {m.name: m.doc for m in self.members if m.doc}, + "underlying_type": self.underlying_type, + "doc": self.doc, + "file": self.file, + "line": self.line, + } + + +@dataclass +class CStructField: + name: str + c_type: str + array_dim: Optional[int] = None + is_pointer: bool = False + doc: str = "" + + +@dataclass +class CStruct: + name: str + fields: List[CStructField] = field(default_factory=list) + doc: str = "" + file: str = "" + line: int = 0 + + def to_dict(self) -> Dict[str, Any]: + return { + "name": self.name, + "fields": [ + { + "name": f.name, + "c_type": f.c_type, + "array_dim": f.array_dim, + "is_pointer": f.is_pointer, + "doc": f.doc, + } + for f in self.fields + ], + "doc": self.doc, + "file": self.file, + "line": self.line, + } + + +@dataclass +class CDefine: + name: str + value: str + doc: str = "" + file: str = "" + line: int = 0 + + +@dataclass +class IntrospectSnapshot: + """Top-level container for the clang-AST scrape output. Serialised + to ``Scripts/introspect_snapshot.json``. snapshot_version bumps on + schema-incompatible changes.""" + snapshot_version: int = 1 + header_hash: str = "" + functions: Dict[str, CFunction] = field(default_factory=dict) + enums: Dict[str, CEnum] = field(default_factory=dict) + structs: Dict[str, CStruct] = field(default_factory=dict) + defines: Dict[str, CDefine] = field(default_factory=dict) + + def to_dict(self) -> Dict[str, Any]: + return { + "_meta": { + "snapshot_version": self.snapshot_version, + "header_hash": self.header_hash, + }, + "functions": {n: f.to_dict() for n, f in self.functions.items()}, + "enums": {n: e.to_dict() for n, e in self.enums.items()}, + "structs": {n: s.to_dict() for n, s in self.structs.items()}, + "defines": { + n: {"value": d.value, "doc": d.doc, "file": d.file, "line": d.line} + for n, d in self.defines.items() + }, + } diff --git a/Scripts/codegen/_vendored/mjspecmacro.h b/Scripts/codegen/_vendored/mjspecmacro.h new file mode 100644 index 0000000..81e861e --- /dev/null +++ b/Scripts/codegen/_vendored/mjspecmacro.h @@ -0,0 +1,603 @@ +// Copyright 2026 DeepMind Technologies Limited +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef MUJOCO_MJSPECMACRO_H_ +#define MUJOCO_MJSPECMACRO_H_ + + +//-------------------------------- mjsElement ------------------------------------------------------ + +#define MJSELEMENT_FIELDS \ + X( mjtObj, elemtype, 1 ) \ + X( uint64_t, signature, 1 ) + + +//-------------------------------- mjsCompiler ----------------------------------------------------- + +#define MJSCOMPILER_FIELDS \ + X ( mjtByte, autolimits, 1 ) \ + X ( double, boundmass, 1 ) \ + X ( double, boundinertia, 1 ) \ + X ( double, settotalmass, 1 ) \ + X ( mjtByte, balanceinertia, 1 ) \ + X ( mjtByte, fitaabb, 1 ) \ + X ( mjtByte, degree, 1 ) \ + XVEC( char, eulerseq, 3 ) \ + X ( mjtByte, discardvisual, 1 ) \ + X ( mjtByte, usethread, 1 ) \ + X ( mjtByte, fusestatic, 1 ) \ + X ( int, inertiafromgeom, 1 ) \ + XVEC( int, inertiagrouprange, 2 ) \ + X ( mjtByte, saveinertial, 1 ) \ + X ( int, alignfree, 1 ) \ + X ( mjLROpt, LRopt, 1 ) \ + X ( mjString*, meshdir, 1 ) \ + X ( mjString*, texturedir, 1 ) + + +//-------------------------------- mjSpec ---------------------------------------------------------- + +#define MJSPEC_FIELDS \ + X( mjsElement*, element, 1 ) \ + X( mjString*, modelname, 1 ) \ + X( mjsCompiler, compiler, 1 ) \ + X( mjtByte, strippath, 1 ) \ + X( mjOption, option, 1 ) \ + X( mjVisual, visual, 1 ) \ + X( mjStatistic, stat, 1 ) \ + X( mjtSize, memory, 1 ) \ + X( int, nemax, 1 ) \ + X( int, nuserdata, 1 ) \ + X( int, nuser_body, 1 ) \ + X( int, nuser_jnt, 1 ) \ + X( int, nuser_geom, 1 ) \ + X( int, nuser_site, 1 ) \ + X( int, nuser_cam, 1 ) \ + X( int, nuser_tendon, 1 ) \ + X( int, nuser_actuator, 1 ) \ + X( int, nuser_sensor, 1 ) \ + X( int, nkey, 1 ) \ + X( int, njmax, 1 ) \ + X( int, nconmax, 1 ) \ + X( mjtSize, nstack, 1 ) \ + X( mjString*, comment, 1 ) \ + X( mjString*, modelfiledir, 1 ) \ + X( mjtByte, hasImplicitPluginElem, 1 ) + + +//-------------------------------- mjsOrientation -------------------------------------------------- + +#define MJSORIENTATION_FIELDS \ + X ( mjtOrientation, type, 1 ) \ + XVEC( double, axisangle, 4 ) \ + XVEC( double, xyaxes, 6 ) \ + XVEC( double, zaxis, 3 ) \ + XVEC( double, euler, 3 ) + + +//-------------------------------- mjsPlugin ------------------------------------------------------- + +#define MJSPLUGIN_FIELDS \ + X( mjsElement*, element, 1 ) \ + X( mjString*, name, 1 ) \ + X( mjString*, plugin_name, 1 ) \ + X( mjtByte, active, 1 ) \ + X( mjString*, info, 1 ) + + +//-------------------------------- mjsBody --------------------------------------------------------- + +#define MJSBODY_FIELDS \ + X ( mjsElement*, element, 1 ) \ + X ( mjString*, childclass, 1 ) \ + XVEC( double, pos, 3 ) \ + XVEC( double, quat, 4 ) \ + X ( mjsOrientation, alt, 1 ) \ + X ( double, mass, 1 ) \ + XVEC( double, ipos, 3 ) \ + XVEC( double, iquat, 4 ) \ + XVEC( double, inertia, 3 ) \ + X ( mjsOrientation, ialt, 1 ) \ + XVEC( double, fullinertia, 6 ) \ + X ( mjtByte, mocap, 1 ) \ + X ( double, gravcomp, 1 ) \ + X ( mjtSleepPolicy, sleep, 1 ) \ + X ( mjDoubleVec*, userdata, 1 ) \ + X ( mjtByte, explicitinertial, 1 ) \ + X ( mjsPlugin, plugin, 1 ) \ + X ( mjString*, info, 1 ) + + +//-------------------------------- mjsFrame -------------------------------------------------------- + +#define MJSFRAME_FIELDS \ + X ( mjsElement*, element, 1 ) \ + X ( mjString*, childclass, 1 ) \ + XVEC( double, pos, 3 ) \ + XVEC( double, quat, 4 ) \ + X ( mjsOrientation, alt, 1 ) \ + X ( mjString*, info, 1 ) + + +//-------------------------------- mjsJoint -------------------------------------------------------- + +#define MJSJOINT_FIELDS \ + X ( mjsElement*, element, 1 ) \ + X ( mjtJoint, type, 1 ) \ + XVEC( double, pos, 3 ) \ + XVEC( double, axis, 3 ) \ + X ( double, ref, 1 ) \ + X ( int, align, 1 ) \ + XVEC( double, stiffness, mjNPOLY+1 ) \ + X ( double, springref, 1 ) \ + XVEC( double, springdamper, 2 ) \ + X ( int, limited, 1 ) \ + XVEC( double, range, 2 ) \ + X ( double, margin, 1 ) \ + XVEC( mjtNum, solref_limit, mjNREF ) \ + XVEC( mjtNum, solimp_limit, mjNIMP ) \ + X ( int, actfrclimited, 1 ) \ + XVEC( double, actfrcrange, 2 ) \ + X ( double, armature, 1 ) \ + XVEC( double, damping, mjNPOLY+1 ) \ + X ( double, frictionloss, 1 ) \ + XVEC( mjtNum, solref_friction, mjNREF ) \ + XVEC( mjtNum, solimp_friction, mjNIMP ) \ + X ( int, group, 1 ) \ + X ( mjtByte, actgravcomp, 1 ) \ + X ( mjDoubleVec*, userdata, 1 ) \ + X ( mjString*, info, 1 ) + + +//-------------------------------- mjsGeom --------------------------------------------------------- + +#define MJSGEOM_FIELDS \ + X ( mjsElement*, element, 1 ) \ + X ( mjtGeom, type, 1 ) \ + XVEC( double, pos, 3 ) \ + XVEC( double, quat, 4 ) \ + X ( mjsOrientation, alt, 1 ) \ + XVEC( double, fromto, 6 ) \ + XVEC( double, size, 3 ) \ + X ( int, contype, 1 ) \ + X ( int, conaffinity, 1 ) \ + X ( int, condim, 1 ) \ + X ( int, priority, 1 ) \ + XVEC( double, friction, 3 ) \ + X ( double, solmix, 1 ) \ + XVEC( mjtNum, solref, mjNREF ) \ + XVEC( mjtNum, solimp, mjNIMP ) \ + X ( double, margin, 1 ) \ + X ( double, gap, 1 ) \ + X ( double, mass, 1 ) \ + X ( double, density, 1 ) \ + X ( mjtGeomInertia, typeinertia, 1 ) \ + X ( mjtNum, fluid_ellipsoid, 1 ) \ + XVEC( mjtNum, fluid_coefs, 5 ) \ + X ( mjString*, material, 1 ) \ + XVEC( float, rgba, 4 ) \ + X ( int, group, 1 ) \ + X ( mjString*, hfieldname, 1 ) \ + X ( mjString*, meshname, 1 ) \ + X ( double, fitscale, 1 ) \ + X ( mjDoubleVec*, userdata, 1 ) \ + X ( mjsPlugin, plugin, 1 ) \ + X ( mjString*, info, 1 ) + + +//-------------------------------- mjsSite --------------------------------------------------------- + +#define MJSSITE_FIELDS \ + X ( mjsElement*, element, 1 ) \ + XVEC( double, pos, 3 ) \ + XVEC( double, quat, 4 ) \ + X ( mjsOrientation, alt, 1 ) \ + XVEC( double, fromto, 6 ) \ + XVEC( double, size, 3 ) \ + X ( mjtGeom, type, 1 ) \ + X ( mjString*, material, 1 ) \ + X ( int, group, 1 ) \ + XVEC( float, rgba, 4 ) \ + X ( mjDoubleVec*, userdata, 1 ) \ + X ( mjString*, info, 1 ) + + +//-------------------------------- mjsCamera ------------------------------------------------------- + +#define MJSCAMERA_FIELDS \ + X ( mjsElement*, element, 1 ) \ + XVEC( double, pos, 3 ) \ + XVEC( double, quat, 4 ) \ + X ( mjsOrientation, alt, 1 ) \ + X ( mjtCamLight, mode, 1 ) \ + X ( mjString*, targetbody, 1 ) \ + X ( mjtProjection, proj, 1 ) \ + XVEC( int, resolution, 2 ) \ + X ( int, output, 1 ) \ + X ( double, fovy, 1 ) \ + X ( double, ipd, 1 ) \ + XVEC( float, intrinsic, 4 ) \ + XVEC( float, sensor_size, 2 ) \ + XVEC( float, focal_length, 2 ) \ + XVEC( float, focal_pixel, 2 ) \ + XVEC( float, principal_length, 2 ) \ + XVEC( float, principal_pixel, 2 ) \ + X ( mjDoubleVec*, userdata, 1 ) \ + X ( mjString*, info, 1 ) + + +//-------------------------------- mjsLight -------------------------------------------------------- + +#define MJSLIGHT_FIELDS \ + X ( mjsElement*, element, 1 ) \ + XVEC( double, pos, 3 ) \ + XVEC( double, dir, 3 ) \ + X ( mjtCamLight, mode, 1 ) \ + X ( mjString*, targetbody, 1 ) \ + X ( mjtByte, active, 1 ) \ + X ( mjtLightType, type, 1 ) \ + X ( mjString*, texture, 1 ) \ + X ( mjtByte, castshadow, 1 ) \ + X ( float, bulbradius, 1 ) \ + X ( float, intensity, 1 ) \ + X ( float, range, 1 ) \ + XVEC( float, attenuation, 3 ) \ + X ( float, cutoff, 1 ) \ + X ( float, exponent, 1 ) \ + XVEC( float, ambient, 3 ) \ + XVEC( float, diffuse, 3 ) \ + XVEC( float, specular, 3 ) \ + X ( mjString*, info, 1 ) + + +//-------------------------------- mjsFlex --------------------------------------------------------- + +#define MJSFLEX_FIELDS \ + X ( mjsElement*, element, 1 ) \ + X ( int, contype, 1 ) \ + X ( int, conaffinity, 1 ) \ + X ( int, condim, 1 ) \ + X ( int, priority, 1 ) \ + XVEC( double, friction, 3 ) \ + X ( double, solmix, 1 ) \ + XVEC( mjtNum, solref, mjNREF ) \ + XVEC( mjtNum, solimp, mjNIMP ) \ + X ( double, margin, 1 ) \ + X ( double, gap, 1 ) \ + X ( int, dim, 1 ) \ + X ( double, radius, 1 ) \ + XVEC( double, size, 3 ) \ + X ( mjtByte, internal, 1 ) \ + X ( mjtByte, flatskin, 1 ) \ + X ( int, selfcollide, 1 ) \ + X ( int, passive, 1 ) \ + X ( int, activelayers, 1 ) \ + X ( int, group, 1 ) \ + X ( double, edgestiffness, 1 ) \ + X ( double, edgedamping, 1 ) \ + XVEC( float, rgba, 4 ) \ + X ( mjString*, material, 1 ) \ + X ( double, young, 1 ) \ + X ( double, poisson, 1 ) \ + X ( double, damping, 1 ) \ + X ( double, thickness, 1 ) \ + X ( int, elastic2d, 1 ) \ + XVEC( int, cellcount, 3 ) \ + X ( int, order, 1 ) \ + X ( mjStringVec*, nodebody, 1 ) \ + X ( mjStringVec*, vertbody, 1 ) \ + X ( mjDoubleVec*, node, 1 ) \ + X ( mjDoubleVec*, vert, 1 ) \ + X ( mjIntVec*, elem, 1 ) \ + X ( mjFloatVec*, texcoord, 1 ) \ + X ( mjIntVec*, elemtexcoord, 1 ) \ + X ( mjString*, info, 1 ) + + +//-------------------------------- mjsMesh --------------------------------------------------------- + +#define MJSMESH_FIELDS \ + X ( mjsElement*, element, 1 ) \ + X ( mjString*, content_type, 1 ) \ + X ( mjString*, file, 1 ) \ + XVEC( double, refpos, 3 ) \ + XVEC( double, refquat, 4 ) \ + XVEC( double, scale, 3 ) \ + X ( mjtMeshInertia, inertia, 1 ) \ + X ( mjtByte, smoothnormal, 1 ) \ + X ( mjtByte, needsdf, 1 ) \ + X ( int, maxhullvert, 1 ) \ + X ( mjFloatVec*, uservert, 1 ) \ + X ( mjFloatVec*, usernormal, 1 ) \ + X ( mjFloatVec*, usertexcoord, 1 ) \ + X ( mjIntVec*, userface, 1 ) \ + X ( mjIntVec*, userfacenormal, 1 ) \ + X ( mjIntVec*, userfacetexcoord, 1 ) \ + X ( mjsPlugin, plugin, 1 ) \ + X ( mjString*, material, 1 ) \ + X ( int, octree_maxdepth, 1 ) \ + X ( mjString*, info, 1 ) + + +//-------------------------------- mjsHField ------------------------------------------------------- + +#define MJSHFIELD_FIELDS \ + X ( mjsElement*, element, 1 ) \ + X ( mjString*, content_type, 1 ) \ + X ( mjString*, file, 1 ) \ + XVEC( double, size, 4 ) \ + X ( int, nrow, 1 ) \ + X ( int, ncol, 1 ) \ + X ( mjFloatVec*, userdata, 1 ) \ + X ( mjString*, info, 1 ) + + +//-------------------------------- mjsSkin --------------------------------------------------------- + +#define MJSSKIN_FIELDS \ + X ( mjsElement*, element, 1 ) \ + X ( mjString*, file, 1 ) \ + X ( mjString*, material, 1 ) \ + XVEC( float, rgba, 4 ) \ + X ( float, inflate, 1 ) \ + X ( int, group, 1 ) \ + X ( mjFloatVec*, vert, 1 ) \ + X ( mjFloatVec*, texcoord, 1 ) \ + X ( mjIntVec*, face, 1 ) \ + X ( mjStringVec*, bodyname, 1 ) \ + X ( mjFloatVec*, bindpos, 1 ) \ + X ( mjFloatVec*, bindquat, 1 ) \ + X ( mjIntVecVec*, vertid, 1 ) \ + X ( mjFloatVecVec*, vertweight, 1 ) \ + X ( mjString*, info, 1 ) + + +//-------------------------------- mjsTexture ------------------------------------------------------ + +#define MJSTEXTURE_FIELDS \ + X ( mjsElement*, element, 1 ) \ + X ( mjtTexture, type, 1 ) \ + X ( mjtColorSpace, colorspace, 1 ) \ + X ( int, builtin, 1 ) \ + X ( int, mark, 1 ) \ + XVEC( double, rgb1, 3 ) \ + XVEC( double, rgb2, 3 ) \ + XVEC( double, markrgb, 3 ) \ + X ( double, random, 1 ) \ + X ( int, height, 1 ) \ + X ( int, width, 1 ) \ + X ( int, nchannel, 1 ) \ + X ( mjString*, content_type, 1 ) \ + X ( mjString*, file, 1 ) \ + XVEC( int, gridsize, 2 ) \ + XVEC( char, gridlayout, 12 ) \ + X ( mjStringVec*, cubefiles, 1 ) \ + X ( mjByteVec*, data, 1 ) \ + X ( mjtByte, hflip, 1 ) \ + X ( mjtByte, vflip, 1 ) \ + X ( mjString*, info, 1 ) + + +//-------------------------------- mjsMaterial ----------------------------------------------------- + +#define MJSMATERIAL_FIELDS \ + X ( mjsElement*, element, 1 ) \ + X ( mjStringVec*, textures, 1 ) \ + X ( mjtByte, texuniform, 1 ) \ + XVEC( float, texrepeat, 2 ) \ + X ( float, emission, 1 ) \ + X ( float, specular, 1 ) \ + X ( float, shininess, 1 ) \ + X ( float, reflectance, 1 ) \ + X ( float, metallic, 1 ) \ + X ( float, roughness, 1 ) \ + XVEC( float, rgba, 4 ) \ + X ( mjString*, info, 1 ) + + +//-------------------------------- mjsPair --------------------------------------------------------- + +#define MJSPAIR_FIELDS \ + X ( mjsElement*, element, 1 ) \ + X ( mjString*, geomname1, 1 ) \ + X ( mjString*, geomname2, 1 ) \ + X ( int, condim, 1 ) \ + XVEC( mjtNum, solref, mjNREF ) \ + XVEC( mjtNum, solreffriction, mjNREF ) \ + XVEC( mjtNum, solimp, mjNIMP ) \ + X ( double, margin, 1 ) \ + X ( double, gap, 1 ) \ + XVEC( double, friction, 5 ) \ + X ( mjString*, info, 1 ) + + +//-------------------------------- mjsExclude ------------------------------------------------------ + +#define MJSEXCLUDE_FIELDS \ + X( mjsElement*, element, 1 ) \ + X( mjString*, bodyname1, 1 ) \ + X( mjString*, bodyname2, 1 ) \ + X( mjString*, info, 1 ) + + +//-------------------------------- mjsEquality ----------------------------------------------------- + +#define MJSEQUALITY_FIELDS \ + X ( mjsElement*, element, 1 ) \ + X ( mjtEq, type, 1 ) \ + XVEC( double, data, mjNEQDATA ) \ + X ( mjtByte, active, 1 ) \ + X ( mjString*, name1, 1 ) \ + X ( mjString*, name2, 1 ) \ + X ( mjtObj, objtype, 1 ) \ + XVEC( mjtNum, solref, mjNREF ) \ + XVEC( mjtNum, solimp, mjNIMP ) \ + X ( mjString*, info, 1 ) + + +//-------------------------------- mjsTendon ------------------------------------------------------- + +#define MJSTENDON_FIELDS \ + X ( mjsElement*, element, 1 ) \ + XVEC( double, stiffness, mjNPOLY+1 ) \ + XVEC( double, springlength, 2 ) \ + XVEC( double, damping, mjNPOLY+1 ) \ + X ( double, frictionloss, 1 ) \ + XVEC( mjtNum, solref_friction, mjNREF ) \ + XVEC( mjtNum, solimp_friction, mjNIMP ) \ + X ( double, armature, 1 ) \ + X ( int, limited, 1 ) \ + X ( int, actfrclimited, 1 ) \ + XVEC( double, range, 2 ) \ + XVEC( double, actfrcrange, 2 ) \ + X ( double, margin, 1 ) \ + XVEC( mjtNum, solref_limit, mjNREF ) \ + XVEC( mjtNum, solimp_limit, mjNIMP ) \ + X ( mjString*, material, 1 ) \ + X ( double, width, 1 ) \ + XVEC( float, rgba, 4 ) \ + X ( int, group, 1 ) \ + X ( mjDoubleVec*, userdata, 1 ) \ + X ( mjString*, info, 1 ) + + +//-------------------------------- mjsWrap --------------------------------------------------------- + +#define MJSWRAP_FIELDS \ + X( mjsElement*, element, 1 ) \ + X( mjtWrap, type, 1 ) \ + X( mjString*, info, 1 ) + + +//-------------------------------- mjsActuator ----------------------------------------------------- + +#define MJSACTUATOR_FIELDS \ + X ( mjsElement*, element, 1 ) \ + X ( mjtGain, gaintype, 1 ) \ + XVEC( double, gainprm, mjNGAIN ) \ + X ( mjtBias, biastype, 1 ) \ + XVEC( double, biasprm, mjNGAIN ) \ + X ( mjtDyn, dyntype, 1 ) \ + XVEC( double, dynprm, mjNDYN ) \ + X ( int, actdim, 1 ) \ + X ( mjtByte, actearly, 1 ) \ + X ( mjtTrn, trntype, 1 ) \ + XVEC( double, gear, 6 ) \ + X ( mjString*, target, 1 ) \ + X ( mjString*, refsite, 1 ) \ + X ( mjString*, slidersite, 1 ) \ + X ( double, cranklength, 1 ) \ + XVEC( double, lengthrange, 2 ) \ + X ( double, inheritrange, 1 ) \ + XVEC( double, damping, mjNPOLY+1 ) \ + X ( double, armature, 1 ) \ + X ( int, ctrllimited, 1 ) \ + XVEC( double, ctrlrange, 2 ) \ + X ( int, forcelimited, 1 ) \ + XVEC( double, forcerange, 2 ) \ + X ( int, actlimited, 1 ) \ + XVEC( double, actrange, 2 ) \ + X ( int, group, 1 ) \ + X ( int, nsample, 1 ) \ + X ( int, interp, 1 ) \ + X ( double, delay, 1 ) \ + X ( mjDoubleVec*, userdata, 1 ) \ + X ( mjsPlugin, plugin, 1 ) \ + X ( mjString*, info, 1 ) + + +//-------------------------------- mjsSensor ------------------------------------------------------- + +#define MJSSENSOR_FIELDS \ + X ( mjsElement*, element, 1 ) \ + X ( mjtSensor, type, 1 ) \ + X ( mjtObj, objtype, 1 ) \ + X ( mjString*, objname, 1 ) \ + X ( mjtObj, reftype, 1 ) \ + X ( mjString*, refname, 1 ) \ + XVEC( int, intprm, mjNSENS ) \ + X ( mjtDataType, datatype, 1 ) \ + X ( mjtStage, needstage, 1 ) \ + X ( int, dim, 1 ) \ + X ( double, cutoff, 1 ) \ + X ( double, noise, 1 ) \ + X ( int, nsample, 1 ) \ + X ( int, interp, 1 ) \ + X ( double, delay, 1 ) \ + XVEC( double, interval, 2 ) \ + X ( mjDoubleVec*, userdata, 1 ) \ + X ( mjsPlugin, plugin, 1 ) \ + X ( mjString*, info, 1 ) + + +//-------------------------------- mjsNumeric ------------------------------------------------------ + +#define MJSNUMERIC_FIELDS \ + X( mjsElement*, element, 1 ) \ + X( mjDoubleVec*, data, 1 ) \ + X( int, size, 1 ) \ + X( mjString*, info, 1 ) + + +//-------------------------------- mjsText --------------------------------------------------------- + +#define MJSTEXT_FIELDS \ + X( mjsElement*, element, 1 ) \ + X( mjString*, data, 1 ) \ + X( mjString*, info, 1 ) + + +//-------------------------------- mjsTuple -------------------------------------------------------- + +#define MJSTUPLE_FIELDS \ + X( mjsElement*, element, 1 ) \ + X( mjIntVec*, objtype, 1 ) \ + X( mjStringVec*, objname, 1 ) \ + X( mjDoubleVec*, objprm, 1 ) \ + X( mjString*, info, 1 ) + + +//-------------------------------- mjsKey ---------------------------------------------------------- + +#define MJSKEY_FIELDS \ + X( mjsElement*, element, 1 ) \ + X( double, time, 1 ) \ + X( mjDoubleVec*, qpos, 1 ) \ + X( mjDoubleVec*, qvel, 1 ) \ + X( mjDoubleVec*, act, 1 ) \ + X( mjDoubleVec*, mpos, 1 ) \ + X( mjDoubleVec*, mquat, 1 ) \ + X( mjDoubleVec*, ctrl, 1 ) \ + X( mjString*, info, 1 ) + + +//-------------------------------- mjsDefault ------------------------------------------------------ + +#define MJSDEFAULT_FIELDS \ + X( mjsElement*, element, 1 ) \ + X( mjsJoint*, joint, 1 ) \ + X( mjsGeom*, geom, 1 ) \ + X( mjsSite*, site, 1 ) \ + X( mjsCamera*, camera, 1 ) \ + X( mjsLight*, light, 1 ) \ + X( mjsFlex*, flex, 1 ) \ + X( mjsMesh*, mesh, 1 ) \ + X( mjsMaterial*, material, 1 ) \ + X( mjsPair*, pair, 1 ) \ + X( mjsEquality*, equality, 1 ) \ + X( mjsTendon*, tendon, 1 ) \ + X( mjsActuator*, actuator, 1 ) + + +#endif // MUJOCO_MJSPECMACRO_H_ diff --git a/Scripts/codegen/build_introspect_snapshot.py b/Scripts/codegen/build_introspect_snapshot.py new file mode 100644 index 0000000..27b94a7 --- /dev/null +++ b/Scripts/codegen/build_introspect_snapshot.py @@ -0,0 +1,305 @@ +# Copyright (c) 2026 Jonathan Embley-Riches. All rights reserved. +""" +clang.cindex-based scrape of MuJoCo headers (mjspec.h + mjmodel.h + +optionally the vendored mjspecmacro.h) into ``Scripts/introspect_snapshot.json``. + +This is the canonical Phase 2d-3 output that replaces / supersedes the +regex-based mjspec_snapshot.json once consumers migrate. Until then +both snapshots coexist and ``generate_ue_components.py`` reads whichever +is present. + +Captures: +- function signatures (every MJAPI-tagged declaration in the headers) +- enum decls with values + per-member doc comments +- struct decls with fields + per-field doc comments + array dims +- ``#define`` constants (after preprocessor evaluation when literal) + +Usage: + python Scripts/codegen/build_introspect_snapshot.py + [--mujoco-include /path/to/mujoco/include] + [--output Scripts/introspect_snapshot.json] + [--libclang /path/to/libclang.dll] (only if not auto-found) + +libclang resolution: respects ``$LIBCLANG_LIBRARY_FILE`` env var; falls +back to clang.cindex's default search. Set ``--libclang`` to override. +""" + +from __future__ import annotations + +import argparse +import hashlib +import json +import os +import sys +from typing import List + +_HERE = os.path.dirname(os.path.abspath(__file__)) +_PLUGIN_ROOT = os.path.normpath(os.path.join(_HERE, "..", "..")) + +# Use the local vendored ast_nodes copy. +sys.path.insert(0, os.path.join(_HERE, "_vendored")) +from ast_nodes import ( # noqa: E402 + CFunction, + CFunctionParam, + CEnum, + CEnumMember, + CStruct, + CStructField, + CDefine, + IntrospectSnapshot, +) + + +def _header_hash(paths: List[str]) -> str: + """SHA-256 of the concatenated header content. Lets callers skip + re-running the snapshot when nothing upstream changed.""" + h = hashlib.sha256() + for p in sorted(paths): + if not os.path.exists(p): + continue + with open(p, "rb") as f: + h.update(f.read()) + return h.hexdigest() + + +def _strip_doc(raw: str) -> str: + """Collapse a libclang raw doc comment into one line, stripping + leading ``//`` / ``/*`` decoration.""" + if not raw: + return "" + out_lines: List[str] = [] + for line in raw.splitlines(): + s = line.strip() + for prefix in ("///", "//!", "//", "/**", "*/", "*", "/*"): + if s.startswith(prefix): + s = s[len(prefix):].strip() + break + if s.endswith("*/"): + s = s[:-2].strip() + if s: + out_lines.append(s) + return " ".join(out_lines) + + +def _walk(tu, mujoco_include: str, snapshot: IntrospectSnapshot) -> None: + """Visit every cursor in the translation unit. ``mujoco_include`` is + the include root; we only capture decls whose file lives under it + (so libc / Windows SDK / TinyXML noise is filtered out).""" + import clang.cindex as cx # noqa: E402, local-only + + def _normalised_path(loc) -> str: + if not loc or not loc.file: + return "" + return os.path.normcase(os.path.abspath(loc.file.name)) + + norm_root = os.path.normcase(os.path.abspath(mujoco_include)) + + for cursor in tu.cursor.get_children(): + fp = _normalised_path(cursor.location) + if not fp.startswith(norm_root): + continue + + kind = cursor.kind + + if kind == cx.CursorKind.FUNCTION_DECL: + params: List[CFunctionParam] = [] + for arg in cursor.get_arguments(): + t = arg.type.spelling + dim = None + if "[" in t and "]" in t: + # e.g. "double [4]" -> dim=4 + try: + dim_str = t[t.index("[") + 1:t.index("]")] + if dim_str.strip().isdigit(): + dim = int(dim_str) + except ValueError: + pass + params.append(CFunctionParam( + name=arg.spelling, c_type=t, array_dim=dim, + )) + fn = CFunction( + name=cursor.spelling, + return_type=cursor.result_type.spelling, + params=params, + doc=_strip_doc(cursor.raw_comment or ""), + file=fp, + line=cursor.location.line if cursor.location else 0, + ) + snapshot.functions[fn.name] = fn + + elif kind == cx.CursorKind.ENUM_DECL: + # Anonymous enums get spelling = "" — skip; we only want + # named typedef enums. The C tag name is ``mjtJoint_`` but + # callers reference the typedef ``mjtJoint``; normalise here. + name = cursor.spelling or cursor.type.spelling + if not name or name.startswith("(anonymous"): + continue + if name.endswith("_"): + name = name[:-1] + members: List[CEnumMember] = [] + for child in cursor.get_children(): + if child.kind == cx.CursorKind.ENUM_CONSTANT_DECL: + members.append(CEnumMember( + name=child.spelling, + value=child.enum_value, + doc=_strip_doc(child.raw_comment or ""), + )) + underlying = cursor.enum_type.spelling if cursor.enum_type else None + snapshot.enums[name] = CEnum( + name=name, members=members, + underlying_type=underlying, + doc=_strip_doc(cursor.raw_comment or ""), + file=fp, + line=cursor.location.line if cursor.location else 0, + ) + + elif kind == cx.CursorKind.STRUCT_DECL: + name = cursor.spelling or cursor.type.spelling + if not name: + continue + # Strip trailing underscore from C tag names ("mjsBody_" -> "mjsBody"). + if name.endswith("_"): + name = name[:-1] + fields: List[CStructField] = [] + for child in cursor.get_children(): + if child.kind != cx.CursorKind.FIELD_DECL: + continue + t = child.type.spelling + dim = None + is_ptr = "*" in t + if "[" in t and "]" in t: + try: + dim_str = t[t.index("[") + 1:t.index("]")] + if dim_str.strip().isdigit(): + dim = int(dim_str) + except ValueError: + pass + fields.append(CStructField( + name=child.spelling, + c_type=t, + array_dim=dim, + is_pointer=is_ptr, + doc=_strip_doc(child.raw_comment or ""), + )) + snapshot.structs[name] = CStruct( + name=name, fields=fields, + doc=_strip_doc(cursor.raw_comment or ""), + file=fp, + line=cursor.location.line if cursor.location else 0, + ) + + elif kind == cx.CursorKind.MACRO_DEFINITION: + name = cursor.spelling + # Skip function-like macros; libclang doesn't expand them. + # Skip header guards. + if name.endswith("_H_") or name.startswith("__"): + continue + # Extract tokens between the cursor's extent to get the value. + tokens = list(tu.get_tokens(extent=cursor.extent)) + if len(tokens) < 2: + continue + value = " ".join(t.spelling for t in tokens[1:]) + snapshot.defines[name] = CDefine( + name=name, value=value, + doc=_strip_doc(cursor.raw_comment or ""), + file=fp, + line=cursor.location.line if cursor.location else 0, + ) + + +def main(argv: List[str] | None = None) -> int: + ap = argparse.ArgumentParser(description=__doc__) + ap.add_argument("--mujoco-include", default=os.path.join( + _PLUGIN_ROOT, "third_party", "install", "MuJoCo", "include", + )) + ap.add_argument("--output", default=os.path.join( + _PLUGIN_ROOT, "Scripts", "codegen", "snapshots", "introspect_snapshot.json", + )) + ap.add_argument("--libclang", default=None, + help="path to libclang.dll/.so/.dylib; overrides auto-detect") + args = ap.parse_args(argv) + + try: + import clang.cindex as cx + except ImportError: + print("ERROR: clang.cindex not installed. Run " + "`uv run --with libclang python build_introspect_snapshot.py` " + "or `pip install libclang`.", file=sys.stderr) + return 1 + + if args.libclang: + cx.Config.set_library_file(args.libclang) + elif os.environ.get("LIBCLANG_LIBRARY_FILE"): + cx.Config.set_library_file(os.environ["LIBCLANG_LIBRARY_FILE"]) + + mujoco_include = args.mujoco_include + if not os.path.exists(mujoco_include): + print(f"ERROR: --mujoco-include not found: {mujoco_include}", file=sys.stderr) + return 2 + + mjspec_h = os.path.join(mujoco_include, "mujoco", "mjspec.h") + mjmodel_h = os.path.join(mujoco_include, "mujoco", "mjmodel.h") + mjxmacro_h = os.path.join(mujoco_include, "mujoco", "mjxmacro.h") + + # Vendored mjspecmacro.h (only used if non-stub; sync_vendored.py + # fills it from upstream). + vendored_mjspecmacro = os.path.join(_HERE, "_vendored", "mjspecmacro.h") + + # Synthesize a small dispatch source that #includes the headers we + # care about. Letting clang chew on a real .c lets it resolve types + # without us threading -include flags. + dispatch_c = "\n".join([ + "#include ", + "#include ", + "#include ", + "#include ", + ]) + args_clang = [ + "-x", "c", + "-std=c11", + f"-I{mujoco_include}", + "-DMJ_STATIC", # avoid MJAPI dllimport/export linkage attrs + ] + + try: + idx = cx.Index.create() + except cx.LibclangError as exc: + print(f"ERROR: libclang failed to load: {exc}", file=sys.stderr) + return 3 + + tu = idx.parse( + path=".c", + args=args_clang, + unsaved_files=[(".c", dispatch_c)], + options=(cx.TranslationUnit.PARSE_DETAILED_PROCESSING_RECORD + | cx.TranslationUnit.PARSE_SKIP_FUNCTION_BODIES), + ) + fatal_diags = [d for d in tu.diagnostics if d.severity >= cx.Diagnostic.Error] + if fatal_diags: + print(f"libclang errors:", file=sys.stderr) + for d in fatal_diags[:5]: + print(f" {d.spelling} ({d.location})", file=sys.stderr) + return 4 + + snapshot = IntrospectSnapshot( + snapshot_version=1, + header_hash=_header_hash([mjspec_h, mjmodel_h, mjxmacro_h, + vendored_mjspecmacro]), + ) + _walk(tu, mujoco_include, snapshot) + + out_dict = snapshot.to_dict() + os.makedirs(os.path.dirname(args.output), exist_ok=True) + with open(args.output, "w", encoding="utf-8") as f: + json.dump(out_dict, f, indent=2) + print(f"wrote {args.output}: " + f"{len(snapshot.functions)} functions, " + f"{len(snapshot.enums)} enums, " + f"{len(snapshot.structs)} structs, " + f"{len(snapshot.defines)} defines, " + f"header_hash={snapshot.header_hash[:12]}") + return 0 + + +if __name__ == "__main__": + raise SystemExit(main()) diff --git a/Scripts/codegen/build_mjcf_schema_snapshot.py b/Scripts/codegen/build_mjcf_schema_snapshot.py index 53f4327..93a2d7c 100644 --- a/Scripts/codegen/build_mjcf_schema_snapshot.py +++ b/Scripts/codegen/build_mjcf_schema_snapshot.py @@ -175,7 +175,210 @@ def _find_child(parent: SchemaNode, name: str) -> Optional[SchemaNode]: ] -def _build_snapshot(root: SchemaNode, mujoco_version: str) -> Dict: +# ---------------------------------------------------------------------------- +# Per-sensor objtype/reftype extraction +# ---------------------------------------------------------------------------- +# +# The static MJCF[nMJCF] schema only carries attr lists — not the per-sensor +# mapping between the XML element name and the mjsSensor objtype/reftype the +# compiler expects. That logic lives in xml_native_reader.cc's `Sensor()` +# method (a giant if/else cascade, one branch per sensor type). Phase 2b +# scrapes those branches so codegen rules don't have to hand-list them +# (Phase 2c wires this into the emitter). + +# Inside Sensor(), each "regular" branch follows: +# if (type == "") { +# sensor->type = mjSENS_X; +# sensor->objtype = mjOBJ_Y; // OPTIONAL: literal default +# ReadAttrTxt(elem, "", objname, true); // OPTIONAL: name source +# sensor->reftype = mjOBJ_Z; // OPTIONAL +# ReadAttrTxt(elem, "", refname, true); // OPTIONAL: ref name source +# } +# +# "Computed" branches (rangefinder, distance/normal/fromto, contact, user, +# plugin) derive objtype/reftype from attribute presence at parse time; +# those get marked computed=True so codegen rules keep their explicit +# overrides for them. +# Matches the open of a sensor branch, capturing the parenthesised condition +# string. We post-process the condition to pull out every ``type == "NAME"`` +# clause so ``else if (type == "distance" || type == "normal" || type == +# "fromto") { ... }`` produces three entries that share the branch body. +_SENSOR_BRANCH_RE = re.compile( + r'(?:if|else if)\s*\((?P[^{]*?type\s*==\s*"[^"]+"[^{]*)\)\s*\{', + re.DOTALL, +) +_SENSOR_NAMES_IN_COND_RE = re.compile(r'type\s*==\s*"([^"]+)"') +_TYPE_LITERAL_RE = re.compile(r'sensor->type\s*=\s*(mjSENS_\w+)\s*;') +_OBJTYPE_LITERAL_RE = re.compile(r'sensor->objtype\s*=\s*(mjOBJ_\w+)\s*;') +_REFTYPE_LITERAL_RE = re.compile(r'sensor->reftype\s*=\s*(mjOBJ_\w+)\s*;') +_OBJTYPE_FROM_XML_RE = re.compile( + r'ReadAttrTxt\s*\(\s*elem\s*,\s*"objtype"\s*,\s*text' +) +_NAME_READ_RE = re.compile( + r'ReadAttrTxt\s*\(\s*elem\s*,\s*"([^"]+)"\s*,\s*(objname|refname)\b' +) + + +def _slice_balanced_braces(src: str, open_idx: int) -> str: + """Given an index pointing AT '{', return the substring up to the + matching close (exclusive of both braces). Tracks string literals and + line/block comments so braces inside ``"..."``, ``//`` or ``/* */`` are + ignored. Returns "" if no matching close found.""" + assert src[open_idx] == "{" + n = len(src) + depth = 0 + i = open_idx + in_str = False + str_q = "" + in_line_comment = False + in_block_comment = False + while i < n: + c = src[i] + c2 = src[i:i+2] + if in_line_comment: + if c == "\n": + in_line_comment = False + i += 1 + continue + if in_block_comment: + if c2 == "*/": + in_block_comment = False + i += 2 + continue + i += 1 + continue + if in_str: + if c == "\\": + i += 2 + continue + if c == str_q: + in_str = False + i += 1 + continue + if c2 == "//": + in_line_comment = True + i += 2 + continue + if c2 == "/*": + in_block_comment = True + i += 2 + continue + if c in ('"', "'"): + in_str = True + str_q = c + i += 1 + continue + if c == "{": + depth += 1 + elif c == "}": + depth -= 1 + if depth == 0: + return src[open_idx+1:i] + i += 1 + return "" + + +# Branches where objtype/reftype are derived from attribute presence at +# parse time (multiple ReadAttrTxt + sensor->objtype = X ? mjOBJ_A : mjOBJ_B +# pattern). Codegen rules keep explicit overrides for these; the extractor +# marks them computed=True so the generated codegen doesn't pretend to know. +_COMPUTED_OBJTYPE_SENSORS = { + "rangefinder", "distance", "normal", "fromto", "contact", + "user", "plugin", +} + + +def _extract_sensor_per_type(src_text: str) -> Dict[str, Dict[str, object]]: + """Scrape ``Sensor()``'s per-type if/else cascade. Returns a dict + keyed by XML element name; each entry has: + + objtype: "mjOBJ_X" | "from_xml" | "computed" | None + reftype: "mjOBJ_Y" | "computed" | None + obj_attr: "site"/"joint"/.../None (XML attr name carrying objname) + ref_attr: "camera"/"site"/.../None (XML attr name carrying refname) + computed: True iff objtype/reftype are derived from attr presence + """ + # Slice out the Sensor() method body so we don't pick up branches from + # other methods that happen to share regex shapes. + sig_re = re.compile(r"void\s+mjXReader::Sensor\s*\(") + m = sig_re.search(src_text) + if not m: + return {} + open_idx = src_text.find("{", m.end()) + if open_idx < 0: + return {} + body = _slice_balanced_braces(src_text, open_idx) + if not body: + return {} + + result: Dict[str, Dict[str, object]] = {} + # Some outer branches (distance/normal/fromto, contact, plugin) contain + # an inner ``if (type == "X")`` that toggles ->type. Those inner matches + # would otherwise overwrite the outer-branch entry with a stripped-down + # body. Track the [start, end) of each outer-branch body and skip + # matches whose '{' falls inside. + consumed_ranges: List[tuple] = [] + for bm in _SENSOR_BRANCH_RE.finditer(body): + names = _SENSOR_NAMES_IN_COND_RE.findall(bm.group("cond")) + if not names: + continue + brace_idx = bm.end() - 1 + if brace_idx < 0 or body[brace_idx] != "{": + continue + if any(s < brace_idx < e for s, e in consumed_ranges): + continue + branch = _slice_balanced_braces(body, brace_idx) + consumed_ranges.append((brace_idx, brace_idx + 1 + len(branch))) + + obj_literal = _OBJTYPE_LITERAL_RE.search(branch) + ref_literal = _REFTYPE_LITERAL_RE.search(branch) + obj_from_xml = bool(_OBJTYPE_FROM_XML_RE.search(branch)) and not obj_literal + + obj_attr: Optional[str] = None + ref_attr: Optional[str] = None + for nm in _NAME_READ_RE.finditer(branch): + attr, target = nm.group(1), nm.group(2) + if attr == "objtype": + continue # the literal "objtype" attr selector, not a name source + if target == "objname" and obj_attr is None: + obj_attr = attr + elif target == "refname" and ref_attr is None: + ref_attr = attr + + # Capture the mjSENS_X assigned in this branch. Multi-name branches + # (distance/normal/fromto) carry an inner positional switch with + # one ->type per name. Single-name branches (touch, framepos, ...) + # have exactly one mjSENS_X. + mj_types = [m.group(1) for m in _TYPE_LITERAL_RE.finditer(branch)] + if len(mj_types) == len(names): + name_to_mj_type = dict(zip(names, mj_types)) + elif mj_types: + # Single-type branch — every name shares it. + name_to_mj_type = {n: mj_types[0] for n in names} + else: + name_to_mj_type = {n: None for n in names} + + # Multi-name branches (distance/normal/fromto share one block, + # routed inside by `if (type == ...)` to set ->type). All share + # the same objtype/reftype derivation, so emit one entry per name. + for name in names: + computed = name in _COMPUTED_OBJTYPE_SENSORS + result[name] = { + "mj_type": name_to_mj_type.get(name), + "objtype": ("computed" if computed + else ("from_xml" if obj_from_xml + else (obj_literal.group(1) if obj_literal else None))), + "reftype": ("computed" if computed + else (ref_literal.group(1) if ref_literal else None)), + "obj_attr": obj_attr, + "ref_attr": ref_attr, + "computed": computed, + } + return result + + +def _build_snapshot(root: SchemaNode, mujoco_version: str, *, + src_text: str = "") -> Dict: """Walk the parsed MJCF tree and project it onto URLab's curated shape.""" out: Dict = { "_meta": { @@ -237,11 +440,22 @@ def _build_snapshot(root: SchemaNode, mujoco_version: str) -> Dict: # Sensor section: per-type attr declarations. URLab tracks: # sensor_types = list of names # sensor_common = shared attrs (_SENSOR_COMMON_ATTRS, URLab convention) + # sensor_per_type = per-sensor objtype/reftype/attr defaults scraped + # from xml_native_reader.cc's Sensor() method body sensor = _find_child(mujoco, "sensor") if sensor is not None: sensor_attrs = {c.name: list(c.attrs) for c in sensor.children} out["sensor_types"] = list(sensor_attrs.keys()) out["sensor_common"] = {"attrs": list(_SENSOR_COMMON_ATTRS)} + if src_text: + per_type = _extract_sensor_per_type(src_text) + # Only emit per-type rows for sensors that exist in the static + # MJCF schema — keeps the snapshot in sync if MuJoCo adds a + # parser branch but not a schema entry (or vice versa). + out["sensor_per_type"] = { + name: per_type[name] for name in sensor_attrs + if name in per_type + } # Tendon section: spatial vs fixed, plus wrap types. tendon = _find_child(mujoco, "tendon") @@ -348,7 +562,7 @@ def main(argv: Optional[List[str]] = None) -> int: plugin_root, "third_party", "MuJoCo", "src", "src", "xml", "xml_native_reader.cc", ) - default_output = os.path.join(plugin_root, "Scripts", "mjcf_schema_snapshot.json") + default_output = os.path.join(plugin_root, "Scripts", "codegen", "snapshots", "mjcf_schema_snapshot.json") ap = argparse.ArgumentParser() ap.add_argument("--src", default=default_src, @@ -367,7 +581,7 @@ def main(argv: Optional[List[str]] = None) -> int: blocks = _tokenise_blocks(body) root = _parse_tree(blocks) version = _detect_mujoco_version(args.src) - snapshot = _build_snapshot(root, mujoco_version=version) + snapshot = _build_snapshot(root, mujoco_version=version, src_text=src_text) os.makedirs(os.path.dirname(args.output), exist_ok=True) with open(args.output, "w", encoding="utf-8") as f: diff --git a/Scripts/codegen/build_mjspec_snapshot.py b/Scripts/codegen/build_mjspec_snapshot.py index 706d7ac..9586105 100644 --- a/Scripts/codegen/build_mjspec_snapshot.py +++ b/Scripts/codegen/build_mjspec_snapshot.py @@ -35,7 +35,7 @@ DEFAULT_MUJOCO_H = os.path.join( PLUGIN_ROOT, "third_party", "install", "MuJoCo", "include", "mujoco", "mujoco.h" ) -DEFAULT_OUTPUT = os.path.join(PLUGIN_ROOT, "Scripts", "mjspec_snapshot.json") +DEFAULT_OUTPUT = os.path.join(PLUGIN_ROOT, "Scripts", "codegen", "snapshots", "mjspec_snapshot.json") # Matches `typedef struct mjsName_ { ... } mjsName;` blocks. _STRUCT_RE = re.compile( @@ -98,6 +98,68 @@ def parse_structs(text: str) -> dict[str, list[str]]: ) +# Phase 2d-1: per-MuJoCo-enum value extraction. +# +# Captures ``typedef enum mjtX_ { mjFOO = 0, mjBAR, mjBAZ = 100, ... } mjtX;`` +# blocks. Auto-increment honoured: a bare entry inherits prev value + 1. +# Explicit ``= N`` resets the counter. Trailing comments are stripped per-line. +# +# Output shape (added under top-level ``"enums"`` key in mjspec_snapshot.json): +# { +# "mjtJoint": {"mjJNT_FREE": 0, "mjJNT_BALL": 1, "mjJNT_SLIDE": 2, "mjJNT_HINGE": 3}, +# "mjtGeom": {"mjGEOM_PLANE": 0, "mjGEOM_HFIELD": 1, ..., "mjGEOM_NONE": 1001}, +# ... +# } +# +# Phase 2c's ``value_map_from_enum`` resolver consumes this to populate +# xml_enum value maps without a hand-listed table in codegen_rules.json. +_ENUM_BLOCK_RE = re.compile( + r"typedef\s+enum\s+(?Pmjt\w+)_\s*\{(?P[^}]*)\}\s*\1\s*;", + re.DOTALL, +) +# Inside the body, each entry: `` or ` = ` (decimal/hex/ +# arithmetic). Stop at comma or newline. We strip comments first. +_ENUM_ENTRY_RE = re.compile( + r"\b(?P\w+)\b(?:\s*=\s*(?P[^,\n]+?))?\s*(?:,|$)", + re.MULTILINE, +) + + +def parse_enums(text: str) -> dict[str, dict[str, int]]: + """Scrape MuJoCo C enum blocks. Skips non-mjt prefixes (the snapshot + is scoped to enums URLab might map to UE enums via xml_enum_attrs).""" + out: dict[str, dict[str, int]] = {} + for m in _ENUM_BLOCK_RE.finditer(text): + name = m.group("name") + body = m.group("body") + # Strip line-end + block comments before tokenising. + body_clean = re.sub(r"//[^\n]*", "", body) + body_clean = re.sub(r"/\*.*?\*/", "", body_clean, flags=re.DOTALL) + members: dict[str, int] = {} + next_value = 0 + for em in _ENUM_ENTRY_RE.finditer(body_clean): + ename = em.group("name") + evalue_raw = (em.group("value") or "").strip() + if evalue_raw: + # Resolve common shapes: decimal, hex, simple arithmetic. + try: + next_value = int(evalue_raw, 0) + except ValueError: + # Fallback for things like "1 << 0"; eval'd in a sandbox. + try: + next_value = int(eval(evalue_raw, {"__builtins__": {}}, {})) + except Exception: + # Unresolved expression — skip the member rather than + # crash; codegen rules can hand-list the value if + # this enum is referenced. + continue + members[ename] = next_value + next_value += 1 + if members: + out[name] = members + return out + + def parse_setto_functions(text: str) -> dict[str, dict]: """Scrape ``mjs_setTo*`` function declarations from mujoco.h. Skips the first ``mjsActuator* actuator`` parameter; returns the remaining @@ -145,7 +207,8 @@ def main() -> int: # Also scrape mjs_setTo* signatures from mujoco.h so codegen can emit # the actuator preset calls from introspection instead of hand-written - # C++ literals in codegen_rules.json. + # C++ literals in codegen_rules.json. mjmodel.h has the typedef enum + # declarations URLab maps through xml_enum_attrs.value_map_from_enum. if os.path.exists(args.mujoco_h): with open(args.mujoco_h, "r", encoding="utf-8") as f: mj_text = f.read() @@ -154,13 +217,25 @@ def main() -> int: print(f"WARN: mujoco.h not found at {args.mujoco_h} — skipping setto functions", file=sys.stderr) out["setto_functions"] = {} + # mjmodel.h sits alongside mujoco.h; reuse the path resolution. + mjmodel_h = os.path.join(os.path.dirname(args.mujoco_h), "mjmodel.h") + if os.path.exists(mjmodel_h): + with open(mjmodel_h, "r", encoding="utf-8") as f: + model_text = f.read() + out["enums"] = parse_enums(model_text) + else: + print(f"WARN: mjmodel.h not found at {mjmodel_h} — skipping enum scrape", file=sys.stderr) + out["enums"] = {} + os.makedirs(os.path.dirname(args.output), exist_ok=True) with open(args.output, "w", encoding="utf-8") as f: json.dump(out, f, indent=2) total_fields = sum(len(v) for v in structs.values()) + total_enum_members = sum(len(v) for v in out["enums"].values()) print(f"wrote {args.output}: {len(structs)} structs, {total_fields} fields, " - f"{len(out['setto_functions'])} setto functions") + f"{len(out['setto_functions'])} setto functions, " + f"{len(out['enums'])} enums ({total_enum_members} members)") return 0 diff --git a/Scripts/codegen/build_mjxmacro_snapshot.py b/Scripts/codegen/build_mjxmacro_snapshot.py index f60706f..7d973c1 100644 --- a/Scripts/codegen/build_mjxmacro_snapshot.py +++ b/Scripts/codegen/build_mjxmacro_snapshot.py @@ -30,7 +30,7 @@ DEFAULT_MJXMACRO = os.path.join( PLUGIN_ROOT, "third_party", "install", "MuJoCo", "include", "mujoco", "mjxmacro.h" ) -DEFAULT_OUTPUT = os.path.join(PLUGIN_ROOT, "Scripts", "mjxmacro_snapshot.json") +DEFAULT_OUTPUT = os.path.join(PLUGIN_ROOT, "Scripts", "codegen", "snapshots", "mjxmacro_snapshot.json") # Block names we care about. Categorized so the consumer knows the # kind of data (per-element pointer table vs flat struct fields). @@ -79,6 +79,8 @@ ] # Flat struct field blocks (no outer dimension — just type + name + size). +# Lives across both mjxmacro.h (the mjmodel-side struct fields) and +# mjspecmacro.h (the mjspec-side struct fields). STRUCT_FIELD_BLOCKS = [ "MJOPTION_FIELDS", "MJSTATISTIC_FIELDS", @@ -88,13 +90,26 @@ "MJVISUAL_MAP_FIELDS", "MJVISUAL_SCALE_FIELDS", "MJVISUAL_RGBA_FIELDS", + "MJSCOMPILER_FIELDS", + "MJSPEC_FIELDS", ] +DEFAULT_MJSPECMACRO = os.path.join( + SCRIPT_DIR, "_vendored", "mjspecmacro.h", +) + # Regexes _BLOCK_START_RE = re.compile(r"^\s*#define\s+(\w+)\s*(?:\(\s*\w+\s*\))?\s*\\?\s*$") +# Single source of truth for the X-macro tag set. Accepts X / XVEC / XNV. +# XNV ("X No Vec") is structurally identical to X (same 4-tuple shape); +# MuJoCo uses the tag so its own codegen knows to skip the vectorised +# emission path. URLab doesn't care about that distinction — we just want +# the entry shape. Add new tags here whenever MuJoCo introduces one; +# duplicating the list in a sibling regex is the bug class that bit XNV. +_X_TAG_RE = r"X(?:VEC|NV)?" # X-macro entry. Tolerates 4 or 3-tuple forms (pointer vs flat field). # Captures parenthesised contents; field split below trims/normalizes. -_X_ENTRY_RE = re.compile(r"^\s*X(?:VEC)?\s*\(\s*(.*?)\s*\)\s*\\?\s*$") +_X_ENTRY_RE = re.compile(rf"^\s*{_X_TAG_RE}\s*\(\s*(.*?)\s*\)\s*\\?\s*$") def _strip_comments(text: str) -> str: @@ -104,13 +119,7 @@ def _strip_comments(text: str) -> str: return text -def _join_continued_lines(text: str) -> str: - # mjxmacro spreads multi-line macros via backslash continuation; preserve - # individual entries on their own lines for downstream parsing. - return text - - -_BODY_ENTRY_RE = re.compile(r"^\s*(X|XVEC)\s*\(") +_BODY_ENTRY_RE = re.compile(rf"^\s*{_X_TAG_RE}\s*\(") def _parse_block_body(lines: List[str], start_idx: int) -> List[str]: @@ -170,12 +179,16 @@ def _parse_pointer_entry(raw: str) -> Optional[Dict[str, Any]]: def _parse_struct_field_entry(raw: str) -> Optional[Dict[str, Any]]: - """Parse `X(type, name, count)` or `X(name, count)` or `XVEC(...)`. + """Parse `X(type, name, count)` or `X(name, count)` or `X(name)` or `XVEC(...)`. mjxmacro flat-struct blocks have a few shapes: - `X(type, name, count)` (mjOption) - `X(name, count)` (mjStatistic — no type, defaults to mjtNum) - `X(type, name)` (mjVisual fields — no explicit count, treated as scalar) + - `X(name)` (mjVisualQuality/Map/Scale/Rgba — bare field name; type is + whatever the corresponding ``struct mjVisualX`` member is. URLab + defaults to mjtNum since these structs are float/int in practice and + consumers can override via ``field_types``.) - `XVEC(type, name, count)` (vec3 / vec5 / etc.) """ m = _X_ENTRY_RE.match(raw) @@ -193,6 +206,9 @@ def _parse_struct_field_entry(raw: str) -> Optional[Dict[str, Any]]: ctype, name, count = fields[0], fields[1], "1" else: ctype, name, count = "mjtNum", fields[0], fields[1] + elif len(fields) == 1: + # Bare field name — type defaults to mjtNum, scalar. + ctype, name, count = "mjtNum", fields[0], "1" else: return None return { @@ -249,6 +265,32 @@ def main() -> int: print(f"error: mjxmacro.h not found at {src}", file=sys.stderr) return 1 snapshot = parse_mjxmacro(src) + # Track which source each struct-field block came from so a snapshot + # reader can tell mjmodel-side (mjxmacro.h) blocks apart from mjspec-side + # (mjspecmacro.h) blocks without re-parsing the headers. + block_sources: Dict[str, str] = {} + for block_name in snapshot["struct_fields"]: + block_sources[block_name] = snapshot["_meta"]["source"] + # Also fold in the vendored mjspecmacro.h (MJSCOMPILER_FIELDS + + # MJSPEC_FIELDS) — both live in the same ``struct_fields`` dict so + # synthetic_categories rules can reference either by block name. + if os.path.isfile(DEFAULT_MJSPECMACRO): + spec_snapshot = parse_mjxmacro(DEFAULT_MJSPECMACRO) + spec_rel = os.path.relpath(DEFAULT_MJSPECMACRO, PLUGIN_ROOT) + for block_name, entries in spec_snapshot["struct_fields"].items(): + snapshot["struct_fields"][block_name] = entries + block_sources[block_name] = spec_rel + else: + # Loud rather than silent — MJSCOMPILER_FIELDS / MJSPEC_FIELDS + # blocks WILL be missing if the vendored header was removed, and + # that surfaces only as a downstream KeyError much later in + # generate_ue_components.py. + print( + f"warning: vendored mjspecmacro.h not found at {DEFAULT_MJSPECMACRO}; " + f"MJSCOMPILER_FIELDS + MJSPEC_FIELDS will be absent from the snapshot.", + file=sys.stderr, + ) + snapshot["_meta"]["struct_field_sources"] = block_sources # Stats for sanity. total_model = sum(len(v) for v in snapshot["mjmodel_pointers"].values()) total_data = sum(len(v) for v in snapshot["mjdata_pointers"].values()) diff --git a/Scripts/codegen/codegen_rules.json b/Scripts/codegen/codegen_rules.json index c29fa76..c574319 100644 --- a/Scripts/codegen/codegen_rules.json +++ b/Scripts/codegen/codegen_rules.json @@ -5,18 +5,21 @@ }, "global_exclusions": [ - "user", "name", "class", "type" + "user", "name", "class", "type", "objtype", "reftype" ], "default_type": "float", "_note_property_renames": "Schema attr -> UPROPERTY identifier. Used when the UE-side identifier must differ from the verbatim schema attr (typically to avoid C++ keyword collisions or to keep PascalCase for legacy consumers). qpos/qvel/etc are PascalCase on UMjKeyframe because BP graphs / runtime accessors reference them that way.", "property_renames": { - "qpos": "Qpos", - "qvel": "Qvel", - "act": "Act", - "ctrl": "Ctrl", - "mpos": "Mpos", - "mquat": "Mquat", - "time": "Time" + "qpos": "Qpos", + "qvel": "Qvel", + "act": "Act", + "ctrl": "Ctrl", + "mpos": "Mpos", + "mquat": "Mquat", + "time": "Time", + "actuatorfrclimited": "ActFrcLimited", + "actuatorfrcrange": "ActFrcRange", + "axis": "Axis" }, "_note_setto_param_defaults": "MuJoCo's mjs_setTo* API treats specific scalar defaults as sentinels. These values are how URLab signals 'not overridden, use MuJoCo's default'. Most use -1.0; a few use 0.0 or 0.01 — encoded here as data, NOT as C++ string literals.", @@ -38,6 +41,43 @@ "skin": "Children of . URLab handles skinning via UE skeletal meshes; in MJCF would need a dedicated asset pipeline." }, + "_note_intentionally_unmodeled_mjs_fields": "Per-mjsX-struct list of fields URLab knows about but doesn't model via codegen. Silences the mjsX-field-drift diagnostic. Add entries for fields handled by a different UE component, by canon, or that we deliberately skip.", + "intentionally_unmodeled_mjs_fields": { + "mjsBody": [ + "inertia", "ipos", "ialt", "mass", "iquat", "fullinertia", "alt", + "plugin" + ], + "mjsFrame": [ + "pos", "quat", "childclass", "alt" + ], + "mjsFlex": [ + "solimp", "solmix", "contype", "activelayers", "edgedamping", "elem", + "size", "passive", "condim", "order", "nodebody", + "vertbody", "elemtexcoord", "selfcollide", "poisson", "vert", "margin", + "conaffinity", "damping", "priority", "edgestiffness", "node", + "solref", "gap", "elastic2d", "young", "friction", "thickness", "internal" + ], + "mjsCamera": [ + "intrinsic", "alt" + ], + "mjsGeom": [ + "alt", "plugin" + ], + "mjsSite": [ + "alt" + ], + "mjsActuator": [ + "plugin" + ], + "mjsJoint": [ + "align" + ], + "mjsSensor": [ + "datatype", "dim", "intprm", "needstage", "objname", "plugin", + "refname", "reftype" + ] + }, + "type_mappings": { "axis": "FVector", "dir": "FVector", @@ -215,6 +255,7 @@ "element_rules": { "actuator": { "_note_enums": "gaintype/biastype/dyntype are mjtGain/mjtBias/mjtDyn enums on mjsActuator. URLab declares EMjGainType/EMjBiasType/EMjDynType hand-side on UMjActuator; codegen owns the XML<->enum map via xml_enum_attrs. dcmotor 'input' is per-subtype (only on UMjDcMotorActuator) — emitter gates on attr-in-subtype-schema for that case.", + "common_imports": ["class"], "exclude_attrs": [], "applies_canonicalizations": ["actuator_transmission"], "xml_enum_attrs": { @@ -223,6 +264,8 @@ "ue_enum_type": "EMjGainType", "mjs_field": "gaintype", "mjs_cast": "mjtGain", + "emit_property_decl": true, + "property_default": "Fixed", "value_map": { "fixed": ["Fixed", "mjGAIN_FIXED"], "affine": ["Affine", "mjGAIN_AFFINE"], @@ -235,6 +278,8 @@ "ue_enum_type": "EMjBiasType", "mjs_field": "biastype", "mjs_cast": "mjtBias", + "emit_property_decl": true, + "property_default": "None", "value_map": { "none": ["None", "mjBIAS_NONE"], "affine": ["Affine", "mjBIAS_AFFINE"], @@ -247,6 +292,8 @@ "ue_enum_type": "EMjDynType", "mjs_field": "dyntype", "mjs_cast": "mjtDyn", + "emit_property_decl": true, + "property_default": "None", "value_map": { "none": ["None", "mjDYN_NONE"], "integrator": ["Integrator", "mjDYN_INTEGRATOR"], @@ -269,14 +316,66 @@ } }, "sensor": { + "_note": "Sensor reads its target name from one of several xor attrs depending on subtype (site for touch/accel/gyro, joint for jointpos, etc.). target_collations collapses them into UE FString TargetName. ReferenceName is direct from 'refname'. ObjType / RefType are EMjObjType enums with their own string<->enum mapping (xml_enum_attrs).", + "common_imports": ["class"], + "target_collations": { + "TargetName": { + "mjs_field": "objname", + "absorbs_attrs": ["site", "joint", "tendon", "actuator", "body", "geom", "objname", "camera", "mesh"] + }, + "ReferenceName": { + "mjs_field": "refname", + "absorbs_attrs": ["refname"] + } + }, + "xml_enum_attrs": { + "objtype": { + "ue_property": "ObjType", + "ue_enum_type": "EMjObjType", + "has_override_toggle": false, + "value_map": { + "body": ["Body", "mjOBJ_BODY"], + "xbody": ["XBody", "mjOBJ_XBODY"], + "joint": ["Joint", "mjOBJ_JOINT"], + "dof": ["DoF", "mjOBJ_DOF"], + "geom": ["Geom", "mjOBJ_GEOM"], + "site": ["Site", "mjOBJ_SITE"], + "camera": ["Camera", "mjOBJ_CAMERA"], + "light": ["Light", "mjOBJ_LIGHT"], + "mesh": ["Mesh", "mjOBJ_MESH"], + "hfield": ["HField", "mjOBJ_HFIELD"], + "texture": ["Texture", "mjOBJ_TEXTURE"], + "material": ["Material", "mjOBJ_MATERIAL"], + "pair": ["Pair", "mjOBJ_PAIR"], + "exclude": ["Exclude", "mjOBJ_EXCLUDE"], + "equality": ["Equality", "mjOBJ_EQUALITY"], + "tendon": ["Tendon", "mjOBJ_TENDON"], + "actuator": ["Actuator", "mjOBJ_ACTUATOR"] + } + }, + "reftype": { + "ue_property": "RefType", + "ue_enum_type": "EMjObjType", + "has_override_toggle": false, + "value_map": { + "body": ["Body", "mjOBJ_BODY"], + "xbody": ["XBody", "mjOBJ_XBODY"], + "joint": ["Joint", "mjOBJ_JOINT"], + "geom": ["Geom", "mjOBJ_GEOM"], + "site": ["Site", "mjOBJ_SITE"], + "camera": ["Camera", "mjOBJ_CAMERA"] + } + } + }, "exclude_attrs": [] }, "joint": { - "exclude_attrs": ["pos", "axis"], - "extra_property_inits": { - "Pos": "FVector::ZeroVector", - "Axis": "FVector(0.0f, 0.0f, 1.0f)" - }, + "_note_axis_pos": "axis: MuJoCo direction vector with opposite Y handedness vs UE; vec3_convert.axis = y_negate flips on import + export. pos: spatial_pose canon emits the Pos UPROPERTY pair + drives SetRelativeLocation on import.", + "common_imports": ["class"], + "applies_canonicalizations": ["spatial_pose"], + "vec3_convert": {"axis": "y_negate"}, + "property_defaults": {"axis": "FVector(0.0f, 0.0f, 1.0f)"}, + "exclude_attrs": [], "xml_enum_attrs": { "type": { "ue_property": "Type", @@ -315,6 +414,7 @@ }, "geom": { "_note": "size is codegen-owned TArray; fromto-decomposed half-length is written into size[1]/[2] by the canon. material is codegen-owned for IMPORT (FString -> UE material lookup) but SKIPPED on export because URLab handles materials as UE assets and does not register them in the mjsSpec (mjs_setString on Element->material would reference a non-existent spec entry and fail mj_compile). Orientation cluster absorbed by `orientation`; fromto absorbed by `fromto_decompose`. type is an URLab enum (EMjGeomType); codegen owns the XML<->enum string map via xml_enum_attrs.", + "common_imports": ["class"], "exclude_attrs": [], "_note_hfield": "hfield references URLab's own hfield actor system, not a mjsHField spec entry. Codegen still imports the string for editor visibility but skips the spec write to avoid 'hfield not found' on compile.", "export_skip_attrs": ["material", "hfield"], @@ -391,6 +491,7 @@ } }, "tendon": { + "common_imports": ["class"], "_note_material": "material codegen-owned for IMPORT but export-skipped — URLab handles materials as UE assets, not mjsMaterial spec entries.", "exclude_attrs": [], "export_skip_attrs": ["material"] @@ -439,6 +540,8 @@ }, "camera": { "_note": "MJCF camera.mode is a tracking mode (mjtCamLight subset). URLab declares EMjCameraTrackingMode hand-side; codegen owns the XML<->enum map. NOT to be confused with URLab's EMjCameraMode which is a UE-side render-mode selector (RGB/Depth/Segmentation).", + "_note_common_imports": "Camera also reads name; the hand-written ImportFromXml has a fallback `if MjName empty -> 'Camera'` that runs AFTER this read.", + "common_imports": ["name"], "exclude_attrs": [], "applies_canonicalizations": ["spatial_pose", "orientation"], "_note_attr_to_mjs_field": "MuJoCo renames a handful of camera attrs between the XML schema and the mjsCamera struct: target -> targetbody (mjString*), projection -> proj (mjtProjection enum), focal -> focal_length, principal -> principal_length. sensorsize auto-resolves to sensor_size via the underscore-normalise heuristic. Without this map the auto-resolver in _resolve_mjs_field can't bridge target/focal/principal and they were silently dropped on export.", @@ -474,6 +577,7 @@ } }, "body": { + "common_imports": ["name"], "exclude_attrs": [], "applies_canonicalizations": ["spatial_pose", "orientation", "body_sleep_policy"], "_note_canon_export_skip": "Body's pos/quat are written by MjSpecWrapper::CreateBody from the UE component transform (the source of truth for body placement). The codegen-emitted spatial_pose/orientation export would overwrite those with the Pos/Quat UPROPERTYs, which are stale for any body not freshly imported from XML. Skip the export side for these two canons.", @@ -538,9 +642,11 @@ "exclude_attrs": [] }, "contact_pair": { + "common_imports": [{"attr": "name", "ue_field": "Name"}], "exclude_attrs": [] }, "contact_exclude": { + "common_imports": [{"attr": "name", "ue_field": "Name"}], "exclude_attrs": [] }, "keyframe": { @@ -604,55 +710,57 @@ "schema_subtypes_block": "sensor_types", "type_enum_name": "EMjSensorType", "subtypes": [ - {"key": "touch", "enum_value": "Touch", "class_name": "UMjTouchSensor", "header": "MjTouchSensor.h"}, - {"key": "accelerometer", "enum_value": "Accelerometer", "class_name": "UMjAccelerometer", "header": "MjAccelerometer.h"}, - {"key": "velocimeter", "enum_value": "Velocimeter", "class_name": "UMjVelocimeter", "header": "MjVelocimeter.h"}, - {"key": "gyro", "enum_value": "Gyro", "class_name": "UMjGyro", "header": "MjGyro.h"}, - {"key": "force", "enum_value": "Force", "class_name": "UMjForceSensor", "header": "MjForceSensor.h"}, - {"key": "torque", "enum_value": "Torque", "class_name": "UMjTorqueSensor", "header": "MjTorqueSensor.h"}, - {"key": "magnetometer", "enum_value": "Magnetometer", "class_name": "UMjMagnetometer", "header": "MjMagnetometer.h"}, - {"key": "camprojection", "enum_value": "CamProjection", "class_name": "UMjCamProjectionSensor", "header": "MjCamProjectionSensor.h"}, - {"key": "rangefinder", "enum_value": "RangeFinder", "class_name": "UMjRangeFinderSensor", "header": "MjRangeFinderSensor.h"}, + {"key": "touch", "enum_value": "Touch", "class_name": "UMjTouchSensor", "header": "MjTouchSensor.h", "fully_emitted": true}, + {"key": "accelerometer", "enum_value": "Accelerometer", "class_name": "UMjAccelerometer", "header": "MjAccelerometer.h", "fully_emitted": true}, + {"key": "velocimeter", "enum_value": "Velocimeter", "class_name": "UMjVelocimeter", "header": "MjVelocimeter.h", "fully_emitted": true}, + {"key": "gyro", "enum_value": "Gyro", "class_name": "UMjGyro", "header": "MjGyro.h", "fully_emitted": true}, + {"key": "force", "enum_value": "Force", "class_name": "UMjForceSensor", "header": "MjForceSensor.h", "fully_emitted": true}, + {"key": "torque", "enum_value": "Torque", "class_name": "UMjTorqueSensor", "header": "MjTorqueSensor.h", "fully_emitted": true}, + {"key": "magnetometer", "enum_value": "Magnetometer", "class_name": "UMjMagnetometer", "header": "MjMagnetometer.h", "fully_emitted": true}, + {"key": "camprojection", "enum_value": "CamProjection", "class_name": "UMjCamProjectionSensor", "header": "MjCamProjectionSensor.h", "fully_emitted": true}, + {"key": "rangefinder", "enum_value": "RangeFinder", "class_name": "UMjRangeFinderSensor", "header": "MjRangeFinderSensor.h", + "case_body_override": "Element->type = mjSENS_RANGEFINDER; Element->objtype = (ObjType == EMjObjType::Camera) ? mjOBJ_CAMERA : mjOBJ_SITE;", + "fully_emitted": true}, {"key": "jointpos", "enum_value": "JointPos", "class_name": "UMjJointPosSensor", "header": "MjJointPosSensor.h"}, - {"key": "jointvel", "enum_value": "JointVel", "class_name": "UMjJointVelSensor", "header": "MjJointVelSensor.h"}, - {"key": "ballquat", "enum_value": "BallQuat", "class_name": "UMjBallQuatSensor", "header": "MjBallQuatSensor.h"}, - {"key": "ballangvel", "enum_value": "BallAngVel", "class_name": "UMjBallAngVelSensor", "header": "MjBallAngVelSensor.h"}, - {"key": "jointlimitpos", "enum_value": "JointLimitPos", "class_name": "UMjJointLimitPosSensor", "header": "MjJointLimitPosSensor.h"}, - {"key": "jointlimitvel", "enum_value": "JointLimitVel", "class_name": "UMjJointLimitVelSensor", "header": "MjJointLimitVelSensor.h"}, - {"key": "jointlimitfrc", "enum_value": "JointLimitFrc", "class_name": "UMjJointLimitFrcSensor", "header": "MjJointLimitFrcSensor.h"}, - {"key": "tendonpos", "enum_value": "TendonPos", "class_name": "UMjTendonPosSensor", "header": "MjTendonPosSensor.h"}, - {"key": "tendonvel", "enum_value": "TendonVel", "class_name": "UMjTendonVelSensor", "header": "MjTendonVelSensor.h"}, - {"key": "tendonlimitpos", "enum_value": "TendonLimitPos", "class_name": "UMjTendonLimitPosSensor", "header": "MjTendonLimitPosSensor.h"}, - {"key": "tendonlimitvel", "enum_value": "TendonLimitVel", "class_name": "UMjTendonLimitVelSensor", "header": "MjTendonLimitVelSensor.h"}, - {"key": "tendonlimitfrc", "enum_value": "TendonLimitFrc", "class_name": "UMjTendonLimitFrcSensor", "header": "MjTendonLimitFrcSensor.h"}, - {"key": "actuatorpos", "enum_value": "ActuatorPos", "class_name": "UMjActuatorPosSensor", "header": "MjActuatorPosSensor.h"}, - {"key": "actuatorvel", "enum_value": "ActuatorVel", "class_name": "UMjActuatorVelSensor", "header": "MjActuatorVelSensor.h"}, - {"key": "actuatorfrc", "enum_value": "ActuatorFrc", "class_name": "UMjActuatorFrcSensor", "header": "MjActuatorFrcSensor.h"}, - {"key": "jointactuatorfrc", "enum_value": "JointActFrc", "class_name": "UMjJointActFrcSensor", "header": "MjJointActFrcSensor.h"}, - {"key": "tendonactuatorfrc","enum_value": "TendonActFrc", "class_name": "UMjTendonActFrcSensor", "header": "MjTendonActFrcSensor.h"}, - {"key": "framepos", "enum_value": "FramePos", "class_name": "UMjFramePosSensor", "header": "MjFramePosSensor.h"}, - {"key": "framequat", "enum_value": "FrameQuat", "class_name": "UMjFrameQuatSensor", "header": "MjFrameQuatSensor.h"}, - {"key": "framexaxis", "enum_value": "FrameXAxis", "class_name": "UMjFrameXAxisSensor", "header": "MjFrameXAxisSensor.h"}, - {"key": "frameyaxis", "enum_value": "FrameYAxis", "class_name": "UMjFrameYAxisSensor", "header": "MjFrameYAxisSensor.h"}, - {"key": "framezaxis", "enum_value": "FrameZAxis", "class_name": "UMjFrameZAxisSensor", "header": "MjFrameZAxisSensor.h"}, - {"key": "framelinvel", "enum_value": "FrameLinVel", "class_name": "UMjFrameLinVelSensor", "header": "MjFrameLinVelSensor.h"}, - {"key": "frameangvel", "enum_value": "FrameAngVel", "class_name": "UMjFrameAngVelSensor", "header": "MjFrameAngVelSensor.h"}, - {"key": "framelinacc", "enum_value": "FrameLinAcc", "class_name": "UMjFrameLinAccSensor", "header": "MjFrameLinAccSensor.h"}, - {"key": "frameangacc", "enum_value": "FrameAngAcc", "class_name": "UMjFrameAngAccSensor", "header": "MjFrameAngAccSensor.h"}, - {"key": "subtreecom", "enum_value": "SubtreeCom", "class_name": "UMjSubtreeComSensor", "header": "MjSubtreeComSensor.h"}, - {"key": "subtreelinvel", "enum_value": "SubtreeLinVel", "class_name": "UMjSubtreeLinVelSensor", "header": "MjSubtreeLinVelSensor.h"}, - {"key": "subtreeangmom", "enum_value": "SubtreeAngMom", "class_name": "UMjSubtreeAngMomSensor", "header": "MjSubtreeAngMomSensor.h"}, - {"key": "insidesite", "enum_value": "InsideSite", "class_name": "UMjInsideSiteSensor", "header": "MjInsideSiteSensor.h"}, - {"key": "distance", "enum_value": "GeomDist", "class_name": "UMjGeomDistSensor", "header": "MjGeomDistSensor.h"}, - {"key": "normal", "enum_value": "GeomNormal", "class_name": "UMjGeomNormalSensor", "header": "MjGeomNormalSensor.h"}, - {"key": "fromto", "enum_value": "GeomFromTo", "class_name": "UMjGeomFromToSensor", "header": "MjGeomFromToSensor.h"}, - {"key": "contact", "enum_value": "Contact", "class_name": "UMjContactSensor", "header": "MjContactSensor.h"}, - {"key": "e_potential", "enum_value": "EPotential", "class_name": "UMjEPotentialSensor", "header": "MjEPotentialSensor.h"}, - {"key": "e_kinetic", "enum_value": "EKinetic", "class_name": "UMjEKineticSensor", "header": "MjEKineticSensor.h"}, - {"key": "clock", "enum_value": "Clock", "class_name": "UMjClockSensor", "header": "MjClockSensor.h"}, + {"key": "jointvel", "enum_value": "JointVel", "class_name": "UMjJointVelSensor", "header": "MjJointVelSensor.h", "fully_emitted": true}, + {"key": "ballquat", "enum_value": "BallQuat", "class_name": "UMjBallQuatSensor", "header": "MjBallQuatSensor.h", "fully_emitted": true}, + {"key": "ballangvel", "enum_value": "BallAngVel", "class_name": "UMjBallAngVelSensor", "header": "MjBallAngVelSensor.h", "fully_emitted": true}, + {"key": "jointlimitpos", "enum_value": "JointLimitPos", "class_name": "UMjJointLimitPosSensor", "header": "MjJointLimitPosSensor.h", "fully_emitted": true}, + {"key": "jointlimitvel", "enum_value": "JointLimitVel", "class_name": "UMjJointLimitVelSensor", "header": "MjJointLimitVelSensor.h", "fully_emitted": true}, + {"key": "jointlimitfrc", "enum_value": "JointLimitFrc", "class_name": "UMjJointLimitFrcSensor", "header": "MjJointLimitFrcSensor.h", "fully_emitted": true}, + {"key": "tendonpos", "enum_value": "TendonPos", "class_name": "UMjTendonPosSensor", "header": "MjTendonPosSensor.h", "fully_emitted": true}, + {"key": "tendonvel", "enum_value": "TendonVel", "class_name": "UMjTendonVelSensor", "header": "MjTendonVelSensor.h", "fully_emitted": true}, + {"key": "tendonlimitpos", "enum_value": "TendonLimitPos", "class_name": "UMjTendonLimitPosSensor", "header": "MjTendonLimitPosSensor.h", "fully_emitted": true}, + {"key": "tendonlimitvel", "enum_value": "TendonLimitVel", "class_name": "UMjTendonLimitVelSensor", "header": "MjTendonLimitVelSensor.h", "fully_emitted": true}, + {"key": "tendonlimitfrc", "enum_value": "TendonLimitFrc", "class_name": "UMjTendonLimitFrcSensor", "header": "MjTendonLimitFrcSensor.h", "fully_emitted": true}, + {"key": "actuatorpos", "enum_value": "ActuatorPos", "class_name": "UMjActuatorPosSensor", "header": "MjActuatorPosSensor.h", "fully_emitted": true}, + {"key": "actuatorvel", "enum_value": "ActuatorVel", "class_name": "UMjActuatorVelSensor", "header": "MjActuatorVelSensor.h", "fully_emitted": true}, + {"key": "actuatorfrc", "enum_value": "ActuatorFrc", "class_name": "UMjActuatorFrcSensor", "header": "MjActuatorFrcSensor.h", "fully_emitted": true}, + {"key": "jointactuatorfrc", "enum_value": "JointActFrc", "class_name": "UMjJointActFrcSensor", "header": "MjJointActFrcSensor.h", "fully_emitted": true}, + {"key": "tendonactuatorfrc","enum_value": "TendonActFrc", "class_name": "UMjTendonActFrcSensor", "header": "MjTendonActFrcSensor.h", "fully_emitted": true}, + {"key": "framepos", "enum_value": "FramePos", "class_name": "UMjFramePosSensor", "header": "MjFramePosSensor.h", "fully_emitted": true}, + {"key": "framequat", "enum_value": "FrameQuat", "class_name": "UMjFrameQuatSensor", "header": "MjFrameQuatSensor.h", "fully_emitted": true}, + {"key": "framexaxis", "enum_value": "FrameXAxis", "class_name": "UMjFrameXAxisSensor", "header": "MjFrameXAxisSensor.h", "fully_emitted": true}, + {"key": "frameyaxis", "enum_value": "FrameYAxis", "class_name": "UMjFrameYAxisSensor", "header": "MjFrameYAxisSensor.h", "fully_emitted": true}, + {"key": "framezaxis", "enum_value": "FrameZAxis", "class_name": "UMjFrameZAxisSensor", "header": "MjFrameZAxisSensor.h", "fully_emitted": true}, + {"key": "framelinvel", "enum_value": "FrameLinVel", "class_name": "UMjFrameLinVelSensor", "header": "MjFrameLinVelSensor.h", "fully_emitted": true}, + {"key": "frameangvel", "enum_value": "FrameAngVel", "class_name": "UMjFrameAngVelSensor", "header": "MjFrameAngVelSensor.h", "fully_emitted": true}, + {"key": "framelinacc", "enum_value": "FrameLinAcc", "class_name": "UMjFrameLinAccSensor", "header": "MjFrameLinAccSensor.h", "fully_emitted": true}, + {"key": "frameangacc", "enum_value": "FrameAngAcc", "class_name": "UMjFrameAngAccSensor", "header": "MjFrameAngAccSensor.h", "fully_emitted": true}, + {"key": "subtreecom", "enum_value": "SubtreeCom", "class_name": "UMjSubtreeComSensor", "header": "MjSubtreeComSensor.h", "fully_emitted": true}, + {"key": "subtreelinvel", "enum_value": "SubtreeLinVel", "class_name": "UMjSubtreeLinVelSensor", "header": "MjSubtreeLinVelSensor.h", "fully_emitted": true}, + {"key": "subtreeangmom", "enum_value": "SubtreeAngMom", "class_name": "UMjSubtreeAngMomSensor", "header": "MjSubtreeAngMomSensor.h", "fully_emitted": true}, + {"key": "insidesite", "enum_value": "InsideSite", "class_name": "UMjInsideSiteSensor", "header": "MjInsideSiteSensor.h", "fully_emitted": true}, + {"key": "distance", "enum_value": "GeomDist", "class_name": "UMjGeomDistSensor", "header": "MjGeomDistSensor.h", "fully_emitted": true}, + {"key": "normal", "enum_value": "GeomNormal", "class_name": "UMjGeomNormalSensor", "header": "MjGeomNormalSensor.h", "fully_emitted": true}, + {"key": "fromto", "enum_value": "GeomFromTo", "class_name": "UMjGeomFromToSensor", "header": "MjGeomFromToSensor.h", "fully_emitted": true}, + {"key": "contact", "enum_value": "Contact", "class_name": "UMjContactSensor", "header": "MjContactSensor.h", "fully_emitted": true}, + {"key": "e_potential", "enum_value": "EPotential", "class_name": "UMjEPotentialSensor", "header": "MjEPotentialSensor.h", "fully_emitted": true}, + {"key": "e_kinetic", "enum_value": "EKinetic", "class_name": "UMjEKineticSensor", "header": "MjEKineticSensor.h", "fully_emitted": true}, + {"key": "clock", "enum_value": "Clock", "class_name": "UMjClockSensor", "header": "MjClockSensor.h", "fully_emitted": true}, {"key": "tactile", "enum_value": "Tactile", "class_name": "UMjTactileSensor", "header": "MjTactileSensor.h"}, - {"key": "user", "enum_value": "User", "class_name": "UMjUserSensor", "header": "MjUserSensor.h"}, - {"key": "plugin", "enum_value": "Plugin", "class_name": "UMjPluginSensor", "header": "MjPluginSensor.h"} + {"key": "user", "enum_value": "User", "class_name": "UMjUserSensor", "header": "MjUserSensor.h", "fully_emitted": true}, + {"key": "plugin", "enum_value": "Plugin", "class_name": "UMjPluginSensor", "header": "MjPluginSensor.h", "fully_emitted": true} ] }, @@ -666,9 +774,13 @@ "schema_common_block": "joint.attrs", "type_enum_name": "EMjJointType", "subtypes": [ - {"key": "hinge", "enum_value": "Hinge", "class_name": "UMjHingeJoint", "header": "MjHingeJoint.h"}, - {"key": "slide", "enum_value": "Slide", "class_name": "UMjSlideJoint", "header": "MjSlideJoint.h"}, - {"key": "ball", "enum_value": "Ball", "class_name": "UMjBallJoint", "header": "MjBallJoint.h"}, + {"key": "hinge", "enum_value": "Hinge", "class_name": "UMjHingeJoint", "header": "MjHingeJoint.h", "fully_emitted": true, + "_note_extra_ctor": "UMjJoint::ExportTo only writes Element->type when bOverride_Type is true. Without this flag set in the subclass ctor, BP-spawned joints fall back to the mjsJoint default (mjJNT_HINGE), silently substituting Ball/Slide joints for Hinge.", + "extra_constructor": "bOverride_Type = true;"}, + {"key": "slide", "enum_value": "Slide", "class_name": "UMjSlideJoint", "header": "MjSlideJoint.h", "fully_emitted": true, + "extra_constructor": "bOverride_Type = true;"}, + {"key": "ball", "enum_value": "Ball", "class_name": "UMjBallJoint", "header": "MjBallJoint.h", "fully_emitted": true, + "extra_constructor": "bOverride_Type = true;"}, {"key": "free", "enum_value": "Free", "class_name": "UMjFreeJoint", "header": "MjFreeJoint.h"} ] }, @@ -710,6 +822,18 @@ "schema_common_block": "equality.weld", "schema_common_extra_attrs": ["polycoef"], "type_enum_name": "EMjEqualityType", + "_note_objtype_dispatch": "mjsEquality.objtype tells MuJoCo what kind of object name1/name2 refer to. Connect/Weld are dual-mode: site-to-site if site1 was specified, else body-to-body. Codegen emits a switch on EqualityType into the CODEGEN_OBJTYPE_DISPATCH markers in MjEquality.cpp.", + "objtype_dispatch": { + "discriminator": "EqualityType", + "target": "Element->objtype", + "default": "mjOBJ_UNKNOWN", + "cases": [ + {"keys": ["Connect", "Weld"], "expr": "!site1.IsEmpty() ? mjOBJ_SITE : mjOBJ_BODY"}, + {"keys": ["Joint"], "expr": "mjOBJ_JOINT"}, + {"keys": ["Tendon"], "expr": "mjOBJ_TENDON"}, + {"keys": ["Flex", "FlexVert", "FlexStrain"], "expr": "mjOBJ_FLEX"} + ] + }, "subtypes": [ {"key": "connect", "enum_value": "Connect", "class_name": "UMjConnectEquality", "display_name": "MuJoCo Connect Equality"}, {"key": "weld", "enum_value": "Weld", "class_name": "UMjWeldEquality", "display_name": "MuJoCo Weld Equality"}, @@ -730,14 +854,25 @@ "mjs_struct": "mjsGeom", "schema_common_block": "geom.attrs", "type_enum_name": "EMjGeomType", + "_note_geom_final_type": "Mesh-name export depends on the COMPILE-TIME geom type, which is either the UPROPERTY Type (if overridden) or the Default geom's type (otherwise). Codegen emits the resolution + the conditional mesh-name write into the CODEGEN_GEOM_FINAL_TYPE markers in MjGeom.cpp. The value_map is pulled from element_rules.geom.xml_enum_attrs.type so there's only one source of truth for the XML/UE/mj triplet.", + "geom_final_type": { + "xml_enum_ref": "type", + "override_field": "bOverride_Type", + "default_lookup": "Default->geom->type", + "default_fallback": "mjGEOM_MESH", + "name_field": "MeshName", + "name_export_for": "mjGEOM_MESH", + "name_target": "Element->meshname", + "name_setter": "MjSetStringRaw" + }, "subtypes": [ {"key": "box", "enum_value": "Box", "class_name": "UMjBox", "header": "MjBox.h", "is_hybrid": true}, {"key": "sphere", "enum_value": "Sphere", "class_name": "UMjSphere", "header": "MjSphere.h", "is_hybrid": true}, {"key": "capsule", "enum_value": "Capsule", "class_name": "UMjCapsule", "header": "MjCapsule.h", "is_hybrid": true}, {"key": "cylinder", "enum_value": "Cylinder", "class_name": "UMjCylinder", "header": "MjCylinder.h", "is_hybrid": true}, - {"key": "ellipsoid", "enum_value": "Ellipsoid", "class_name": "UMjEllipsoid", "header": "MjEllipsoid.h", "is_hybrid": false}, - {"key": "plane", "enum_value": "Plane", "class_name": "UMjPlane", "header": "MjPlane.h", "is_hybrid": false}, - {"key": "sdf", "enum_value": "SDF", "class_name": "UMjSdf", "header": "MjSdf.h", "is_hybrid": false} + {"key": "ellipsoid", "enum_value": "Ellipsoid", "class_name": "UMjEllipsoid", "header": "MjEllipsoid.h", "is_hybrid": false, "fully_emitted": true}, + {"key": "plane", "enum_value": "Plane", "class_name": "UMjPlane", "header": "MjPlane.h", "is_hybrid": false, "fully_emitted": true}, + {"key": "sdf", "enum_value": "SDF", "class_name": "UMjSdf", "header": "MjSdf.h", "is_hybrid": false, "fully_emitted": true} ], "_note_skipped_subtypes": ["hfield (URLab has its own hfield actor system)", "mesh (existing UMjMeshGeom)"] }, @@ -817,7 +952,6 @@ "obj_type": "mjOBJ_BODY", "owner_count_var": "nbody", "include_blocks": ["MJMODEL_POINTERS_BODY", "MJMODEL_POINTERS_TREE"], - "field_renames": {}, "data_fields": { "xpos": {"index_var": "id", "stride": "3"}, "xquat": {"index_var": "id", "stride": "4"}, @@ -839,7 +973,6 @@ "MJMODEL_POINTERS_JOINT": "id", "MJMODEL_POINTERS_DOF": "dof_adr" }, - "field_renames": {}, "data_fields": { "qpos": {"index_var": "qpos_adr", "stride": "1"}, "qvel": {"index_var": "dof_adr", "stride": "1"}, @@ -852,7 +985,6 @@ "obj_type": "mjOBJ_GEOM", "owner_count_var": "ngeom", "include_blocks": ["MJMODEL_POINTERS_GEOM"], - "field_renames": {}, "data_fields": { "geom_xpos": {"index_var": "id", "stride": "3"}, "geom_xmat": {"index_var": "id", "stride": "9"} @@ -862,7 +994,6 @@ "obj_type": "mjOBJ_SITE", "owner_count_var": "nsite", "include_blocks": ["MJMODEL_POINTERS_SITE"], - "field_renames": {}, "data_fields": { "site_xpos": {"index_var": "id", "stride": "3"}, "site_xmat": {"index_var": "id", "stride": "9"} @@ -872,19 +1003,21 @@ "obj_type": "mjOBJ_ACTUATOR", "owner_count_var": "nu", "include_blocks": ["MJMODEL_POINTERS_ACTUATOR"], - "field_renames": {}, "data_fields": { - "ctrl": {"index_var": "id", "stride": "1"}, - "actuator_force":{"index_var": "id", "stride": "1"}, + "ctrl": {"index_var": "id", "stride": "1"}, + "actuator_force": {"index_var": "id", "stride": "1"}, "actuator_length":{"index_var": "id", "stride": "1"}, - "actuator_velocity":{"index_var": "id", "stride": "1"} + "actuator_velocity":{"index_var": "id", "stride": "1"}, + "_note_moment": "Per-actuator row of the actuator_moment (nu x nv) matrix. Stride is m->nv, which is a valid stride expression — no bind_override needed.", + "actuator_moment": {"index_var": "id", "stride": "m->nv"}, + "_note_act": "act lives in d->act indexed by m->actuator_actadr[id]. The adr can be -1 for actuators without an internal activation state; bind_override emits the nullable lookup so consumers can null-check ``act`` directly.", + "act": {"bind_override": "act = (m->actuator_actadr[id] >= 0) ? d->act + m->actuator_actadr[id] : nullptr;"} } }, "TendonView": { "obj_type": "mjOBJ_TENDON", "owner_count_var": "ntendon", "include_blocks": ["MJMODEL_POINTERS_TENDON"], - "field_renames": {}, "data_fields": { "ten_length": {"index_var": "id", "stride": "1"}, "ten_velocity": {"index_var": "id", "stride": "1"} @@ -894,10 +1027,290 @@ "obj_type": "mjOBJ_SENSOR", "owner_count_var": "nsensor", "include_blocks": ["MJMODEL_POINTERS_SENSOR"], - "field_renames": {}, "data_fields": { - "sensordata": {"index_var": "m->sensor_adr[id]", "stride": "m->sensor_dim[id]"} + "_note_sensordata": "Bounds-checked slice — the default base+id*stride formula is wrong for sensordata (it would double-multiply adr*dim). bind_override is a verbatim C++ statement the codegen drops inside the BIND marker.", + "sensordata": {"bind_override": "sensordata = (sensor_adr >= 0 && sensor_adr < m->nsensordata) ? d->sensordata + sensor_adr : nullptr;"} } } + }, + + "_note_editor_option_helpers": "Phase 3e.7. Codegens the trivial UMjX::GetYOptions() editor wrappers, injecting them between CODEGEN_EDITOR_OPTIONS_START/END markers inside each host .cpp's #if WITH_EDITOR block. Wrappers with real logic (TransmissionType / EqualityType / GetClassForObjType switches) stay hand-written in the same #if block.", + "editor_option_helpers": { + "wrappers": [ + {"class": "UMjActuator", "host_cpp": "MuJoCo/Components/Actuators/MjActuator.cpp", + "method": "GetSliderSiteOptions", "filter_class": "UMjSite"}, + {"class": "UMjActuator", "host_cpp": "MuJoCo/Components/Actuators/MjActuator.cpp", + "method": "GetRefSiteOptions", "filter_class": "UMjSite"}, + {"class": "UMjActuator", "host_cpp": "MuJoCo/Components/Actuators/MjActuator.cpp", + "method": "GetDefaultClassOptions", "filter_class": "UMjDefault", "include_defaults": true}, + {"class": "UMjBody", "host_cpp": "MuJoCo/Components/Bodies/MjBody.cpp", + "method": "GetChildClassOptions", "filter_class": "UMjDefault", "include_defaults": true}, + {"class": "UMjGeom", "host_cpp": "MuJoCo/Components/Geometry/MjGeom.cpp", + "method": "GetDefaultClassOptions", "filter_class": "UMjDefault", "include_defaults": true}, + {"class": "UMjSite", "host_cpp": "MuJoCo/Components/Geometry/MjSite.cpp", + "method": "GetDefaultClassOptions", "filter_class": "UMjDefault", "include_defaults": true}, + {"class": "UMjJoint", "host_cpp": "MuJoCo/Components/Joints/MjJoint.cpp", + "method": "GetDefaultClassOptions", "filter_class": "UMjDefault", "include_defaults": true}, + {"class": "UMjContactExclude","host_cpp": "MuJoCo/Components/Physics/MjContactExclude.cpp", + "method": "GetBodyOptions", "filter_class": "UMjBody"}, + {"class": "UMjContactPair", "host_cpp": "MuJoCo/Components/Physics/MjContactPair.cpp", + "method": "GetGeomOptions", "filter_class": "UMjGeom"}, + {"class": "UMjSensor", "host_cpp": "MuJoCo/Components/Sensors/MjSensor.cpp", + "method": "GetDefaultClassOptions", "filter_class": "UMjDefault", "include_defaults": true}, + {"class": "UMjTendon", "host_cpp": "MuJoCo/Components/Tendons/MjTendon.cpp", + "method": "GetDefaultClassOptions", "filter_class": "UMjDefault", "include_defaults": true} + ] + }, + + "_note_generated_enums": "Phase 2e-finalize-a. Banner-mode .h with one or more UENUMs derived from mjspec_snapshot['enums']. Hand-edits get clobbered on next regen.", + "generated_enums": { + "MjOptionEnums": { + "public_header": "MuJoCo/Generated/MjOptionEnums.h", + "enums": [ + { + "ue_name": "EMjIntegrator", + "from_mj_enum": "mjtIntegrator", + "ue_member_from_mj": { + "mjINT_EULER": "Euler", + "mjINT_RK4": "RK4", + "mjINT_IMPLICIT": "Implicit", + "mjINT_IMPLICITFAST": "ImplicitFast" + } + }, + { + "ue_name": "EMjCone", + "from_mj_enum": "mjtCone", + "ue_member_from_mj": { + "mjCONE_PYRAMIDAL": "Pyramidal", + "mjCONE_ELLIPTIC": "Elliptic" + } + }, + { + "ue_name": "EMjSolver", + "from_mj_enum": "mjtSolver", + "ue_member_from_mj": { + "mjSOL_PGS": "PGS", + "mjSOL_CG": "CG", + "mjSOL_NEWTON": "Newton" + } + } + ] + } + }, + + "_note_synthetic_categories": "Phase 2e pilot. Whole-file banner-mode emission for USTRUCTs mirroring C structs from mjxmacro_block. Hand-edits to generated files get clobbered on next regen. See generate_ue_components.py::_phase_synthetic_categories.", + "synthetic_categories": { + "MjStatistic": { + "ue_struct_name": "FMjStatistic", + "mjxmacro_block": "MJSTATISTIC_FIELDS", + "c_struct_type": "mjStatistic", + "public_header": "MuJoCo/Generated/MjStatistic.h", + "private_source": "MuJoCo/Generated/MjStatistic.cpp", + "category_label": "Statistic" + }, + + "_note_MjOption": "Codegen-emitted FMjOptionGenerated. Mirrors mjOption (MJOPTION_FIELDS) with URLab extras (MemoryMB, bEnableMultiCCD, bEnableSleep, SleepTolerance). Hand-written FMuJoCoOptions in MjSimOptions.h was removed in codegen(item-1); SimOptions on AMjArticulation and UMjPhysicsEngine now point at this struct directly.", + "MjOption": { + "ue_struct_name": "FMjOptionGenerated", + "mjxmacro_block": "MJOPTION_FIELDS", + "c_struct_type": "mjOption", + "public_header": "MuJoCo/Generated/MjOptionGenerated.h", + "private_source": "MuJoCo/Generated/MjOptionGenerated.cpp", + "category_label": "MjOption", + "include_directives": [ + "mujoco/mujoco.h", + "MuJoCo/Generated/MjOptionEnums.h" + ], + "field_renames": { + "timestep": "Timestep", + "impratio": "Impratio", + "tolerance": "Tolerance", + "ls_tolerance": "LsTolerance", + "noslip_tolerance": "NoslipTolerance", + "ccd_tolerance": "CCD_Tolerance", + "sdf_initpoints": "SdfInitPoints", + "sdf_iterations": "SdfIterations", + "iterations": "Iterations", + "ls_iterations": "LsIterations", + "noslip_iterations": "NoslipIterations", + "ccd_iterations": "CCD_Iterations", + "disableflags": "DisableFlags", + "enableflags": "EnableFlags", + "disableactuator": "DisableActuator", + "apirate": "ApiRate", + "sleep_tolerance": "SleepToleranceMj", + "rebuild_interval": "RebuildInterval" + }, + "field_types": { + "timestep": "float", + "apirate": "float", + "integrator": "EMjIntegrator", + "cone": "EMjCone", + "solver": "EMjSolver" + }, + "field_defaults": { + "Timestep": "0.002f", + "Impratio": "1.0f", + "Tolerance": "1e-8f", + "Iterations": "100", + "LsIterations": "50", + "NoslipTolerance": "1e-6f", + "CCD_Tolerance": "1e-6f", + "Gravity": "FVector(0.0f, 0.0f, -981.0f)", + "Magnetic": "FVector(0.0f, -0.5f, 0.0f)", + "Integrator": "EMjIntegrator::Euler", + "Cone": "EMjCone::Pyramidal", + "Solver": "EMjSolver::Newton" + }, + "field_apply_to_spec_mode": { + "gravity": "vec3_cm", + "wind": "vec3_cm", + "magnetic": "vec3_y_flip", + "integrator": "guarded", + "cone": "guarded", + "solver": "guarded", + "noslip_iterations": "guarded", + "noslip_tolerance": "guarded", + "ccd_iterations": "guarded", + "ccd_tolerance": "guarded" + }, + "_note_skip_vs_exclude": "field_skip_apply: emitted as UPROPERTY but not written to mjOption (apply body skips). exclude_fields: omitted from the struct entirely. exclude_fields takes precedence in iteration, so entries listed in both would be dead — keep them apart.", + "field_skip_apply": [ + "disableflags", "enableflags", "disableactuator", + "sdf_initpoints", "sdf_iterations", "sleep_tolerance" + ], + "exclude_fields": ["apirate", "rebuild_interval", "o_solref", "o_solimp", "o_friction"], + "urlab_extra_fields": [ + { + "name": "MemoryMB", + "type": "int32", + "default": "100", + "meta": "ClampMin=\"1\"", + "has_override": true + }, + { + "name": "bEnableMultiCCD", + "type": "bool", + "default": "false", + "sub_category": "Collision", + "meta": "ToolTip=\"Enable multi-contact convex collision detection. Useful for flat surfaces (e.g. mesh-mesh) where single-point contact causes sliding or wobbling.\"", + "has_override": false + }, + { + "name": "bEnableSleep", + "type": "bool", + "default": "false", + "sub_category": "Sleep", + "has_override": false + }, + { + "name": "SleepTolerance", + "type": "float", + "default": "1e-4f", + "sub_category": "Sleep", + "edit_condition": "bEnableSleep", + "has_override": false + } + ], + "apply_extras_function": "ApplyMjOptionExtras", + "emit_apply_methods": true + }, + + "_note_MjVisualStructs": "Codegen-emitted FMjVisual{Global,Headlight,Quality,Map,Scale,Rgba} parallel to mjVisual sub-blocks. All six ship today; QUALITY/MAP/SCALE/RGBA were originally empty because build_mjxmacro_snapshot.py dropped at the first XNV macro, fixed in codegen(item-2).", + "MjVisualGlobal": { + "ue_struct_name": "FMjVisualGlobal", + "mjxmacro_block": "MJVISUAL_GLOBAL_FIELDS", + "c_struct_type": "mjVisualGlobal", + "public_header": "MuJoCo/Generated/MjVisualGlobal.h", + "private_source": "MuJoCo/Generated/MjVisualGlobal.cpp", + "category_label": "Visual|Global", + "field_defaults": { + "Fovy": "45.0f", + "Ipd": "0.068f", + "Realtime": "1.0f" + } + }, + "MjVisualHeadlight": { + "ue_struct_name": "FMjVisualHeadlight", + "mjxmacro_block": "MJVISUAL_HEADLIGHT_FIELDS", + "c_struct_type": "mjVisualHeadlight", + "public_header": "MuJoCo/Generated/MjVisualHeadlight.h", + "private_source": "MuJoCo/Generated/MjVisualHeadlight.cpp", + "category_label": "Visual|Headlight", + "field_defaults": { + "Ambient": "FVector(0.1f, 0.1f, 0.1f)", + "Diffuse": "FVector(0.4f, 0.4f, 0.4f)", + "Specular": "FVector(0.5f, 0.5f, 0.5f)", + "Active": "1" + } + }, + "MjVisualQuality": { + "ue_struct_name": "FMjVisualQuality", + "mjxmacro_block": "MJVISUAL_QUALITY_FIELDS", + "c_struct_type": "mjVisualQuality", + "public_header": "MuJoCo/Generated/MjVisualQuality.h", + "category_label": "Visual|Quality", + "_note": "All quality fields are int in mjmodel.h (shadowsize=1024, offsamples=4, numslices=28, numstacks=16, numquads=4). mjxmacro carries no type info for these (bare X(name) form); explicit field_types override.", + "field_types": { + "shadowsize": "int32", "offsamples": "int32", "numslices": "int32", + "numstacks": "int32", "numquads": "int32" + }, + "field_defaults": { + "Shadowsize": "1024", "Offsamples": "4", "Numslices": "28", + "Numstacks": "16", "Numquads": "4" + } + }, + "MjVisualMap": { + "ue_struct_name": "FMjVisualMap", + "mjxmacro_block": "MJVISUAL_MAP_FIELDS", + "c_struct_type": "mjVisualMap", + "public_header": "MuJoCo/Generated/MjVisualMap.h", + "category_label": "Visual|Map", + "_note": "All map fields are float scalars in mjVisualMap (force, torque, stiffness, etc.). mjxmacro defaults them to mjtNum (double) which compiles cleanly via implicit conversion." + }, + "MjVisualScale": { + "ue_struct_name": "FMjVisualScale", + "mjxmacro_block": "MJVISUAL_SCALE_FIELDS", + "c_struct_type": "mjVisualScale", + "public_header": "MuJoCo/Generated/MjVisualScale.h", + "category_label": "Visual|Scale", + "_note": "Same as MjVisualMap — float scalars in mjmodel.h, mjxmacro defaults to mjtNum which compiles fine." + }, + "MjVisualRgba": { + "ue_struct_name": "FMjVisualRgba", + "mjxmacro_block": "MJVISUAL_RGBA_FIELDS", + "c_struct_type": "mjVisualRgba", + "public_header": "MuJoCo/Generated/MjVisualRgba.h", + "category_label": "Visual|Rgba", + "_note": "Every field is float[4] color in mjVisualRgba. mjxmacro's bare X(name) form drops that info; all_fields_type forces FLinearColor for the UPROPERTY + flips the ApplyTo emit to .R/.G/.B/.A writes.", + "all_fields_type": "FLinearColor" + }, + "_note_MjsCompilerOptions": "Mirror of mjsCompiler (MJSCOMPILER_FIELDS in mjspecmacro.h, vendored via Scripts/codegen/sync_vendored.py). Header-only USTRUCT — no .cpp emission today since URLab parses compiler settings via the legacy FMjCompilerSettings struct in MjOrientationUtils.h. Future migration: route MjArticulation through this struct + an ApplyToSpec method.", + "MjsCompilerOptions": { + "ue_struct_name": "FMjsCompilerOptions", + "mjxmacro_block": "MJSCOMPILER_FIELDS", + "c_struct_type": "mjsCompiler", + "public_header": "MuJoCo/Generated/MjsCompilerOptions.h", + "category_label": "Spec|Compiler", + "_note_exclude": "LRopt is mjLROpt (nested struct, not mirror-able as a UPROPERTY); meshdir/texturedir are mjString* (different shape — handled by the existing MeshDir/AssetDir on FMjCompilerSettings). eulerseq is a char[3] vec — mirror as FString instead, but skip in ApplyTo since FString -> char[3] needs a copy not a cast.", + "exclude_fields": ["LRopt", "meshdir", "texturedir"], + "field_skip_apply": ["eulerseq"], + "field_types": {"eulerseq": "FString"}, + "field_defaults": {"Eulerseq": "TEXT(\"xyz\")"} + }, + "_note_MjsSpec": "Mirror of mjSpec top-level fields (MJSPEC_FIELDS in mjspecmacro.h). Many entries are NESTED structs (mjsCompiler, mjOption, mjVisual, mjStatistic) — those are exposed via the dedicated FMjsCompilerOptions / FMjOptionGenerated / FMjVisual* / FMjStatistic structs. We only mirror the scalar + string fields here.", + "MjsSpec": { + "ue_struct_name": "FMjsSpec", + "mjxmacro_block": "MJSPEC_FIELDS", + "c_struct_type": "mjSpec", + "public_header": "MuJoCo/Generated/MjsSpec.h", + "category_label": "Spec", + "_note_exclude": "element/compiler/option/visual/stat are nested structs already exposed via their own synthetic_categories. modelname / comment / modelfiledir / meshdir / texturedir are mjString* — distinct shape. memory is mjtSize (handle separately).", + "exclude_fields": [ + "element", "compiler", "option", "visual", "stat", + "modelname", "comment", "modelfiledir", "meshdir", "texturedir", + "memory", "strippath" + ] + } } } diff --git a/Scripts/codegen/generate_ue_components.py b/Scripts/codegen/generate_ue_components.py index 477d92c..5110d1a 100644 --- a/Scripts/codegen/generate_ue_components.py +++ b/Scripts/codegen/generate_ue_components.py @@ -38,15 +38,17 @@ import os import re import sys -from dataclasses import dataclass +from dataclasses import dataclass, field from typing import Any, Dict, List, Optional, Sequence, Tuple SCRIPT_DIR = os.path.dirname(os.path.abspath(__file__)) PLUGIN_ROOT = os.path.abspath(os.path.join(SCRIPT_DIR, "..", "..")) -DEFAULT_SCHEMA = os.path.join(PLUGIN_ROOT, "Scripts", "mjcf_schema_snapshot.json") -DEFAULT_MJXMACRO = os.path.join(PLUGIN_ROOT, "Scripts", "mjxmacro_snapshot.json") -DEFAULT_MJSPEC = os.path.join(PLUGIN_ROOT, "Scripts", "mjspec_snapshot.json") +_SNAPSHOT_DIR = os.path.join(PLUGIN_ROOT, "Scripts", "codegen", "snapshots") +DEFAULT_SCHEMA = os.path.join(_SNAPSHOT_DIR, "mjcf_schema_snapshot.json") +DEFAULT_MJXMACRO = os.path.join(_SNAPSHOT_DIR, "mjxmacro_snapshot.json") +DEFAULT_MJSPEC = os.path.join(_SNAPSHOT_DIR, "mjspec_snapshot.json") +DEFAULT_INTROSPECT = os.path.join(_SNAPSHOT_DIR, "introspect_snapshot.json") DEFAULT_RULES = os.path.join(SCRIPT_DIR, "codegen_rules.json") DEFAULT_PUBLIC_ROOT = os.path.join(PLUGIN_ROOT, "Source", "URLab", "Public") DEFAULT_PRIVATE_ROOT= os.path.join(PLUGIN_ROOT, "Source", "URLab", "Private") @@ -183,9 +185,142 @@ class EmittedSchema: exports_cpp: str # ExportTo body (between codegen tags) +@dataclass +class EmissionContext: + """Packages the cross-cutting rules / element / call-site state that + ``emit_schema_for_attrs`` and its helpers thread through their bodies. + + Built once at the top of ``emit_schema_for_attrs`` via ``from_call``. + Phase 2 widening (2b-2e) extends this with typed-snapshot data so the + emitters don't grow new positional args on every commit. + """ + # --- caller-provided --- + attrs: Sequence[str] + rules: Dict[str, Any] + element_name: str + category_label: str + apply_canonicalizations: bool = True + mjs_fields: Optional[set] = None + consumed_by_setto: Optional[set] = None + # --- derived from rules (cached on construct) --- + global_excl: set = field(default_factory=set) + type_map: Dict[str, str] = field(default_factory=dict) + default_type: str = "float" + renames: Dict[str, str] = field(default_factory=dict) + elem_rules: Dict[str, Any] = field(default_factory=dict) + elem_excl: set = field(default_factory=set) + canonicalizations: Dict[str, Any] = field(default_factory=dict) + attr_to_mjs_field: Dict[str, str] = field(default_factory=dict) + + @classmethod + def from_call(cls, + attrs: Sequence[str], + rules: Dict[str, Any], + element_name: str, + category_label: str, + *, + apply_canonicalizations: bool = True, + mjs_fields: Optional[set] = None, + consumed_by_setto: Optional[set] = None) -> "EmissionContext": + elem_rules = rules.get("element_rules", {}).get(element_name, {}) + return cls( + attrs=attrs, + rules=rules, + element_name=element_name, + category_label=category_label, + apply_canonicalizations=apply_canonicalizations, + mjs_fields=mjs_fields, + consumed_by_setto=consumed_by_setto, + global_excl=set(rules.get("global_exclusions", [])), + type_map=rules.get("type_mappings", {}), + default_type=rules.get("default_type", "float"), + renames=rules.get("property_renames", {}), + elem_rules=elem_rules, + elem_excl=set(elem_rules.get("exclude_attrs", [])), + canonicalizations=rules.get("canonicalizations", {}), + attr_to_mjs_field=elem_rules.get("attr_to_mjs_field", {}), + ) + + def is_excluded(self, attr: str, canon_absorbed: set) -> bool: + """Common "skip this attr" check used in 4 loops.""" + return (attr in self.global_excl + or attr in self.elem_excl + or attr in canon_absorbed) + + +@dataclass +class Diagnostic: + """A non-fatal codegen warning. Collected by ``_diag_add`` during a run + and flushed once at the end via ``_diag_flush``. Replaces the prior + "build a local list inside _emit_drift_diagnostics, then print" pattern + so 2b-2e emitters can surface their own diagnostics without each + inventing a stderr channel. + """ + message: str + source: str = "" # short tag for grouping (e.g. "schema_drift", "type_fallback") + + +_DIAGS: List[Diagnostic] = [] +# Surviving counter that --strict reads after _diag_flush clears _DIAGS. +# List wrapper so nested closures can mutate the value. +_STRICT_DIAGS_FIRED: List[int] = [0] + + +def _diag_add(message: str, *, source: str = "") -> None: + _DIAGS.append(Diagnostic(message=message, source=source)) + + +def _diag_flush() -> None: + """Print collected diagnostics to stderr and clear the buffer. Format + matches the legacy ``_emit_drift_diagnostics`` output so log-greppers + keep working.""" + if not _DIAGS: + return + print(f"\n--- codegen diagnostics ({len(_DIAGS)}) ---", file=sys.stderr) + for d in _DIAGS: + print(d.message, file=sys.stderr) + print( + "(diagnostics are non-fatal; the codegen has emitted what it " + "can — fix the rules to silence them.)", + file=sys.stderr, + ) + _STRICT_DIAGS_FIRED[0] += len(_DIAGS) + _DIAGS.clear() + + +def _guarded_export(toggle: str, body: str, + extra_cond: Optional[str] = None, + extra_cond_first: bool = False, + multiline: bool = False) -> str: + """Wrap ``body`` in an ``if ({toggle})`` guard and return the indented + emission. + + ``extra_cond=None``: ``if ({toggle}) {body}`` + ``extra_cond`` + first=False: ``if ({toggle} && {extra_cond}) {body}`` + ``extra_cond`` + first=True: ``if (({extra_cond}) && {toggle}) {body}`` + + ``multiline=True``: emit a braced block. ``body`` is dropped verbatim + inside the braces (caller controls inner indent — the helper does + NOT auto-indent each line so existing multi-line bodies migrate + byte-identically). Use for blocks that were previously hand-rolled + as ``if ({toggle})\\n{{\\n\\n}}\\n``. + """ + if extra_cond is None: + cond = toggle + elif extra_cond_first: + cond = f"({extra_cond}) && {toggle}" + else: + cond = f"{toggle} && {extra_cond}" + if multiline: + return f" if ({cond})\n {{\n{body} }}\n" + return f" if ({cond}) {body}\n" + + def _attr_default_value(ue_type: str) -> str: if ue_type == "float": return "0.0f" + if ue_type == "double": return "0.0" if ue_type == "int32": return "0" + if ue_type == "uint8": return "0" if ue_type == "bool": return "false" if ue_type == "FString": return "TEXT(\"\")" if ue_type == "FVector": return "FVector::ZeroVector" @@ -197,7 +332,8 @@ def _attr_default_value(ue_type: str) -> str: def _emit_uproperty(prop_name: str, ue_type: str, category_label: str, sub_category: Optional[str] = None, - extra_meta: Optional[str] = None) -> str: + extra_meta: Optional[str] = None, + default_override: Optional[str] = None) -> str: """Emit the toggle + value UPROPERTY pair for a schema-driven attr. ``extra_meta`` appends to the value UPROPERTY's meta=() block — used to @@ -208,7 +344,7 @@ def _emit_uproperty(prop_name: str, ue_type: str, category_label: str, if sub_category: cat = f"{cat}|{sub_category}" toggle = override_toggle_name(prop_name) - default = _attr_default_value(ue_type) + default = default_override if default_override else _attr_default_value(ue_type) meta_inner = f'EditCondition="{toggle}"' if extra_meta: meta_inner = f'{meta_inner}, {extra_meta}' @@ -221,7 +357,8 @@ def _emit_uproperty(prop_name: str, ue_type: str, category_label: str, ) -def _emit_import_line(attr: str, prop_name: str, ue_type: str) -> str: +def _emit_import_line(attr: str, prop_name: str, ue_type: str, + vec3_convert: Optional[str] = None) -> str: toggle = override_toggle_name(prop_name) key = f'TEXT("{attr}")' if ue_type == "float": @@ -234,7 +371,12 @@ def _emit_import_line(attr: str, prop_name: str, ue_type: str) -> str: return (f' if (MjXmlUtils::ReadAttrString(Node, {key}, {prop_name}))' f' {toggle} = true;\n') if ue_type == "FVector": - return f' MjXmlUtils::ReadAttrVec3(Node, {key}, {prop_name}, {toggle});\n' + out = f' MjXmlUtils::ReadAttrVec3(Node, {key}, {prop_name}, {toggle});\n' + # MuJoCo direction vectors don't carry units but DO use opposite Y + # handedness vs UE. Apply Y-negate post-read when configured. + if vec3_convert == "y_negate": + out += f' if ({toggle}) {prop_name}.Y = -{prop_name}.Y;\n' + return out if ue_type == "FLinearColor": return f' MjXmlUtils::ReadAttrColor(Node, {key}, {prop_name}, {toggle});\n' if ue_type.startswith("TArray str: + consumed_by_setto: set | None = None, + export_if: str | None = None, + vec3_convert: Optional[str] = None) -> str: toggle = override_toggle_name(prop_name) + # ``export_if`` is a rule-side C++ predicate that ANDs with the toggle + # before the write fires (e.g. ``Type == EMjSiteType::Box``). Used by + # subtype-discriminated attrs whose write would be wrong for siblings. + # No current rule sets it (gate stays green); Phase 5 cleanups expected + # to enable e.g. site-size export only when site Type matches. + extra_cond = export_if # If we have an mjs field set and the attr can't be resolved to one of # them, this attr isn't directly assignable on the mjs struct (e.g. # actuator subtype params like `kp` live in gainprm[], not Element->kp). @@ -326,27 +476,49 @@ def _emit_export_line(attr: str, prop_name: str, ue_type: str, # Per-slot sentinel guard: skip slots whose value equals the # sentinel (used for `size` so fromto-only imports don't # clobber the inherited default radius / earlier slots). - return ( - f' if ({toggle}) {{ for (int32 i = 0; i < {prop_name}.Num(); ++i)' - f' {{ if ({prop_name}[i] != {slot_sentinel}) Element->{field}[i] = {prop_name}[i]; }} }}\n' + return _guarded_export(toggle, + f'{{ for (int32 i = 0; i < {prop_name}.Num(); ++i)' + f' {{ if ({prop_name}[i] != {slot_sentinel}) Element->{field}[i] = {prop_name}[i]; }} }}', + extra_cond=extra_cond, ) - return (f' if ({toggle}) {{ for (int32 i = 0; i < {prop_name}.Num(); ++i)' - f' Element->{field}[i] = {prop_name}[i]; }}\n') + return _guarded_export(toggle, + f'{{ for (int32 i = 0; i < {prop_name}.Num(); ++i)' + f' Element->{field}[i] = {prop_name}[i]; }}', + extra_cond=extra_cond, + ) if ue_type == "FVector": - return (f' if ({toggle}) {{ Element->{field}[0] = {prop_name}.X;' - f' Element->{field}[1] = {prop_name}.Y;' - f' Element->{field}[2] = {prop_name}.Z; }}\n') + if vec3_convert == "y_negate": + return _guarded_export(toggle, + f'{{ Element->{field}[0] = {prop_name}.X;' + f' Element->{field}[1] = -{prop_name}.Y;' + f' Element->{field}[2] = {prop_name}.Z; }}', + extra_cond=extra_cond, + ) + return _guarded_export(toggle, + f'{{ Element->{field}[0] = {prop_name}.X;' + f' Element->{field}[1] = {prop_name}.Y;' + f' Element->{field}[2] = {prop_name}.Z; }}', + extra_cond=extra_cond, + ) if ue_type == "FLinearColor": - return (f' if ({toggle}) {{ Element->{field}[0] = {prop_name}.R;' - f' Element->{field}[1] = {prop_name}.G;' - f' Element->{field}[2] = {prop_name}.B;' - f' Element->{field}[3] = {prop_name}.A; }}\n') + return _guarded_export(toggle, + f'{{ Element->{field}[0] = {prop_name}.R;' + f' Element->{field}[1] = {prop_name}.G;' + f' Element->{field}[2] = {prop_name}.B;' + f' Element->{field}[3] = {prop_name}.A; }}', + extra_cond=extra_cond, + ) if ue_type == "FString": - return (f' if ({toggle} && !{prop_name}.IsEmpty())' - f' mjs_setString(Element->{field}, TCHAR_TO_UTF8(*{prop_name}));\n') + # MjSetString (Public/MuJoCo/Utils/MjUtils.h) internally skips empty + # FStrings, so the previous `!X.IsEmpty()` guard collapses into the + # helper. Toggle-guard stays. + return _guarded_export(toggle, f'MjSetString(Element->{field}, {prop_name});', + extra_cond=extra_cond) if ue_type == "bool": - return f' if ({toggle}) Element->{field} = {prop_name} ? 1 : 0;\n' - return f' if ({toggle}) Element->{field} = {prop_name};\n' + return _guarded_export(toggle, f'Element->{field} = {prop_name} ? 1 : 0;', + extra_cond=extra_cond) + return _guarded_export(toggle, f'Element->{field} = {prop_name};', + extra_cond=extra_cond) # --- unit conversion ---------------------------------------------------------- @@ -425,25 +597,21 @@ def _emit_unit_conversion_export( return "" inner = "\n".join(branches) if is_array: - return ( - f" if ({toggle})\n" - f" {{\n" + body = ( f" for (int32 i = 0; i < {prop_name}.Num(); ++i)\n" f" {{\n" f" float V = {prop_name}[i];\n" f"{inner}\n" f" Element->{mjs_field}[i] = (mjtNum)V;\n" f" }}\n" - f" }}\n" ) - return ( - f" if ({toggle})\n" - f" {{\n" - f" float V = {prop_name};\n" - f"{inner}\n" - f" Element->{mjs_field} = (mjtNum)V;\n" - f" }}\n" - ) + else: + body = ( + f" float V = {prop_name};\n" + f"{inner}\n" + f" Element->{mjs_field} = (mjtNum)V;\n" + ) + return _guarded_export(toggle, body, multiline=True) def _emit_unit_conversion_block( @@ -493,12 +661,7 @@ def _apply(per_elem: str) -> str: if not branches: return "" body_lines = "\n".join(branches) - return ( - f" if ({toggle})\n" - f" {{\n" - f"{body_lines}\n" - f" }}\n" - ) + return _guarded_export(toggle, f"{body_lines}\n", multiline=True) def _emit_target_collation_import(prop_name: str, absorbs_attrs: Sequence[str]) -> str: @@ -524,28 +687,22 @@ def _emit_target_collation_import(prop_name: str, absorbs_attrs: Sequence[str]) def _emit_target_collation_export(prop_name: str, mjs_field: str) -> str: - return ( - f' if (!{prop_name}.IsEmpty()) ' - f'mjs_setString(Element->{mjs_field}, TCHAR_TO_UTF8(*{prop_name}));\n' - ) + # MjSetString skips empty FStrings internally; preserves the existing + # "only write when set" semantics without the explicit guard. + return f' MjSetString(Element->{mjs_field}, {prop_name});\n' def _emit_double_vec_export(attr: str, prop_name: str, mjs_field: str) -> str: """Emit export for an attr whose mjs counterpart is a ``mjDoubleVec*`` (std::vector*) — used by mjsKey for qpos/qvel/act/ctrl/mpos/mquat. - The mjs side requires ``->clear()`` + ``->push_back()`` per element, not - the standard ``Element->X[i] = X[i]`` pattern. Pre-condition: Element - field is non-null (mjs allocates the vector pointers on element create). + Delegates to ``MjSetDoubleVec`` (Public/MuJoCo/Utils/MjUtils.h) which + handles the ``clear() + push_back`` boilerplate. The helper accepts + a null Dest so we don't need the ``&& Element->X`` guard at the + call site. """ toggle = override_toggle_name(prop_name) - return ( - f" if ({toggle} && Element->{mjs_field})\n" - f" {{\n" - f" Element->{mjs_field}->clear();\n" - f" for (float V : {prop_name}) Element->{mjs_field}->push_back((double)V);\n" - f" }}\n" - ) + return f" if ({toggle}) MjSetDoubleVec(Element->{mjs_field}, {prop_name});\n" def _emit_data_packed_export(attr: str, packed_def: Dict[str, Any], @@ -568,7 +725,6 @@ def _emit_data_packed_export(attr: str, packed_def: Dict[str, Any], target = packed_def.get("target", "data") condition = packed_def.get("condition") toggle = override_toggle_name(prop_name) - inner_cond = toggle if condition is None else f"({condition}) && {toggle}" export_op_name = packed_def.get("export_op") op_body = "" @@ -580,23 +736,23 @@ def _emit_data_packed_export(attr: str, packed_def: Dict[str, Any], ) op_body = op["per_elem"] + def _wrap(body: str) -> str: + return _guarded_export(toggle, body, + extra_cond=condition, + extra_cond_first=True, + multiline=True) + if "slot" in packed_def: slot = packed_def["slot"] if op_body: - return ( - f" if ({inner_cond})\n" - f" {{\n" + body = ( f" float V = (float){prop_name};\n" f" {op_body}\n" f" Element->{target}[{slot}] = (mjtNum)V;\n" - f" }}\n" ) - return ( - f" if ({inner_cond})\n" - f" {{\n" - f" Element->{target}[{slot}] = (mjtNum){prop_name};\n" - f" }}\n" - ) + return _wrap(body) + body = f" Element->{target}[{slot}] = (mjtNum){prop_name};\n" + return _wrap(body) if "slot_range" in packed_def: start, end = packed_def["slot_range"] count = end - start @@ -605,28 +761,65 @@ def _emit_data_packed_export(attr: str, packed_def: Dict[str, Any], f"mjs_data_packed_attrs '{attr}': slot_range requires UE TArray; got {ue_type}" ) if op_body: - return ( - f" if ({inner_cond})\n" - f" {{\n" + body = ( f" for (int32 i = 0; i < {prop_name}.Num() && i < {count}; ++i)\n" f" {{\n" f" float V = {prop_name}[i];\n" f" {op_body}\n" f" Element->{target}[{start} + i] = (mjtNum)V;\n" f" }}\n" - f" }}\n" ) - return ( - f" if ({inner_cond})\n" - f" {{\n" + return _wrap(body) + body = ( f" for (int32 i = 0; i < {prop_name}.Num() && i < {count}; ++i)\n" f" Element->{target}[{start} + i] = (mjtNum){prop_name}[i];\n" - f" }}\n" ) + return _wrap(body) raise RuntimeError(f"mjs_data_packed_attrs '{attr}': must specify either 'slot' or 'slot_range'") -def _emit_xml_enum_import(attr: str, enum_def: Dict[str, Any]) -> str: +def _resolve_value_map(attr: str, enum_def: Dict[str, Any], + mjspec: Optional[Dict[str, Any]] = None) -> Dict[str, Sequence[str]]: + """Return the [xml_val -> [UE_enum_member, mj_const]] table for an + xml_enum attr. Three sources, checked in order: + + 1) Explicit ``value_map`` in the rule (current convention). + 2) ``value_map_from_enum: "mjtX"`` — looks up the C enum in the + introspect snapshot (mjspec / 2d) and derives the UE-side + enum_member names from a sibling ``ue_member_from_mj`` table. + Empty if 2d hasn't landed yet — falls through to (3). + 3) Error. + + The resolver lives between the emitters and the raw rules so 2d can + populate the snapshot side without each emitter learning two paths. + """ + if "value_map" in enum_def: + return enum_def["value_map"] + enum_name = enum_def.get("value_map_from_enum") + if enum_name and mjspec: + c_enum = mjspec.get("enums", {}).get(enum_name) + ue_member_from_mj: Dict[str, str] = enum_def.get("ue_member_from_mj", {}) + if c_enum: + out: Dict[str, Sequence[str]] = {} + for mj_const, _value in c_enum.items(): + ue_member = ue_member_from_mj.get(mj_const) + if not ue_member: + # No mapping → skip silently; rule author opts in per-const. + continue + xml_val = enum_def.get("xml_from_mj", {}).get(mj_const) + if not xml_val: + continue + out[xml_val] = [ue_member, mj_const] + if out: + return out + raise RuntimeError( + f"xml_enum {attr}: no value_map and value_map_from_enum did not " + f"resolve (missing snapshot enum data or ue_member_from_mj rules)" + ) + + +def _emit_xml_enum_import(attr: str, enum_def: Dict[str, Any], + mjspec: Optional[Dict[str, Any]] = None) -> str: """Emit the XML-string -> URLab-enum mapping inside CODEGEN_IMPORT. enum_def shape: @@ -640,7 +833,7 @@ def _emit_xml_enum_import(attr: str, enum_def: Dict[str, Any]) -> str: } """ ue_prop = enum_def["ue_property"] - value_map: Dict[str, Sequence[str]] = enum_def["value_map"] + value_map: Dict[str, Sequence[str]] = _resolve_value_map(attr, enum_def, mjspec) has_toggle = enum_def.get("has_override_toggle", True) ue_enum_type = enum_def.get("ue_enum_type", "") lines: List[str] = [] @@ -663,7 +856,8 @@ def _emit_xml_enum_import(attr: str, enum_def: Dict[str, Any]) -> str: return "\n".join(lines) + "\n" -def _emit_xml_enum_export(attr: str, enum_def: Dict[str, Any]) -> str: +def _emit_xml_enum_export(attr: str, enum_def: Dict[str, Any], + mjspec: Optional[Dict[str, Any]] = None) -> str: """Emit the URLab-enum -> mjt* / mjsField mapping inside CODEGEN_EXPORT. Gated on ``bOverride_X`` when ``has_override_toggle`` is true (default). @@ -677,20 +871,16 @@ def _emit_xml_enum_export(attr: str, enum_def: Dict[str, Any]) -> str: """ ue_prop = enum_def["ue_property"] ue_enum_type = enum_def.get("ue_enum_type", "") - value_map: Dict[str, Sequence[str]] = enum_def["value_map"] + value_map: Dict[str, Sequence[str]] = _resolve_value_map(attr, enum_def, mjspec) mjs_field = enum_def.get("mjs_field") if not mjs_field: return "" mjs_cast = enum_def.get("mjs_cast", "") has_toggle = enum_def.get("has_override_toggle", True) indent = " " if has_toggle else " " - lines: List[str] = [] - if has_toggle: - toggle = override_toggle_name(ue_prop) - lines.append(f" if ({toggle})") - lines.append(" {") - lines.append(f"{indent}switch ({ue_prop})") - lines.append(f"{indent}{{") + switch_lines: List[str] = [] + switch_lines.append(f"{indent}switch ({ue_prop})") + switch_lines.append(f"{indent}{{") for _, mapping in value_map.items(): if not isinstance(mapping, list) or len(mapping) < 2: raise RuntimeError( @@ -699,14 +889,16 @@ def _emit_xml_enum_export(attr: str, enum_def: Dict[str, Any]) -> str: ue_enum_member, mj_const = mapping[0], mapping[1] cast_lhs = f"Element->{mjs_field}" cast_expr = f"({mjs_cast}){mj_const}" if mjs_cast else mj_const - lines.append( + switch_lines.append( f"{indent} case {ue_enum_type}::{ue_enum_member}: {cast_lhs} = {cast_expr}; break;" ) - lines.append(f"{indent} default: break;") - lines.append(f"{indent}}}") + switch_lines.append(f"{indent} default: break;") + switch_lines.append(f"{indent}}}") + switch_body = "\n".join(switch_lines) + "\n" if has_toggle: - lines.append(" }") - return "\n".join(lines) + "\n" + toggle = override_toggle_name(ue_prop) + return _guarded_export(toggle, switch_body, multiline=True) + return switch_body def _canon_property_block(canon_name: str, canon_def: Dict[str, Any], category_label: str) -> str: @@ -722,15 +914,16 @@ def _canon_import_block(canon_name: str, canon_def: Dict[str, Any], element_name helper = canon_def["import_helper"] if canon_name == "body_sleep_policy": # MJCF body.sleep is a string ("never"/"allowed"/"init"); map to URLab's - # EMjBodySleepPolicy. Absent attr leaves SleepPolicy at its default - # (Default = let the global option decide). + # EMjBodySleepPolicy + flip bOverride_SleepPolicy so the export emits. + # Absent attr leaves both at their defaults (Auto + override=false = + # "use global sleep policy"). return ( - ' { // canonicalize body.sleep -> EMjBodySleepPolicy\n' + ' { // canonicalize body.sleep -> EMjBodySleepPolicy + bOverride_SleepPolicy\n' ' FString S = Node->GetAttribute(TEXT("sleep"));\n' ' S = S.ToLower();\n' - ' if (S == TEXT("never")) SleepPolicy = EMjBodySleepPolicy::Never;\n' - ' else if (S == TEXT("allowed")) SleepPolicy = EMjBodySleepPolicy::Allowed;\n' - ' else if (S == TEXT("init")) SleepPolicy = EMjBodySleepPolicy::InitAsleep;\n' + ' if (S == TEXT("never")) { SleepPolicy = EMjBodySleepPolicy::Never; bOverride_SleepPolicy = true; }\n' + ' else if (S == TEXT("allowed")) { SleepPolicy = EMjBodySleepPolicy::Allowed; bOverride_SleepPolicy = true; }\n' + ' else if (S == TEXT("init")) { SleepPolicy = EMjBodySleepPolicy::InitAsleep; bOverride_SleepPolicy = true; }\n' ' }\n' ) if canon_name == "actuator_transmission": @@ -826,20 +1019,21 @@ def _canon_export_block(canon_name: str, canon_def: Dict[str, Any]) -> str: prop = canon_def.get("emits_property") helper = canon_def.get("export_helper") if canon_name == "body_sleep_policy": - # Only write to mjsBody.sleep when the user chose a non-Default policy. - # Default lets the global AAMjManager option decide. - return ( - ' if (SleepPolicy != EMjBodySleepPolicy::Default)\n' - ' {\n' - ' Element->sleep = static_cast(static_cast(SleepPolicy));\n' - ' }\n' + # Only write to mjsBody.sleep when the user explicitly overrode the + # policy (bOverride_SleepPolicy). Default leaves the field alone so + # the global AAMjManager option decides. + return _guarded_export( + "bOverride_SleepPolicy", + " Element->sleep = static_cast(static_cast(SleepPolicy));\n", + multiline=True, ) if canon_name == "actuator_transmission": - # Write the URLab transmission state back to mjsActuator fields. Strings - # are only written when non-empty (mjs_setString must not be called on - # an empty FString — its TCHAR_TO_UTF8 buffer would dangle). + # Write the URLab transmission state back to mjsActuator fields. + # MjSetString skips empty FStrings; the two inner sites use the + # ...Raw variant since the outer enum + IsEmpty guard already + # ensures the FString is non-empty. return ( - ' if (!TargetName.IsEmpty()) mjs_setString(Element->target, TCHAR_TO_UTF8(*TargetName));\n' + ' MjSetString(Element->target, TargetName);\n' ' switch (TransmissionType)\n' ' {\n' ' case EMjActuatorTrnType::Joint: Element->trntype = mjTRN_JOINT; break;\n' @@ -852,11 +1046,11 @@ def _canon_export_block(canon_name: str, canon_def: Dict[str, Any]) -> str: ' }\n' ' if (TransmissionType == EMjActuatorTrnType::SliderCrank && !SliderSite.IsEmpty())\n' ' {\n' - ' mjs_setString(Element->slidersite, TCHAR_TO_UTF8(*SliderSite));\n' + ' MjSetStringRaw(Element->slidersite, SliderSite);\n' ' }\n' ' if (TransmissionType == EMjActuatorTrnType::Site && !RefSite.IsEmpty())\n' ' {\n' - ' mjs_setString(Element->refsite, TCHAR_TO_UTF8(*RefSite));\n' + ' MjSetStringRaw(Element->refsite, RefSite);\n' ' }\n' ) if canon_name == "fromto_decompose": @@ -865,23 +1059,21 @@ def _canon_export_block(canon_name: str, canon_def: Dict[str, Any]) -> str: # export-side emission needed here. return "" if canon_name == "orientation": - return ( - f' if ({override_toggle_name(prop["name"])})\n' - f' {{\n' + return _guarded_export( + override_toggle_name(prop["name"]), f' double TmpQuat[4];\n' f' {helper}({prop["name"]}, TmpQuat);\n' f' Element->quat[0] = TmpQuat[0]; Element->quat[1] = TmpQuat[1];\n' - f' Element->quat[2] = TmpQuat[2]; Element->quat[3] = TmpQuat[3];\n' - f' }}\n' + f' Element->quat[2] = TmpQuat[2]; Element->quat[3] = TmpQuat[3];\n', + multiline=True, ) if canon_name == "spatial_pose": - return ( - f' if ({override_toggle_name(prop["name"])})\n' - f' {{\n' + return _guarded_export( + override_toggle_name(prop["name"]), f' double TmpPos[3];\n' f' {helper}({prop["name"]}, TmpPos);\n' - f' Element->pos[0] = TmpPos[0]; Element->pos[1] = TmpPos[1]; Element->pos[2] = TmpPos[2];\n' - f' }}\n' + f' Element->pos[0] = TmpPos[0]; Element->pos[1] = TmpPos[1]; Element->pos[2] = TmpPos[2];\n', + multiline=True, ) return "" @@ -914,15 +1106,22 @@ def emit_schema_for_attrs( fallback "(skipped: mjs has no field)" comment to keep the emitted file uncluttered. """ - global_excl = set(rules.get("global_exclusions", [])) - type_map: Dict[str, str] = rules.get("type_mappings", {}) - default_type: str = rules.get("default_type", "float") - renames: Dict[str, str] = rules.get("property_renames", {}) - - elem_rules: Dict[str, Any] = rules.get("element_rules", {}).get(element_name, {}) - elem_excl = set(elem_rules.get("exclude_attrs", [])) + ctx = EmissionContext.from_call( + attrs, rules, element_name, category_label, + apply_canonicalizations=apply_canonicalizations, + mjs_fields=mjs_fields, + consumed_by_setto=consumed_by_setto, + ) + # Backwards-compat local aliases so the rest of the body stays unchanged. + # Phase 2b-2e migrate individual loops to ``ctx.xxx`` references. + global_excl = ctx.global_excl + type_map = ctx.type_map + default_type = ctx.default_type + renames = ctx.renames + elem_rules = ctx.elem_rules + elem_excl = ctx.elem_excl elem_canons: List[str] = elem_rules.get("applies_canonicalizations", []) - canonicalizations: Dict[str, Any] = rules.get("canonicalizations", {}) + canonicalizations = ctx.canonicalizations # All attrs absorbed by an applied canonicalisation are silently excluded # from per-attr emission (the canonicalisation owns them collectively). @@ -955,6 +1154,9 @@ def emit_schema_for_attrs( # for those (codegen only owns the import/export mapping, not the decl). xml_enum_attr_names: set = set(elem_rules.get("xml_enum_attrs", {}).keys()) prop_meta: Dict[str, str] = elem_rules.get("property_meta", {}) + # Per-attr UE default value (literal C++ expression). Used to override + # the type-derived default (e.g. joint.axis defaults to (0,0,1) not (0,0,0)). + property_defaults: Dict[str, str] = elem_rules.get("property_defaults", {}) for attr in attrs: if attr in global_excl or attr in elem_excl or attr in canon_absorbed: continue @@ -965,6 +1167,79 @@ def emit_schema_for_attrs( props += _emit_uproperty( prop_name, ue_type, category_label, extra_meta=prop_meta.get(attr), + default_override=property_defaults.get(attr) or property_defaults.get(prop_name), + ) + + # 2a) Common imports (name / class). These attrs are globally excluded + # from per-attr emission because their destination UPROPERTY isn't + # the literal attr name (e.g. ``name`` → ``MjName``). Rule-driven + # ``common_imports: ["name", "class"]`` (or per-attr dict form) emits + # the boilerplate ReadAttrString at the TOP of the import block, + # eliminating the same 1-2 hand-written lines that used to repeat + # across every component's ImportFromXml. + _COMMON_IMPORT_FIELDS = {"name": "MjName", "class": "MjClassName"} + common_imports_list = ctx.elem_rules.get("common_imports", []) if apply_canonicalizations else [] + if common_imports_list: + common_block = "" + for entry in common_imports_list: + if isinstance(entry, str): + attr = entry + ue_field = _COMMON_IMPORT_FIELDS.get(attr, attr) + else: + attr = entry["attr"] + ue_field = entry.get("ue_field", _COMMON_IMPORT_FIELDS.get(attr, attr)) + common_block += ( + f' MjXmlUtils::ReadAttrString(Node, TEXT("{attr}"), {ue_field});\n' + ) + imports = common_block + imports + + # 2b) Optional xml_enum UPROPERTY decls. Today URLab hand-declares the + # UE-side enum properties (e.g. ``EMjJointType Type`` in MjJoint.h). + # A rule can opt-in to codegen emitting the decl by setting + # ``emit_property_decl: true`` on its xml_enum_attrs entry. No current + # rule opts in (gate stays green); Phase 5 cleanup moves hand-decl'd + # enum props into codegen-managed regions and flips this flag. + # ``emit_property_decl`` only fires on the BASE-class emission + # (``apply_canonicalizations=True``). Otherwise each subclass would + # re-emit the same UPROPERTY and UHT errors with "shadowing not + # allowed". This matches the canonicalization-block emission policy. + xml_enum_attrs_for_props: Dict[str, Any] = ( + elem_rules.get("xml_enum_attrs", {}) if apply_canonicalizations else {} + ) + for attr, enum_def in xml_enum_attrs_for_props.items(): + if not enum_def.get("emit_property_decl"): + continue + ue_prop = enum_def.get("ue_property") + ue_enum_type = enum_def.get("ue_enum_type") + if not ue_prop or not ue_enum_type: + continue + # Per-rule default (``property_default``) lets the enum decl take + # a real initializer like ``EMjGainType::Fixed`` instead of the + # ``{}`` fallback that ``_attr_default_value`` would produce for + # unknown types. Cross-check the default against the value_map's + # UE members so a typo (``property_default: "Fxed"``) surfaces as + # a codegen diagnostic, not a misleading UHT compile error. + prop_default = enum_def.get("property_default") + if prop_default: + value_map = enum_def.get("value_map", {}) + valid_members = {m[0] for m in value_map.values() + if isinstance(m, (list, tuple)) and m} + if valid_members and prop_default not in valid_members: + _diag_add( + f"[diagnostic] xml_enum '{attr}' property_default " + f"'{prop_default}' is not in value_map UE members " + f"({sorted(valid_members)}); UPROPERTY default will " + f"fail UHT compile.", + source="property_default", + ) + full_default = ( + f"{ue_enum_type}::{prop_default}" + if prop_default else None + ) + props += _emit_uproperty( + ue_prop, ue_enum_type, category_label, + extra_meta=enum_def.get("property_meta"), + default_override=full_default, ) # 3a) XML enum attr imports run FIRST so downstream emission can depend @@ -995,6 +1270,9 @@ def _should_emit_xml_enum(attr: str) -> bool: # canon like fromto_decompose can override individual slots (e.g. # ``size[1] = halflength``) on top of the XML-provided values without # being clobbered by a later per-attr read. + # Per-attr vec3 conversion (currently: "y_negate" for direction vectors + # like joint.axis that need MuJoCo→UE handedness flip without scaling). + vec3_convert_map: Dict[str, str] = elem_rules.get("vec3_convert", {}) for attr in attrs: if attr in global_excl or attr in elem_excl or attr in canon_absorbed: continue @@ -1002,7 +1280,8 @@ def _should_emit_xml_enum(attr: str) -> bool: continue ue_type = type_map.get(attr, default_type) prop_name = renames.get(attr, pascal_case(attr)) - imports += _emit_import_line(attr, prop_name, ue_type) + imports += _emit_import_line(attr, prop_name, ue_type, + vec3_convert=vec3_convert_map.get(attr)) # 3c) Canonicalisations now run AFTER per-attr imports. for c in elem_canons: @@ -1109,6 +1388,9 @@ def _should_emit_xml_enum(attr: str) -> bool: if apply_canonicalizations: for prop_name, coll_def in target_collations.items(): target_collation_absorbed.update(coll_def.get("absorbs_attrs", [])) + # Per-attr ``export_if`` predicates from rules — ANDed with the toggle + # at emit time. No current rule sets this (gate stays green). + export_if_map: Dict[str, str] = elem_rules.get("export_if", {}) for attr in attrs: if attr in global_excl or attr in elem_excl or attr in canon_absorbed: continue @@ -1132,6 +1414,8 @@ def _should_emit_xml_enum(attr: str) -> bool: slot_sentinel=sentinel_skip.get(attr), attr_to_mjs_field=attr_to_mjs_field, consumed_by_setto=consumed_by_setto, + export_if=export_if_map.get(attr), + vec3_convert=vec3_convert_map.get(attr), ) # 6b) Data-packed exports (e.g. mjsEquality.data[]). Run AFTER per-attr @@ -1178,6 +1462,7 @@ def emit_xml_passthrough_body( attrs: Sequence[str], rules: Dict[str, Any], element_name: str, + mjspec: Optional[Dict[str, Any]] = None, ) -> str: """Emit the body of a `BuildSchemaAttrsXml() const -> FString` method. @@ -1251,10 +1536,15 @@ def emit_xml_passthrough_body( lines.append(" }") # xml_enum_attrs: emit the XML attribute string for the chosen enum value. + # Uses the shared _resolve_value_map helper so a rule can opt into the + # snapshot-driven ``value_map_from_enum`` form without this emitter + # crashing on a missing literal ``value_map`` key (the form is the same + # bug class that bit the XNV regex — a second copy of the resolution + # logic always drifts). for attr, enum_def in xml_enum_attrs.items(): ue_prop = enum_def["ue_property"] ue_enum = enum_def["ue_enum_type"] - value_map = enum_def["value_map"] + value_map = _resolve_value_map(attr, enum_def, mjspec) toggle = override_toggle_name(ue_prop) lines.append(f" if ({toggle})") lines.append(" {") @@ -1486,6 +1776,75 @@ def _resolve_include_path(public_root: str, file_relpath: str) -> str: return rel.replace(os.sep, "/") +_BANNER_TEMPLATE_INCLUDES = { + "MuJoCo/Utils/MjXmlUtils.h", + "MuJoCo/Utils/MjOrientationUtils.h", + "MuJoCo/Utils/MjUtils.h", + "XmlNode.h", + "mujoco/mjspec.h", +} + + +def _audit_banner_safety(source_path: str, subtype: Dict[str, Any]) -> None: + """Scan an existing source file the codegen is ABOUT to overwrite via + ``fully_emitted: true`` and emit a diagnostic if it carries content + the template wouldn't reproduce (extra includes beyond the template + set, extra method definitions, ctor extras not in ``extra_constructor``). + + Non-fatal — the rewrite still proceeds. The diagnostic exists so a + rule author who flips ``fully_emitted: true`` without running the + audit helper sees a loud warning the next time the codegen runs. + """ + try: + with open(source_path, "r", encoding="utf-8") as f: + text = f.read() + except OSError: + return + + rel = os.path.basename(source_path) + own_h = os.path.splitext(rel)[0] + ".h" + + # Extra includes beyond the template set. + extras = [] + for inc in re.findall(r'#include\s+"([^"]+)"', text): + if inc.endswith(own_h) or inc in _BANNER_TEMPLATE_INCLUDES: + continue + extras.append(inc) + if extras: + _diag_add( + f"[diagnostic] fully_emitted: true on '{subtype.get('class_name', rel)}' " + f"is about to OVERWRITE {rel} which has non-template includes " + f"{extras}. Run Scripts/codegen/_audit_banner_candidates.py " + f"before flipping, or revert fully_emitted on this subtype.", + source="banner_overwrite", + ) + + # Extra ctor lines beyond what the rule provides via extra_constructor. + expected = {subtype.get("extra_constructor", "").strip()} + expected.discard("") + class_name = subtype.get("class_name", "") + if class_name: + m = re.search( + rf'{re.escape(class_name)}::{re.escape(class_name)}\(\)\s*\{{([^}}]*)\}}', + text, + ) + if m: + body = m.group(1) + stripped = re.sub(r"(Type\s*=\s*EMj\w+::\w+;|//[^\n]*|\s+)", "", body) + for e in expected: + # The expected extras may themselves contain whitespace — + # strip to compare. + stripped = stripped.replace(re.sub(r"\s+", "", e), "") + if stripped: + _diag_add( + f"[diagnostic] fully_emitted: true on " + f"'{class_name}' is about to OVERWRITE the ctor in " + f"{rel} — non-template ctor content remains after " + f"stripping Type+extra_constructor: {stripped!r}.", + source="banner_overwrite", + ) + + def _subclass_constructor_body( category: str, subtype: Dict[str, Any], @@ -1726,7 +2085,7 @@ def emit_subclass_files( emitted = emit_schema_for_attrs( attrs, rules, element_name=category, - category_label=base_class.removeprefix("U"), + category_label=base_class.removeprefix("UMj"), apply_canonicalizations=False, # base owns the canon block mjs_fields=mjs_fields, consumed_by_setto=setto_consumed, @@ -1760,7 +2119,16 @@ def emit_subclass_files( header_path = os.path.join(pub_dir, header_filename) source_path = os.path.join(priv_dir, class_file_stem + ".cpp") - if os.path.exists(header_path): + # ``fully_emitted: true`` on a subtype rule means codegen owns the + # entire file (header + source). Existing files get overwritten + # from the template every regen — equivalent to "delete and let + # the codegen recreate", but stable across runs. Use this for + # pure-stub subclasses (no extra includes, no extra methods, ctor + # only sets Type). The ``Scripts/codegen/_audit_banner_candidates.py`` + # helper identifies the safe subset. + fully_emitted = bool(subtype.get("fully_emitted")) + + if os.path.exists(header_path) and not fully_emitted: # Existing subclass file — inject between pre-prepped tags. with open(header_path, "r", encoding="utf-8") as f: h_text = f.read() @@ -1774,7 +2142,21 @@ def emit_subclass_files( c_text, _ = inject_between_tags(c_text, "EXPORT", emitted.exports_cpp) writes.append(FileWrite(path=source_path, content=c_text)) else: - # Brand-new subclass file — emit from template. + # Brand-new file OR ``fully_emitted: true`` → write the whole + # file from the template. + # + # Safety check on the ``fully_emitted`` overwrite path: if the + # existing file carries non-template content (extra includes + # beyond the template, hand-written methods, ctor extras not + # covered by ``extra_constructor``), the rewrite would silently + # destroy it. The audit-helper script + # (Scripts/codegen/_audit_banner_candidates.py) is the + # expected pre-flip gate; this is a defence-in-depth diagnostic + # for cases where someone flips ``fully_emitted: true`` without + # running the helper first. + if fully_emitted and os.path.exists(source_path): + _audit_banner_safety(source_path, subtype) + include_path = _resolve_include_path(public_root, header_path) ctor_body = _subclass_constructor_body(category, subtype, type_enum) @@ -1839,7 +2221,7 @@ def emit_base_class_injection( common_attrs = list(common_attrs) + cat_rules.get("schema_common_extra_attrs", []) emitted = emit_schema_for_attrs( - common_attrs, rules, element_name=category, category_label=base_class.removeprefix("U"), + common_attrs, rules, element_name=category, category_label=base_class.removeprefix("UMj"), mjs_fields=mjs_fields, ) owned = codegen_owned_property_names(category, common_attrs, rules) @@ -1862,7 +2244,7 @@ def emit_base_class_injection( c_text, ok_e = inject_between_tags(c_text, "EXPORT", emitted.exports_cpp) ok_x = False if cat_rules.get("xml_passthrough_emission"): - xml_body = emit_xml_passthrough_body(common_attrs, rules, element_name=category) + xml_body = emit_xml_passthrough_body(common_attrs, rules, element_name=category, mjspec=mjspec) c_text, ok_x = inject_between_tags(c_text, "XML_PASSTHROUGH", xml_body) if ok_i or ok_e or ok_x: writes.append(FileWrite(path=source_path, content=c_text)) @@ -1923,7 +2305,7 @@ def emit_multi_uclass( attrs = [a for a in per_type_attrs if a not in common_attrs] emitted = emit_schema_for_attrs( attrs, rules, element_name=category, - category_label=base_class.removeprefix("U"), + category_label=base_class.removeprefix("UMj"), apply_canonicalizations=False, # base owns the canon block mjs_fields=mjs_fields, ) @@ -1993,27 +2375,70 @@ def emit_view_structs(rules: Dict[str, Any], mjxmacro: Dict[str, Any]) -> Dict[s bind_lines.append(f" const int {var} = {expr};") # mjModel pointer fields. + # + # Stride-1 ``int`` entries (e.g. ``geom_type``, ``body_mocapid``, + # ``actuator_trntype``) are emitted as DEREFERENCED scalars rather + # than pointers — there's exactly one int per element, and the + # consumer always wants the value, not the pointer. Matches the + # ergonomic shape the hand-written MjBind.h had before activation. + # Mat-vec entries (``geom_size`` stride 3, ``jnt_solref`` stride + # mjNREF, etc.) stay as pointers since consumers index into them. for block in include_blocks: entries = mjxmacro["mjmodel_pointers"].get(block, []) index_var = block_index_var.get(block, "id") for entry in entries: name = entry["name"] - cpp_type = _view_field_type_cpp(entry["type"]) view_field = renames.get(name, name) stride = _expand_stride(entry["stride"]) - fields_lines.append(f" {cpp_type} {view_field};") - bind_lines.append( - f" {view_field} = m->{name} + {index_var} * {stride};" - ) + is_scalar_int = (entry["type"] == "int" and entry["stride"] == "1") + if is_scalar_int: + fields_lines.append(f" int {view_field};") + bind_lines.append( + f" {view_field} = m->{name}[{index_var}];" + ) + else: + cpp_type = _view_field_type_cpp(entry["type"]) + fields_lines.append(f" {cpp_type} {view_field};") + bind_lines.append( + f" {view_field} = m->{name} + {index_var} * {stride};" + ) # mjData fields (explicitly listed per view). + # + # Each spec dict has ``index_var`` + ``stride``. Some fields don't + # fit the simple ``d->src + index_var * stride`` formula — e.g. + # SensorView::sensordata, where the right slice depends on a + # bounds-checked sensor_adr lookup. For those, set ``bind_override`` + # in the rule to a C++ statement that assigns the field; the field + # decl is still emitted at the standard cpp_type. This kills the + # fragile "codegen emits wrong code, hand-written override after + # the marker" pattern. for data_name, spec in data_fields.items(): + # ``_note_*`` keys document the data_fields entries; skip them. + if data_name.startswith("_note_"): + continue cpp_type = "mjtNum*" view_field = renames.get(data_name, data_name) - index_var = spec.get("index_var", "id") - stride = _expand_stride(spec.get("stride", "1")) fields_lines.append(f" {cpp_type} {view_field};") - bind_lines.append(f" {view_field} = d->{data_name} + {index_var} * {stride};") + bind_override = spec.get("bind_override") + if bind_override: + bind_lines.append(f" {bind_override}") + else: + index_var = spec.get("index_var", "id") + stride = _expand_stride(spec.get("stride", "1")) + bind_lines.append(f" {view_field} = d->{data_name} + {index_var} * {stride};") + + # Scalar-int fields. Used for views that need to carry a derived + # integer (e.g. a precomputed slot index, or a sentinel marker) + # rather than a pointer slice. Each entry maps ``field_name`` -> an + # expression evaluated at bind time. No current view uses these + # (gate stays green); Phase 2e adds the first synthetic_categories + # consumer. + scalar_int_fields: Dict[str, str] = view_def.get("scalar_int_fields", {}) + for field_name, expr in scalar_int_fields.items(): + view_field = renames.get(field_name, field_name) + fields_lines.append(f" int {view_field};") + bind_lines.append(f" {view_field} = {expr};") fields_block = "\n".join(fields_lines) + ("\n" if fields_lines else "") bind_block = "\n".join(bind_lines) + ("\n" if bind_lines else "") @@ -2147,24 +2572,989 @@ def emit_schema_for_tests(schema: Dict[str, Any], rules: Dict[str, Any]) -> File # Top-level orchestration # --------------------------------------------------------------------------- -def collect_all_writes( - schema: Dict[str, Any], +@dataclass +class EmissionPhase: + """One step in the codegen pipeline. Phases are run in order; each + either appends to ``writes`` (emit phases) or has side effects only + (the diagnostics phase). The registry below makes 2b-2e additions a + one-line insert rather than another `writes.extend(...)` block in + ``collect_all_writes``. + """ + name: str + fn: Any # Callable[[ctx], None]; signature varies per phase. + + +# --------------------------------------------------------------------------- +# Synthetic categories (Phase 2e): whole-file banner-mode emission +# --------------------------------------------------------------------------- +# +# "Synthetic" because the USTRUCT doesn't correspond to one entry in the +# MJCF schema (which describes XML element shapes). Instead it mirrors a +# C struct laid out in mjxmacro.h (MJOPTION_FIELDS, MJSTATISTIC_FIELDS, +# MJVISUAL_*_FIELDS) — the runtime-only state URLab exposes as USTRUCT +# blueprint properties. +# +# Files are emitted in BANNER mode (no // --- CODEGEN_*_START/END --- +# tags). The whole .h / .cpp pair is codegen-owned; hand-edits get +# clobbered on next regen. +# +# Rule shape (under top-level ``synthetic_categories`` in codegen_rules.json): +# "MjStatistic": { +# "ue_struct_name": "FMjStatistic", +# "mjxmacro_block": "MJSTATISTIC_FIELDS", +# "public_header": "MuJoCo/Generated/MjStatistic.h", +# "private_source": "MuJoCo/Generated/MjStatistic.cpp", +# "category_label": "MuJoCo|Statistic", +# "exclude_fields": [], +# "per_field_meta": { "extent": "ClampMin=0.0" }, +# "urlab_extra_fields": [], // empty for pure mirrors +# } + + +_CPP_TO_UE_TYPE = { + "int": "int32", + "float": "float", + "mjtNum": "double", + "mjtByte": "uint8", +} + + +def _ue_field_name(c_name: str) -> str: + """snake_case mjxmacro name -> PascalCase UE field. Preserves URLab's + naming convention from the hand-written MjSimOptions.h (ls_iterations + -> LsIterations, ccd_iterations -> CCD_Iterations is a deliberate + one-off — synthetic_categories rules can override via field_renames).""" + parts = c_name.split("_") + return "".join(p[:1].upper() + p[1:] for p in parts if p) + + +# Conversion macros used by synthetic_categories ApplyToSpec / Overrides +# emission for UE→MJ FVector fields. URLab convention: UE uses cm + Y-flip, +# MuJoCo uses m + RHS frame; "pos"/"vec3_cm" cm→m + Y-negate; "vec3_y_flip" +# only flips Y (no unit conversion); "passthrough" is identity. +_VEC3_CONVERT_FMT = { + "pos": "{c}[0] = {ue}.X / 100.0; {c}[1] = -{ue}.Y / 100.0; {c}[2] = {ue}.Z / 100.0;", + "vec3_cm": "{c}[0] = {ue}.X / 100.0; {c}[1] = -{ue}.Y / 100.0; {c}[2] = {ue}.Z / 100.0;", + "vec3_y_flip": "{c}[0] = {ue}.X; {c}[1] = -{ue}.Y; {c}[2] = {ue}.Z;", + "passthrough": "{c}[0] = {ue}.X; {c}[1] = {ue}.Y; {c}[2] = {ue}.Z;", +} + + +def _emit_synthetic_struct_files( + cat_name: str, def_: Dict[str, Any], mjxmacro: Dict[str, Any], + public_root: str, private_root: str, +) -> List["FileWrite"]: + """Emit the .h + .cpp pair for one synthetic_categories entry. + + Currently supports the mjxmacro_block source (X-macro field list). + mjspecmacro_block is reserved for 2d-2 once mjspecmacro.h is vendored. + """ + block_name = def_.get("mjxmacro_block") + if not block_name: + # mjspecmacro_block path not yet implemented (D8 - 2d-2 deferred). + return [] + fields = mjxmacro.get("struct_fields", {}).get(block_name, []) + if not fields: + _diag_add( + f"[diagnostic] synthetic_categories['{cat_name}'] references " + f"mjxmacro_block='{block_name}' which is empty or missing in " + f"the snapshot. Skipping emission.", + source="synthetic_categories", + ) + return [] + + ue_struct = def_["ue_struct_name"] + category_label = def_.get("category_label", "MuJoCo") + exclude = set(def_.get("exclude_fields", [])) + field_renames: Dict[str, str] = def_.get("field_renames", {}) + field_types: Dict[str, str] = def_.get("field_types", {}) + # ``all_fields_type``: short-circuit type/shape derivation for blocks + # where every X(name) bare entry is the same shape (e.g. mjVisualRgba + # — every field is float[4] / FLinearColor). Applied AFTER field_types + # so per-field overrides win. + all_fields_type: Optional[str] = def_.get("all_fields_type") + field_defaults: Dict[str, str] = def_.get("field_defaults", {}) + field_sub_category: Dict[str, str] = def_.get("field_sub_category", {}) + field_meta: Dict[str, str] = def_.get("field_meta", {}) + field_apply_mode: Dict[str, str] = def_.get("field_apply_to_spec_mode", {}) + field_skip_apply: set = set(def_.get("field_skip_apply", [])) + per_field_meta: Dict[str, str] = def_.get("per_field_meta", {}) + public_relpath = def_["public_header"] + private_relpath = def_.get("private_source") + extra_includes: List[str] = def_.get("include_directives", []) + urlab_extras: List[Dict[str, Any]] = def_.get("urlab_extra_fields", []) + apply_extras_function: Optional[str] = def_.get("apply_extras_function") + emit_apply_methods: bool = bool(def_.get("emit_apply_methods", False)) + + # ---------- pass 1: UPROPERTY emission ---------- + prop_lines: List[str] = [] + fields_meta: List[Dict[str, Any]] = [] # used by apply emission below + for f in fields: + c_name = f["name"] + if c_name in exclude: + continue + ue_name = field_renames.get(c_name, _ue_field_name(c_name)) + c_type = f["type"] + is_vec = f.get("is_vec", False) + count = int(f.get("count", "1") if isinstance(f.get("count"), str) and f["count"].isdigit() else 1) + + # Type mapping. field_types override wins; otherwise default by shape. + if c_name in field_types: + ue_type = field_types[c_name] + elif all_fields_type: + ue_type = all_fields_type + elif is_vec and count == 3: + ue_type = "FVector" + elif is_vec and count == 4: + ue_type = "FLinearColor" + elif is_vec: + ue_type = "TArray" + else: + ue_type = _CPP_TO_UE_TYPE.get(c_type, "float") + + sub_category = field_sub_category.get(ue_name) or field_sub_category.get(c_name) + meta_extra = field_meta.get(ue_name) or field_meta.get(c_name) or per_field_meta.get(c_name) + default_override = field_defaults.get(ue_name) or field_defaults.get(c_name) + + # Build the toggle + value UPROPERTY pair, honouring the default + # override if present. + cat = f"MuJoCo|{category_label}" + if sub_category: + cat = f"{cat}|{sub_category}" + toggle = override_toggle_name(ue_name) + default = default_override if default_override else _attr_default_value(ue_type) + meta_inner = f'EditCondition="{toggle}"' + if meta_extra: + meta_inner = f'{meta_inner}, {meta_extra}' + prop_lines.append( + f' UPROPERTY(EditAnywhere, Category = "{cat}", meta=(InlineEditConditionToggle))\n' + f' bool {toggle} = false;\n\n' + f' UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "{cat}", meta=({meta_inner}))\n' + f' {ue_type} {ue_name} = {default};\n\n' + ) + fields_meta.append({ + "c_name": c_name, + "ue_name": ue_name, + "ue_type": ue_type, + "is_vec": is_vec, + "count": count, + }) + + # ---------- URLab extras UPROPERTYs ---------- + extras_meta: List[Dict[str, Any]] = [] + for extra in urlab_extras: + ue_name = extra["name"] + ue_type = extra["type"] + default = extra.get("default", _attr_default_value(ue_type)) + sub_category = extra.get("sub_category") + has_override = extra.get("has_override", True) + edit_condition = extra.get("edit_condition") + meta_extra = extra.get("meta") + cat = f"MuJoCo|{category_label}" + if sub_category: + cat = f"{cat}|{sub_category}" + if has_override: + toggle = override_toggle_name(ue_name) + meta_inner = f'EditCondition="{toggle}"' + if meta_extra: + meta_inner = f'{meta_inner}, {meta_extra}' + prop_lines.append( + f' UPROPERTY(EditAnywhere, Category = "{cat}", meta=(InlineEditConditionToggle))\n' + f' bool {toggle} = false;\n\n' + f' UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "{cat}", meta=({meta_inner}))\n' + f' {ue_type} {ue_name} = {default};\n\n' + ) + else: + meta_parts = [] + if edit_condition: + meta_parts.append(f'EditCondition="{edit_condition}"') + if meta_extra: + meta_parts.append(meta_extra) + meta_str = ", ".join(meta_parts) + meta_clause = f', meta=({meta_str})' if meta_str else "" + prop_lines.append( + f' UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "{cat}"{meta_clause})\n' + f' {ue_type} {ue_name} = {default};\n\n' + ) + extras_meta.append({"ue_name": ue_name, "type": ue_type, + "has_override": has_override}) + + properties_block = "".join(prop_lines) + c_struct = def_.get("c_struct_type", block_name.lower().replace("_fields", "")) + + # ---------- header content ---------- + extra_includes_block = "".join(f'#include "{inc}"\n' for inc in extra_includes) + header_basename = os.path.basename(public_relpath).replace('.h', '') + public_path = os.path.join(public_root, public_relpath.replace("/", os.sep)) + + # Method decls in the header. If emit_apply_methods=True, declare + # ApplyToSpec / ApplyOverridesToModel as forward decls (definitions + # land in the .cpp). + method_decls = "" + if emit_apply_methods: + method_decls = ( + f" /** @brief Writes every mirror field plus URLab extras into the " + f"runtime spec. Used by articulations to set child spec options. */\n" + f" void ApplyToSpec(mjSpec* Spec) const;\n\n" + f" /** @brief Applies only override-toggled mirror fields to a " + f"compiled model (post-compile override path). */\n" + f" void ApplyOverridesToModel(mjModel* Model) const;\n" + ) + else: + # Templated inline ApplyTo for pure-mirror structs (mjStatistic etc.). + apply_lines: List[str] = [] + for fm in fields_meta: + c_name = fm["c_name"] + ue_name = fm["ue_name"] + # ``field_skip_apply`` honored here too — used when the field + # is mirrored as a different UE type (e.g. char[3] eulerseq + # mirrored as FString) and the per-element cast won't compile. + if c_name in field_skip_apply: + continue + # FLinearColor handled by ue_type takes precedence over snapshot + # is_vec/count — used by all_fields_type='FLinearColor' for + # mjVisualRgba where every C field is float[4] but the X-macro + # form is bare X(name). + if fm["ue_type"] == "FLinearColor": + apply_lines.append( + f" Dst.{c_name}[0] = (decltype(Dst.{c_name}[0])){ue_name}.R;\n" + f" Dst.{c_name}[1] = (decltype(Dst.{c_name}[1])){ue_name}.G;\n" + f" Dst.{c_name}[2] = (decltype(Dst.{c_name}[2])){ue_name}.B;\n" + f" Dst.{c_name}[3] = (decltype(Dst.{c_name}[3])){ue_name}.A;" + ) + elif fm["ue_type"] == "FVector": + apply_lines.append( + f" Dst.{c_name}[0] = (decltype(Dst.{c_name}[0])){ue_name}.X;\n" + f" Dst.{c_name}[1] = (decltype(Dst.{c_name}[1])){ue_name}.Y;\n" + f" Dst.{c_name}[2] = (decltype(Dst.{c_name}[2])){ue_name}.Z;" + ) + elif fm["is_vec"]: + apply_lines.append( + f" for (int32 I = 0; I < {ue_name}.Num() && I < {fm['count']}; ++I)\n" + f" Dst.{c_name}[I] = (decltype(Dst.{c_name}[0])){ue_name}[I];" + ) + else: + apply_lines.append(f" Dst.{c_name} = (decltype(Dst.{c_name})){ue_name};") + method_decls = ( + f" /** @brief Mirror every field into a runtime C struct. */\n" + f" template \n" + f" void ApplyTo(TDst& Dst) const\n" + f" {{\n" + f"{chr(10).join(apply_lines)}\n" + f" }}\n" + ) + + # Forward-decl the extras function so the codegen-emitted .cpp can + # call it without #including a hand-written header. Operator writes + # the body in *Extras.cpp. + extras_forward_decl = "" + if apply_extras_function and urlab_extras: + extras_forward_decl = ( + f"// Forward-decl: hand-written body lives in " + f"{os.path.basename(public_relpath).replace('.h', '')}Extras.cpp.\n" + f"struct {ue_struct};\n" + f"void {apply_extras_function}(" + f"mjOption* Opt, const {ue_struct}& Self, " + f"mjSpec* Spec, mjModel* Model = nullptr);\n\n" + ) + + header_content = ( + f"{COPYRIGHT_BLOCK}\n" + f"#pragma once\n\n" + f"#include \"CoreMinimal.h\"\n" + f"{extra_includes_block}" + f"#include \"{header_basename}.generated.h\"\n\n" + f"{extras_forward_decl}" + f"// Mirror of MuJoCo's ``{c_struct}`` ({block_name}). Codegen-owned —\n" + f"// hand-edits get clobbered on next regen. Add fields by editing\n" + f"// codegen_rules.json[synthetic_categories.{cat_name}].\n" + f"USTRUCT(BlueprintType)\n" + f"struct URLAB_API {ue_struct}\n" + f"{{\n" + f" GENERATED_BODY()\n\n" + f"{properties_block}" + f"{method_decls}" + f"}};\n" + ) + + writes: List[FileWrite] = [FileWrite(path=public_path, content=header_content)] + + # ---------- emit .cpp when apply methods are out-of-line ---------- + if emit_apply_methods and private_relpath: + apply_to_spec_lines: List[str] = [" if (!Spec) return;"] + apply_to_model_lines: List[str] = [" if (!Model) return;"] + for fm in fields_meta: + c_name = fm["c_name"] + ue_name = fm["ue_name"] + ue_type = fm["ue_type"] + if c_name in field_skip_apply: + continue + toggle = override_toggle_name(ue_name) + spec_mode = field_apply_mode.get(c_name, "unconditional") + # Compute the assignment expression(s) once. + if ue_type == "FVector": + conv = spec_mode if spec_mode.startswith("vec3") or spec_mode == "pos" else "vec3_y_flip" + if spec_mode.startswith("guarded"): + # guarded_vec3_cm / guarded_pos / guarded_vec3_y_flip etc. + conv = spec_mode.replace("guarded_", "") or "vec3_y_flip" + stmt_spec_inner = _VEC3_CONVERT_FMT.get(conv, _VEC3_CONVERT_FMT["vec3_y_flip"]).format(c=f"Spec->option.{c_name}", ue=ue_name) + stmt_model_inner = _VEC3_CONVERT_FMT.get(conv, _VEC3_CONVERT_FMT["vec3_y_flip"]).format(c=f"Model->opt.{c_name}", ue=ue_name) + elif ue_type.startswith("EMj"): + # Enum: cast to int. + stmt_spec_inner = f"Spec->option.{c_name} = (int){ue_name};" + stmt_model_inner = f"Model->opt.{c_name} = (int){ue_name};" + else: + stmt_spec_inner = f"Spec->option.{c_name} = {ue_name};" + stmt_model_inner = f"Model->opt.{c_name} = {ue_name};" + + if spec_mode.startswith("guarded") or spec_mode == "guarded": + apply_to_spec_lines.append(f" if ({toggle}) {{ {stmt_spec_inner} }}") + else: + apply_to_spec_lines.append(f" {stmt_spec_inner}") + # ApplyOverridesToModel is always guarded. + apply_to_model_lines.append(f" if ({toggle}) {{ {stmt_model_inner} }}") + + # Append URLab-extras hook. + if apply_extras_function and urlab_extras: + apply_to_spec_lines.append( + f" {apply_extras_function}(Spec ? &Spec->option : nullptr, *this, Spec);" + ) + apply_to_model_lines.append( + f" {apply_extras_function}(Model ? &Model->opt : nullptr, *this, nullptr, Model);" + ) + + cpp_basename = os.path.basename(private_relpath).replace(".cpp", "") + cpp_content = ( + f"{COPYRIGHT_BLOCK}\n" + f"#include \"{os.path.dirname(public_relpath).replace(os.sep, '/')}/{header_basename}.h\"\n" + f"#include \n\n" + f"void {ue_struct}::ApplyToSpec(mjSpec* Spec) const\n" + f"{{\n" + + "\n".join(apply_to_spec_lines) + "\n" + f"}}\n\n" + f"void {ue_struct}::ApplyOverridesToModel(mjModel* Model) const\n" + f"{{\n" + + "\n".join(apply_to_model_lines) + "\n" + f"}}\n" + ) + private_path = os.path.join(private_root, private_relpath.replace("/", os.sep)) + writes.append(FileWrite(path=private_path, content=cpp_content)) + + return writes + + +def _phase_synthetic_categories(rules, schema, mjxmacro, mjspec, + public_root, private_root, writes) -> None: + """Run after the main category walk; emits whole-file synthetic structs.""" + synth = rules.get("synthetic_categories", {}) + for cat_name, def_ in synth.items(): + # Skip _note_* sibling keys used for inline documentation. + if cat_name.startswith("_") or not isinstance(def_, dict): + continue + writes.extend(_emit_synthetic_struct_files( + cat_name, def_, mjxmacro, public_root, private_root, + )) + + +# --------------------------------------------------------------------------- +# Sensor switch + TagToType codegen (D7 follow-up) +# --------------------------------------------------------------------------- +# +# Replaces the hand-written switch + map in MjSensor.cpp with codegen +# output driven by: +# - codegen_rules.json[categories.sensor.subtypes] for XML key + enum +# value + (optional) case_body_override +# - sensor_per_type (from build_mjcf_schema_snapshot.py's Sensor() +# scrape) for mj_type + static objtype/reftype literals +# +# Variable-objtype/reftype branches (frame*, geomdist, contact, plugin, +# user) stay hand-written in the post-switch block — that block reads +# UE-side ObjType / RefType properties and applies them after the +# codegen case fires. + +def _emit_sensor_switch_block(cat_rules: Dict[str, Any], + sensor_per_type: Dict[str, Any]) -> str: + """One ``case EMjSensorType::X: ...`` per subtype + the default fallback. + Lives between ``CODEGEN_SENSOR_TYPE_SWITCH_*`` markers in MjSensor.cpp. + """ + lines: List[str] = [] + type_enum = cat_rules.get("type_enum_name", "EMjSensorType") + for subtype in cat_rules.get("subtypes", []): + key = subtype["key"] + enum_value = subtype["enum_value"] + override = subtype.get("case_body_override") + if override: + lines.append(f" case {type_enum}::{enum_value}:") + lines.append(f" {override} break;") + continue + per = sensor_per_type.get(key, {}) + mj_type = per.get("mj_type") + if not mj_type: + lines.append(f" // (skipped: no mj_type for '{key}' in sensor_per_type)") + continue + stmts = [f"Element->type = {mj_type};"] + # Only emit static objtype/reftype when sensor_per_type carries a + # literal mjOBJ_X. "from_xml" and "computed" entries are handled + # by the post-switch block reading UE-side ObjType/RefType. + objtype = per.get("objtype") + if isinstance(objtype, str) and objtype.startswith("mjOBJ_"): + stmts.append(f"Element->objtype = {objtype};") + reftype = per.get("reftype") + if isinstance(reftype, str) and reftype.startswith("mjOBJ_"): + stmts.append(f"Element->reftype = {reftype};") + lines.append(f" case {type_enum}::{enum_value}: " + f"{' '.join(stmts)} break;") + # Default fallback matches the previous hand-written behaviour. + default_subtype = cat_rules.get("default_subtype_key", "accelerometer") + default_per = sensor_per_type.get(default_subtype, {}) + default_type = default_per.get("mj_type", "mjSENS_ACCELEROMETER") + default_objtype = default_per.get("objtype") or "mjOBJ_SITE" + if not (isinstance(default_objtype, str) and default_objtype.startswith("mjOBJ_")): + default_objtype = "mjOBJ_SITE" + lines.append(f" default: Element->type = {default_type}; " + f"Element->objtype = {default_objtype}; break;") + return "\n".join(lines) + "\n" + + +def _emit_sensor_tag_to_type_block(cat_rules: Dict[str, Any]) -> str: + """One ``{TEXT(""), EMjSensorType::X}`` per subtype. Lives between + ``CODEGEN_SENSOR_TAG_TO_TYPE_*`` markers in MjSensor.cpp. + """ + lines: List[str] = [] + type_enum = cat_rules.get("type_enum_name", "EMjSensorType") + for subtype in cat_rules.get("subtypes", []): + # Some subtype XML keys collide with C++ enum members that diverge + # (e.g. `key=tendonactuatorfrc`, `enum_value=TendonActFrc`, + # mjSENS_TENDONACTFRC). The tag-to-type map uses the XML key + # verbatim so MJCF lookups match. + key = subtype["key"] + enum_value = subtype["enum_value"] + lines.append(f' {{TEXT("{key}"), {type_enum}::{enum_value}}},') + return "\n".join(lines) + "\n" + + +# --------------------------------------------------------------------------- +# Generated enum headers (Phase 2e-finalize-a) +# --------------------------------------------------------------------------- +# +# Some MuJoCo C enums (mjtIntegrator/mjtCone/mjtSolver/...) map to URLab +# UENUMs that are blueprint-exposed. The hand-written copies in +# MjSimOptions.h diverge from the C source over time; this emitter +# generates them from mjspec_snapshot["enums"] data scraped in Phase 2d-1. +# +# Rule shape (under top-level ``generated_enums`` in codegen_rules.json): +# "MjOptionEnums": { +# "public_header": "MuJoCo/Generated/MjOptionEnums.h", +# "enums": [ +# { +# "ue_name": "EMjIntegrator", +# "from_mj_enum": "mjtIntegrator", +# "underlying_type": "uint8", // optional, defaults uint8 +# "ue_member_from_mj": { +# "mjINT_EULER": "Euler", +# "mjINT_RK4": "RK4", +# ... +# }, +# // Optional: members from C enum to skip in UE (e.g. internal +# // sentinels that aren't blueprint-meaningful). +# "exclude_mj_members": [] +# } +# ] +# } + + +def _emit_generated_enum_file(cat_name: str, def_: Dict[str, Any], + mjspec: Optional[Dict[str, Any]], + public_root: str) -> List["FileWrite"]: + """Emit a single banner-mode .h carrying one or more UENUMs.""" + if not mjspec or "enums" not in mjspec: + _diag_add( + f"[diagnostic] generated_enums['{cat_name}'] needs mjspec_snapshot " + f"with 'enums' key (Phase 2d-1). Skipping emission.", + source="generated_enums", + ) + return [] + enums = def_.get("enums", []) + if not enums: + return [] + + public_relpath = def_["public_header"] + header_basename = os.path.basename(public_relpath).replace(".h", "") + + enum_blocks: List[str] = [] + for entry in enums: + ue_name = entry["ue_name"] + mj_enum_name = entry["from_mj_enum"] + underlying = entry.get("underlying_type", "uint8") + ue_member_from_mj: Dict[str, str] = entry.get("ue_member_from_mj", {}) + exclude: set = set(entry.get("exclude_mj_members", [])) + c_enum = mjspec["enums"].get(mj_enum_name) + if not c_enum: + _diag_add( + f"[diagnostic] generated_enums['{cat_name}']: C enum " + f"'{mj_enum_name}' missing from mjspec_snapshot. Skipping " + f"'{ue_name}'.", + source="generated_enums", + ) + continue + member_lines: List[str] = [] + for mj_const, value in c_enum.items(): + if mj_const in exclude: + continue + ue_member = ue_member_from_mj.get(mj_const) + if not ue_member: + continue # silently skip; rule author opts in per-const + member_lines.append(f" {ue_member} = {value},") + if not member_lines: + continue + # Strip the trailing comma on the last member for cleaner C++. + member_lines[-1] = member_lines[-1].rstrip(",") + enum_blocks.append( + f"/** {ue_name} — mirror of MuJoCo's {mj_enum_name}. */\n" + f"UENUM(BlueprintType)\n" + f"enum class {ue_name} : {underlying}\n" + f"{{\n" + + "\n".join(member_lines) + "\n" + f"}};\n" + ) + + if not enum_blocks: + return [] + + content = ( + f"{COPYRIGHT_BLOCK}\n" + f"#pragma once\n\n" + f"#include \"CoreMinimal.h\"\n" + f"#include \"{header_basename}.generated.h\"\n\n" + + "\n".join(enum_blocks) + ) + public_path = os.path.join(public_root, public_relpath.replace("/", os.sep)) + return [FileWrite(path=public_path, content=content)] + + +def _phase_generated_enums(rules, schema, mjxmacro, mjspec, + public_root, private_root, writes) -> None: + gen = rules.get("generated_enums", {}) + for cat_name, def_ in gen.items(): + writes.extend(_emit_generated_enum_file( + cat_name, def_, mjspec, public_root, + )) + + +# --------------------------------------------------------------------------- +# Articulation category registry (Phase 2e-finalize-b) +# --------------------------------------------------------------------------- +# +# Emits a header with a compile-time table of every URLab-managed MuJoCo +# category, listing the schema element name, UE base class, mjs struct, +# and the layout shape. Consumers (diagnostic dumps, BP iteration, +# test-time category enumeration) can iterate constexpr instead of +# duplicating the category list in C++ source. + +# --------------------------------------------------------------------------- +# Editor option helpers (Phase 3e.7) +# --------------------------------------------------------------------------- +# +# Codegens the trivial ``TArray UMjX::GetYOptions() const`` editor +# helpers that just forward to ``UMjComponent::GetSiblingComponentOptions``. +# Wrappers with real per-class logic (UMjActuator::GetTargetNameOptions, +# UMjSensor::Get(Target|Reference)NameOptions, UMjEquality::GetObjOptions) +# stay hand-written in their owning .cpp files. +# +# Emission shape: each host .cpp file has a CODEGEN_EDITOR_OPTIONS_START/END +# marker pair inside its ``#if WITH_EDITOR`` block. The phase injects the +# class's wrappers between those markers — output stays INSIDE the host +# .cpp, not a separate file. (Avoids the ``.gen.cpp`` UHT-collision name.) +# +# Rule shape (top-level ``editor_option_helpers.wrappers``): +# [ +# { +# "class": "UMjActuator", +# "host_cpp": "MuJoCo/Components/Actuators/MjActuator.cpp", +# "method": "GetSliderSiteOptions", +# "filter_class": "UMjSite", +# "include_defaults": false +# }, +# ... +# ] + +def _phase_editor_option_helpers(rules, schema, mjxmacro, mjspec, + public_root, private_root, writes) -> None: + def_ = rules.get("editor_option_helpers") + if not def_: + return + wrappers = def_.get("wrappers", []) + if not wrappers: + return + # Group by host_cpp. + by_host: Dict[str, List[Dict[str, Any]]] = {} + for w in wrappers: + host = w.get("host_cpp") + if not host: + _diag_add( + f"[diagnostic] editor_option_helpers: missing host_cpp on " + f"wrapper {w!r}. Skipping.", + source="editor_option_helpers", + ) + continue + by_host.setdefault(host, []).append(w) + # Inject per-file. + for host_relpath, group in by_host.items(): + host_path = os.path.join(private_root, host_relpath.replace("/", os.sep)) + if not os.path.exists(host_path): + _diag_add( + f"[diagnostic] editor_option_helpers: host_cpp '{host_relpath}' " + f"not found on disk. Skipping injection.", + source="editor_option_helpers", + ) + continue + with open(host_path, "r", encoding="utf-8") as f: + text = f.read() + lines: List[str] = [] + for w in group: + cls = w["class"] + method = w["method"] + filt = w["filter_class"] + inc_def = bool(w.get("include_defaults", False)) + defaults_arg = ", true" if inc_def else "" + lines.append( + f"TArray {cls}::{method}() const {{ return " + f"UMjComponent::GetSiblingComponentOptions(this, " + f"{filt}::StaticClass(){defaults_arg}); }}" + ) + body = "\n".join(lines) + "\n" + new_text, _ = inject_between_tags(text, "EDITOR_OPTIONS", body) + if new_text != text: + writes.append(FileWrite(path=host_path, content=new_text)) + + +def _phase_articulation_registry(rules, schema, mjxmacro, mjspec, + public_root, private_root, writes) -> None: + cats = rules.get("categories", {}) + if not cats: + return + out_relpath = rules.get("articulation_registry_path", + "MuJoCo/Generated/MjArticulationRegistry.h") + entries: List[str] = [] + for name in sorted(cats): + cat = cats[name] + base = cat.get("base_class_name", "") + mjs = cat.get("mjs_struct", "") + layout = cat.get("layout", "no_subclasses") + n_subtypes = len(cat.get("subtypes", [])) + entries.append( + f' {{ TEXT("{name}"), TEXT("{base}"), TEXT("{mjs}"), ' + f'TEXT("{layout}"), {n_subtypes} }},' + ) + content = ( + f"{COPYRIGHT_BLOCK}\n" + f"#pragma once\n\n" + f"#include \"CoreMinimal.h\"\n\n" + f"// Compile-time registry of every URLab-managed MuJoCo category.\n" + f"// Codegen-owned — driven by codegen_rules.json[categories].\n" + f"namespace MjArticulationRegistry\n" + f"{{\n" + f" struct CategoryEntry\n" + f" {{\n" + f" const TCHAR* Name; // schema element name, e.g. \"body\"\n" + f" const TCHAR* BaseClassName; // UE base UClass, e.g. \"UMjBody\"\n" + f" const TCHAR* MjsStruct; // MuJoCo spec struct, e.g. \"mjsBody\"\n" + f" const TCHAR* Layout; // \"single_uclass_per_file\" / \"multi_uclass\" / \"no_subclasses\"\n" + f" int NumSubtypes;\n" + f" }};\n\n" + f" inline constexpr CategoryEntry kCategories[] = {{\n" + + "\n".join(entries) + "\n" + f" }};\n" + f" inline constexpr int kNumCategories = sizeof(kCategories) / sizeof(kCategories[0]);\n" + f"}}\n" + ) + out_path = os.path.join(public_root, out_relpath.replace("/", os.sep)) + writes.append(FileWrite(path=out_path, content=content)) + + +def _emit_objtype_dispatch_block(cat_rules: Dict[str, Any]) -> Optional[str]: + """Emit a switch on ``cat_rules['objtype_dispatch']`` that assigns + each case's ``expr`` to ``target``. Used by categories where mjs's + objtype field varies by enum value (today: MjEquality).""" + dispatch = cat_rules.get("objtype_dispatch") + if not dispatch: + return None + enum_name = cat_rules.get("type_enum_name") + if not enum_name: + _diag_add( + "[diagnostic] objtype_dispatch on category missing " + "'type_enum_name'; cannot emit case labels.", + source="objtype_dispatch", + ) + return None + discriminator = dispatch["discriminator"] + target = dispatch["target"] + default_expr = dispatch.get("default", "mjOBJ_UNKNOWN") + cases = dispatch.get("cases", []) + if not cases: + _diag_add( + f"[diagnostic] objtype_dispatch '{discriminator}' has no cases; " + f"only the default branch would emit.", + source="objtype_dispatch", + ) + return None + + lines: List[str] = [] + lines.append(f" switch ({discriminator})") + lines.append(" {") + for i, case in enumerate(cases): + keys = case.get("keys", []) + if not keys: + _diag_add( + f"[diagnostic] objtype_dispatch case #{i} has empty " + f"'keys' list; would emit a body with no case label.", + source="objtype_dispatch", + ) + return None + if "expr" not in case: + _diag_add( + f"[diagnostic] objtype_dispatch case #{i} (keys={keys}) " + f"missing 'expr'.", + source="objtype_dispatch", + ) + return None + for k in keys: + lines.append(f" case {enum_name}::{k}:") + # last case of the group emits the body + break. + lines.append(f" {target} = {case['expr']};") + lines.append(" break;") + lines.append(" default:") + lines.append(f" {target} = {default_expr};") + lines.append(" break;") + lines.append(" }") + return "\n".join(lines) + "\n" + + +def _inject_into_category_cpp( rules: Dict[str, Any], - mjxmacro: Dict[str, Any], - public_root: str, private_root: str, - bind_h_path: str, - mjspec: Dict[str, Any] | None = None, -) -> List[FileWrite]: - """Walk every category in `codegen_rules.json` and produce the full set - of file writes the codegen would perform. No I/O side effects.""" - writes: List[FileWrite] = [] - categories: Dict[str, Any] = rules.get("categories", {}) + writes: List["FileWrite"], + tag: str, + emit_fn, + *, + diag_source: str, +) -> None: + """Shared scaffolding: walk every category, call ``emit_fn(cat_rules)``, + inject the result between ``CODEGEN__START/END`` markers in the + category's base-class .cpp. ``emit_fn`` returns ``None`` to skip + (already diagnosed inside the emit_fn). The function does its own + diagnostics for missing files / missing markers — silent skip would + let a rule author bake an unreachable block into the rules JSON + without realising it never fires.""" + for cat_name, cat_rules in rules.get("categories", {}).items(): + body = emit_fn(cat_rules) + if body is None: + continue + base_header = cat_rules.get("base_class_header") + if not base_header: + _diag_add( + f"[diagnostic] category '{cat_name}' has codegen rule for " + f"{diag_source} but no 'base_class_header'; block not emitted.", + source=diag_source, + ) + continue + cpp_path = os.path.join( + private_root, base_header.replace(".h", ".cpp"), + ) + if not os.path.exists(cpp_path): + _diag_add( + f"[diagnostic] {diag_source}: host .cpp '{cpp_path}' " + f"does not exist; block not emitted.", + source=diag_source, + ) + continue + with open(cpp_path, "r", encoding="utf-8") as f: + text = f.read() + new_text, ok = inject_between_tags(text, tag, body) + if not ok: + _diag_add( + f"[diagnostic] {diag_source}: '{cpp_path}' is missing the " + f"CODEGEN_{tag}_START/END marker pair; block not injected.", + source=diag_source, + ) + continue + if new_text != text: + writes.append(FileWrite(path=cpp_path, content=new_text)) + + +def _phase_objtype_dispatch(rules, schema, mjxmacro, mjspec, + public_root, private_root, writes) -> None: + """Inject objtype dispatch block; host .cpp must carry + ``CODEGEN_OBJTYPE_DISPATCH_START/END`` markers.""" + _inject_into_category_cpp( + rules, private_root, writes, + tag="OBJTYPE_DISPATCH", + emit_fn=_emit_objtype_dispatch_block, + diag_source="objtype_dispatch", + ) + + +def _emit_geom_final_type_block(cat_rules: Dict[str, Any], + element_rules: Dict[str, Any], + mjspec: Optional[Dict[str, Any]] = None) -> Optional[str]: + """Emit MjGeom's FinalType resolution + mesh-name export. Specific + to geom because the mesh-name write depends on the COMPILE-TIME geom + type (UPROPERTY Type if overridden, else Default's type). + + The value_map is pulled from ``element_rules[xml_enum_ref]`` via + ``_resolve_value_map`` so rules using the snapshot-driven + ``value_map_from_enum`` form work alongside the literal-map form. + Returns None (with a diagnostic) when the xml_enum_ref entry is + missing — silent failure here would drop the block from MjGeom.cpp + and only surface as a runtime mesh-bind error. + """ + final = cat_rules.get("geom_final_type") + if not final: + return None + xml_enum_attrs = element_rules.get("xml_enum_attrs", {}) + attr_key = final["xml_enum_ref"] + enum_def = xml_enum_attrs.get(attr_key) + if not enum_def: + _diag_add( + f"[diagnostic] geom_final_type references xml_enum '{attr_key}' " + f"that doesn't exist in element_rules; FinalType block will be " + f"empty and mesh-name export will not fire.", + source="geom_final_type", + ) + return None + value_map = _resolve_value_map(attr_key, enum_def, mjspec) + if not value_map: + _diag_add( + f"[diagnostic] geom_final_type xml_enum '{attr_key}' resolved " + f"to an empty value_map; FinalType switch would have no cases.", + source="geom_final_type", + ) + return None + ue_prop = enum_def["ue_property"] + ue_enum = enum_def["ue_enum_type"] + + override = final["override_field"] + default_lookup = final["default_lookup"] + fallback = final["default_fallback"] + name_field = final["name_field"] + name_for = final["name_export_for"] + name_target = final["name_target"] + name_setter = final["name_setter"] + # Placeholder for the FinalType init when override=true: any mj_const + # works because the switch below remaps. Pick the value_map's first + # entry for stability. + first_mj = next(iter(value_map.values()))[1] + + lines: List[str] = [] + lines.append(f" int FinalType = {override}") + lines.append(f" ? {first_mj} /* placeholder; remapped below */") + lines.append(f" : (Default ? {default_lookup} : {fallback});") + lines.append(f" if ({override})") + lines.append(" {") + lines.append(f" switch ({ue_prop})") + lines.append(" {") + for _xml_val, mapping in value_map.items(): + ue_member, mj_const = mapping[0], mapping[1] + lines.append( + f" case {ue_enum}::{ue_member}: FinalType = {mj_const}; break;" + ) + lines.append(" }") + lines.append(" }") + lines.append(f" if (FinalType == {name_for} && !{name_field}.IsEmpty())") + lines.append(" {") + lines.append(f" {name_setter}({name_target}, {name_field});") + lines.append(" }") + return "\n".join(lines) + "\n" + + +def _phase_geom_final_type(rules, schema, mjxmacro, mjspec, + public_root, private_root, writes) -> None: + """Inject geom_final_type block into MjGeom.cpp between the + CODEGEN_GEOM_FINAL_TYPE markers.""" + element_rules_all = rules.get("element_rules", {}) + + def emit_fn(cat_rules): + # Look up element_rules entry via the category key already used by + # rules.categories. The shared helper passes cat_rules through; + # we recover the category name from the dict identity. + cat_name = next( + (k for k, v in rules.get("categories", {}).items() + if v is cat_rules), + None, + ) + if cat_name is None: + return None + return _emit_geom_final_type_block( + cat_rules, element_rules_all.get(cat_name, {}), mjspec, + ) + + _inject_into_category_cpp( + rules, private_root, writes, + tag="GEOM_FINAL_TYPE", + emit_fn=emit_fn, + diag_source="geom_final_type", + ) + + +def _phase_sensor_codegen(rules, schema, mjxmacro, mjspec, + public_root, private_root, writes) -> None: + """Inject codegen-emitted sensor switch + TagToType into MjSensor.cpp.""" + sensor_rules = rules.get("categories", {}).get("sensor") + if not sensor_rules: + return + sensor_per_type = schema.get("sensor_per_type", {}) + if not sensor_per_type: + _diag_add( + "[diagnostic] sensor_per_type missing from schema snapshot; " + "skipping sensor switch codegen (run " + "build_mjcf_schema_snapshot.py).", + source="sensor_codegen", + ) + return + cpp_path = os.path.join( + private_root, "MuJoCo", "Components", "Sensors", "MjSensor.cpp", + ) + if not os.path.exists(cpp_path): + _diag_add( + f"[diagnostic] sensor_codegen: host .cpp '{cpp_path}' does " + f"not exist; sensor switch + tag map will not be emitted.", + source="sensor_codegen", + ) + return + with open(cpp_path, "r", encoding="utf-8") as f: + text = f.read() + switch_body = _emit_sensor_switch_block(sensor_rules, sensor_per_type) + tag_map_body = _emit_sensor_tag_to_type_block(sensor_rules) + new_text = text + new_text, ok_switch = inject_between_tags( + new_text, "SENSOR_TYPE_SWITCH", switch_body, + ) + if not ok_switch: + _diag_add( + f"[diagnostic] sensor_codegen: '{cpp_path}' is missing the " + f"CODEGEN_SENSOR_TYPE_SWITCH_START/END marker pair.", + source="sensor_codegen", + ) + new_text, ok_tag = inject_between_tags( + new_text, "SENSOR_TAG_TO_TYPE", tag_map_body, + ) + if not ok_tag: + _diag_add( + f"[diagnostic] sensor_codegen: '{cpp_path}' is missing the " + f"CODEGEN_SENSOR_TAG_TO_TYPE_START/END marker pair.", + source="sensor_codegen", + ) + if new_text != text: + writes.append(FileWrite(path=cpp_path, content=new_text)) + + +def _phase_categories(rules, schema, mjxmacro, mjspec, + public_root, private_root, writes) -> None: + categories: Dict[str, Any] = rules.get("categories", {}) for cat, cat_rules in categories.items(): layout = cat_rules.get("layout", "no_subclasses") if layout == "single_uclass_per_file": - # Base class injection + N subclass files. writes.extend(emit_base_class_injection(cat, cat_rules, schema, rules, public_root, private_root, mjspec=mjspec)) writes.extend(emit_subclass_files(cat, cat_rules, schema, rules, public_root, private_root, mjspec=mjspec)) elif layout == "multi_uclass": @@ -2172,17 +3562,71 @@ def collect_all_writes( elif layout == "no_subclasses": writes.extend(emit_base_class_injection(cat, cat_rules, schema, rules, public_root, private_root, mjspec=mjspec)) + +def _phase_bind_h(rules, schema, mjxmacro, mjspec, + public_root, private_root, writes, bind_h_path) -> None: bind_write = emit_bind_h_injection(rules, mjxmacro, bind_h_path) if bind_write: writes.append(bind_write) + +def _phase_schema_tests(rules, schema, mjxmacro, mjspec, + public_root, private_root, writes) -> None: writes.append(emit_schema_for_tests(schema, rules)) - # Diagnostics: surface schema/snapshot drift that the rules don't yet - # account for. Stdout, not fatal — the codegen has emitted what it can; - # the operator reads these to know what manual rule edits are needed. + +def _phase_diagnostics(rules, schema, mjxmacro, mjspec, + public_root, private_root, writes) -> None: _emit_drift_diagnostics(schema, rules, mjspec) + +# Order matters: emit phases run first (collect writes), then diagnostics +# scans the final rule set. Phase 2b-2e add their entries here. +EMISSION_PHASES: List[EmissionPhase] = [ + EmissionPhase(name="categories", fn=_phase_categories), + EmissionPhase(name="synthetic_categories", fn=_phase_synthetic_categories), + EmissionPhase(name="generated_enums", fn=_phase_generated_enums), + EmissionPhase(name="editor_option_helpers", fn=_phase_editor_option_helpers), + EmissionPhase(name="articulation_registry", fn=_phase_articulation_registry), + EmissionPhase(name="sensor_codegen", fn=_phase_sensor_codegen), + EmissionPhase(name="objtype_dispatch", fn=_phase_objtype_dispatch), + EmissionPhase(name="geom_final_type", fn=_phase_geom_final_type), + EmissionPhase(name="bind_h", fn=_phase_bind_h), + EmissionPhase(name="schema_tests", fn=_phase_schema_tests), + EmissionPhase(name="diagnostics", fn=_phase_diagnostics), +] + + +def collect_all_writes( + schema: Dict[str, Any], + rules: Dict[str, Any], + mjxmacro: Dict[str, Any], + public_root: str, + private_root: str, + bind_h_path: str, + mjspec: Dict[str, Any] | None = None, +) -> List[FileWrite]: + """Drive every phase in ``EMISSION_PHASES`` and return the full set of + file writes the codegen would perform. No I/O side effects on disk — + diagnostics print to stderr at the end. + """ + # Reset both the diag buffer and the strict counter at the start of + # each invocation. Without this, running the generator twice in the + # same Python process (test runners, future integration shells, etc.) + # carries the previous run's diagnostic count into ``--strict`` and + # exits 2 even when the current run produced none. + _DIAGS.clear() + _STRICT_DIAGS_FIRED[0] = 0 + + writes: List[FileWrite] = [] + for phase in EMISSION_PHASES: + if phase.name == "bind_h": + phase.fn(rules, schema, mjxmacro, mjspec, + public_root, private_root, writes, bind_h_path) + else: + phase.fn(rules, schema, mjxmacro, mjspec, + public_root, private_root, writes) + _diag_flush() return writes @@ -2204,9 +3648,13 @@ def _emit_drift_diagnostics(schema: Dict[str, Any], rules: Dict[str, Any], Each item prints a one-line ``[diagnostic] ...`` hint with the file + rule path the operator should edit. None of these are fatal because the codegen is still useful in the partially-covered state. + + Diagnostics are routed through the module-level ``_DIAGS`` collector + and flushed once at the end of ``collect_all_writes`` so 2b-2e + emitters can surface their own without each inventing a stderr + channel. """ categories = rules.get("categories", {}) - msgs: List[str] = [] # 1) Top-level schema elements with no category coverage. known_blocks = {c.get("schema_common_block", "").split(".", 1)[0] @@ -2217,7 +3665,8 @@ def _emit_drift_diagnostics(schema: Dict[str, Any], rules: Dict[str, Any], # don't need their own category, so we ignore them here. container_keys = { "_meta", "actuator_common", "actuator_types", "sensor_common", - "sensor_types", "sensor_extras", "tendon", "equality", "contact", + "sensor_types", "sensor_per_type", "sensor_extras", + "tendon", "equality", "contact", "asset", "compiler", "option", "keyframe", "default", } # Schema elements URLab intentionally does NOT codegen (yet). Each @@ -2230,7 +3679,7 @@ def _emit_drift_diagnostics(schema: Dict[str, Any], rules: Dict[str, Any], continue if key in unmodeled: continue - msgs.append( + _diag_add( f"[diagnostic] schema has top-level element '{key}' but no " f"category in codegen_rules.json (rules['categories']). " f"Either add a category entry, list '{key}' in " @@ -2244,7 +3693,7 @@ def _emit_drift_diagnostics(schema: Dict[str, Any], rules: Dict[str, Any], known_act_subs = {s.get("key") for s in act_cat.get("subtypes", [])} for name in schema.get("actuator_types", {}): if name not in known_act_subs: - msgs.append( + _diag_add( f"[diagnostic] schema actuator subtype '{name}' has no " f"entry in categories.actuator.subtypes. Add a subtype " f"+ subtype_setto rule pair so codegen emits the UMj" @@ -2256,7 +3705,7 @@ def _emit_drift_diagnostics(schema: Dict[str, Any], rules: Dict[str, Any], known_sens_subs = {s.get("key") for s in sens_cat.get("subtypes", [])} for name in schema.get("sensor_types", []): if name not in known_sens_subs: - msgs.append( + _diag_add( f"[diagnostic] schema sensor type '{name}' has no entry " f"in categories.sensor.subtypes. Add it so the per-sensor " f"UMjXSensor subclass is emitted." @@ -2288,7 +3737,7 @@ def _emit_drift_diagnostics(schema: Dict[str, Any], rules: Dict[str, Any], ue_prop = renames.get(pname, pname) if ue_prop in schema_attr_set or pname in fn_defaults: continue - msgs.append( + _diag_add( f"[diagnostic] {fn_name} param '{pname}' is not " f"in the {cat_name}.{sub_key} schema attrs and " f"has no param_renames or setto_param_defaults " @@ -2314,7 +3763,7 @@ def _emit_drift_diagnostics(schema: Dict[str, Any], rules: Dict[str, Any], if any(s in attr for s in ("count", "range", "limit", "coef", "data", "params", "vert", "elem", "size", "list", "ids")): - msgs.append( + _diag_add( f"[diagnostic] attr '{attr}' (used by {cat_name}) " f"falls back to default_type ('{default_type}') — " f"add it to type_mappings if it should be TArray<...> " @@ -2322,15 +3771,133 @@ def _emit_drift_diagnostics(schema: Dict[str, Any], rules: Dict[str, Any], ) seen_untyped.add(attr) - if msgs: - print(f"\n--- codegen diagnostics ({len(msgs)}) ---", file=sys.stderr) - for m in msgs: - print(m, file=sys.stderr) - print( - "(diagnostics are non-fatal; the codegen has emitted what it " - "can — fix the rules to silence them.)", - file=sys.stderr, - ) + # 6) mjsX struct field drift. If a category's mjs_struct gains fields + # in MuJoCo that aren't excluded by the rule AND aren't covered by a + # schema attr or canonicalisation, the codegen silently ignores them. + # Surface the candidates so a MuJoCo bump can't hide a new spec field. + unmodeled_by_struct: Dict[str, set] = { + struct: set(fields) for struct, fields in + rules.get("intentionally_unmodeled_mjs_fields", {}).items() + } + if mjspec and "structs" in mjspec: + for cat_name, cat_rules in categories.items(): + mjs_struct = cat_rules.get("mjs_struct") + if not mjs_struct or mjs_struct not in mjspec["structs"]: + continue + block = cat_rules.get("schema_common_block", "") + schema_attrs_set = set(schema_attrs(schema, block)) + # Add subtype attrs so per-subtype emissions count. + for sub in cat_rules.get("subtypes", []): + schema_attrs_set.update( + schema_subtype_attrs(schema, cat_name, sub.get("key", "")) + ) + mjs_field_set = set(mjspec["structs"][mjs_struct]) + # Pull rename + collation targets from element_rules — any mjs + # field that an attr maps to via these is "covered". + elem_rules = rules.get("element_rules", {}).get(cat_name, {}) + attr_to_mjs = elem_rules.get("attr_to_mjs_field", {}) + mapped_fields = set(attr_to_mjs.values()) + for coll_def in elem_rules.get("target_collations", {}).values(): + if isinstance(coll_def, dict) and coll_def.get("mjs_field"): + mapped_fields.add(coll_def["mjs_field"]) + for enum_def in elem_rules.get("xml_enum_attrs", {}).values(): + if isinstance(enum_def, dict) and enum_def.get("mjs_field"): + mapped_fields.add(enum_def["mjs_field"]) + # Data-packed attrs (e.g. equality.data, sensor.data) write to a + # specific field on the struct, not Element->attr directly. + # Default target is "data" when unspecified. + for packed in elem_rules.get("mjs_data_packed_attrs", {}).values(): + if isinstance(packed, dict): + mapped_fields.add(packed.get("target") or "data") + # Double-vec attrs (mjsKey.qpos/qvel/...) read mjDoubleVec* + # fields that match the attr name verbatim — already covered + # by schema_attrs_set but listed here for clarity. + for da in elem_rules.get("mjs_double_vec_attrs", []): + mapped_fields.add(da) + # Subtype-discriminator fields ("type", "objtype") set by the + # category's enum-driven export. equality.type / objtype are + # written by xml_enum_attrs already captured; subtype-shape + # categories also assign them via their subtype switch. + if cat_rules.get("type_enum_name"): + mapped_fields.add("type") + mapped_fields.add("objtype") # set by all subtype-switch emit paths + for conv_list in elem_rules.get("unit_conversion", {}).values(): + for entry in conv_list if isinstance(conv_list, list) else []: + if isinstance(entry, dict) and entry.get("mjs_field"): + mapped_fields.add(entry["mjs_field"]) + # Canonicalisation-emitted fields. Each entry maps canon name + # to the set of mjs struct fields its export_block writes. The + # diagnostic uses this to recognize fields handled by canon as + # NOT drift. Keep in sync with _canon_export_block. + _CANON_MJS_FIELDS = { + "body_sleep_policy": {"sleep"}, + "actuator_transmission": {"target", "trntype", "slidersite", "refsite"}, + "fromto_decompose": set(), # writes via Pos/Quat/size pipelines + "orientation": {"quat"}, + "spatial_pose": {"pos"}, + } + for canon in elem_rules.get("applies_canonicalizations", []): + mapped_fields |= _CANON_MJS_FIELDS.get(canon, set()) + # Whitelist: structural fields the codegen intentionally never + # touches (element pointer, info string, parent links). + structural = { + "element", "info", "userdata", "user", "name", "classname", + "parent", "frame", "explicitinertial", + } + structural |= unmodeled_by_struct.get(mjs_struct, set()) + structural |= mapped_fields + # Map schema attr names to likely mjs field names. The codegen + # has _resolve_mjs_field for the real conversion; here we do a + # cheap normalisation to flag genuinely missing fields, not + # every name spelling difference. + normalised_schema = {a.replace("_", "").lower() + for a in schema_attrs_set} + for mjs_field in mjs_field_set: + if mjs_field in structural: + continue + # Map mjs spelling back to a schema-attr candidate. + candidate = mjs_field.replace("_", "").lower() + if candidate in normalised_schema: + continue + # Try common stripping: "bodyname1" -> "body1". + stripped = candidate.replace("name", "") + if stripped in normalised_schema: + continue + # Try mjs-side "act" prefix expansion ("actrange" -> "actuatorrange"). + if candidate.startswith("act") and ("actuator" + candidate[3:]) in normalised_schema: + continue + _diag_add( + f"[diagnostic] {mjs_struct}.{mjs_field} (in mjspec_snapshot) " + f"has no corresponding schema attr in '{cat_name}'. Either " + f"add a schema canonicalisation, list it under " + f"intentionally_unmodeled_mjs_fields, or accept that codegen " + f"silently skips it.", + source="mjs_field_drift", + ) + + # 7) Generated enum coverage. Flag if a generated_enums entry maps + # FEWER C enum members than mjspec carries — likely a MuJoCo bump + # added a new value the UE-side enum hasn't picked up yet. + if mjspec and "enums" in mjspec: + for gen_name, gen_def in rules.get("generated_enums", {}).items(): + for entry in gen_def.get("enums", []): + mj_enum_name = entry.get("from_mj_enum") + ue_member_from_mj = entry.get("ue_member_from_mj", {}) + exclude = set(entry.get("exclude_mj_members", [])) + c_enum = mjspec["enums"].get(mj_enum_name, {}) + if not c_enum: + continue + mapped = set(ue_member_from_mj) | exclude + missing = [m for m in c_enum if m not in mapped] + if missing: + _diag_add( + f"[diagnostic] generated_enums['{gen_name}'].{entry.get('ue_name')}: " + f"C enum '{mj_enum_name}' has {len(missing)} member(s) with no UE " + f"mapping: {missing[:5]}{'...' if len(missing) > 5 else ''}. Add to " + f"ue_member_from_mj or exclude_mj_members.", + source="enum_drift", + ) + # _diag_flush() is called once from collect_all_writes after all phases. def apply_writes(writes: List[FileWrite], dry_run: bool, check_only: bool) -> int: @@ -2373,12 +3940,18 @@ def main() -> int: parser.add_argument("--schema", default=DEFAULT_SCHEMA) parser.add_argument("--mjxmacro", default=DEFAULT_MJXMACRO) parser.add_argument("--mjspec", default=DEFAULT_MJSPEC) + parser.add_argument("--introspect", default=DEFAULT_INTROSPECT, + help="Optional clang-AST scrape (Phase 2d-3 output). Loaded " + "alongside mjspec_snapshot; the generator merges enums + " + "structs from both, preferring introspect when present.") parser.add_argument("--rules", default=DEFAULT_RULES) parser.add_argument("--public-root", default=DEFAULT_PUBLIC_ROOT) parser.add_argument("--private-root", default=DEFAULT_PRIVATE_ROOT) parser.add_argument("--bind-h", default=DEFAULT_BIND_H) parser.add_argument("--dry-run", action="store_true", help="print diffs, write nothing") parser.add_argument("--check", action="store_true", help="non-zero exit if writes would change anything") + parser.add_argument("--strict", action="store_true", + help="make any drift diagnostic fatal (exit 2). Default off — diagnostics print but don't fail the run.") args = parser.parse_args() with open(args.schema, "r", encoding="utf-8") as f: @@ -2391,9 +3964,41 @@ def main() -> int: if os.path.exists(args.mjspec): with open(args.mjspec, "r", encoding="utf-8") as f: mjspec = json.load(f) + # Merge in the introspect (clang) snapshot if present. Introspect's + # ``enums`` shape (each enum is {members: {name: value}, ...}) is + # richer than mjspec's flat {name: value} map; collapse to the flat + # form for backwards compatibility. + if os.path.exists(args.introspect): + with open(args.introspect, "r", encoding="utf-8") as f: + introspect = json.load(f) + if mjspec is None: + mjspec = {"structs": {}, "enums": {}, "setto_functions": {}} + intro_enums = introspect.get("enums", {}) + flat_enums = {name: e.get("members", {}) for name, e in intro_enums.items()} + # Preserve any mjspec-only enum entries (e.g. ones the regex + # scraper caught that clang missed). Introspect wins on overlap. + merged = dict(mjspec.get("enums", {})) + merged.update(flat_enums) + mjspec["enums"] = merged + # Make introspect's struct/function tables visible alongside. + mjspec.setdefault("introspect", {}) + mjspec["introspect"] = { + "functions": introspect.get("functions", {}), + "structs": introspect.get("structs", {}), + "defines": introspect.get("defines", {}), + } writes = collect_all_writes(schema, rules, mjxmacro, args.public_root, args.private_root, args.bind_h, mjspec=mjspec) - return apply_writes(writes, args.dry_run, args.check) + # collect_all_writes calls _diag_flush() which prints + clears the + # buffer. We need to know whether anything fired before that clear, + # so we re-run with a tap. Simpler: track via a side-channel flag. + fired = _STRICT_DIAGS_FIRED[0] + rc = apply_writes(writes, args.dry_run, args.check) + if args.strict and fired: + print(f"[codegen] --strict: {fired} diagnostic(s) flushed; exiting non-zero.", + file=sys.stderr) + return 2 + return rc if __name__ == "__main__": diff --git a/Scripts/codegen/regen_all.py b/Scripts/codegen/regen_all.py index 2d5c9e9..43f5f09 100644 --- a/Scripts/codegen/regen_all.py +++ b/Scripts/codegen/regen_all.py @@ -4,9 +4,10 @@ Runs every codegen step in order: 1. Rebuild snapshots from the installed MuJoCo headers + submodule source: - - Scripts/mjspec_snapshot.json (mjsX struct fields + mjs_setTo* sigs) - - Scripts/mjxmacro_snapshot.json (model/data array layouts) - - Scripts/mjcf_schema_snapshot.json (MJCF schema, per element) + - Scripts/codegen/snapshots/mjspec_snapshot.json (mjsX struct fields + mjs_setTo* sigs + mjt* enums) + - Scripts/codegen/snapshots/mjxmacro_snapshot.json (model/data array layouts) + - Scripts/codegen/snapshots/mjcf_schema_snapshot.json (MJCF schema + per-sensor objtype scrape) + - Scripts/codegen/snapshots/introspect_snapshot.json (clang-AST scrape — optional, requires libclang) 2. Run the C++ generator (generate_ue_components.py) against the fresh snapshots. Emits / updates the per-component .h/.cpp files in Source/. diff --git a/Scripts/codegen/snapshots/introspect_snapshot.json b/Scripts/codegen/snapshots/introspect_snapshot.json new file mode 100644 index 0000000..98acd39 --- /dev/null +++ b/Scripts/codegen/snapshots/introspect_snapshot.json @@ -0,0 +1,26279 @@ +{ + "_meta": { + "snapshot_version": 1, + "header_hash": "b987492b3adfd9c31a226b1c2634dd013b59fcb05863c7e0bf82942b6c5ebf23" + }, + "functions": { + "mj_defaultVFS": { + "name": "mj_defaultVFS", + "return_type": "void", + "params": [ + { + "name": "vfs", + "c_type": "mjVFS *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 79 + }, + "mj_mountVFS": { + "name": "mj_mountVFS", + "return_type": "int", + "params": [ + { + "name": "vfs", + "c_type": "mjVFS *", + "array_dim": null + }, + { + "name": "filepath", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "provider", + "c_type": "const mjpResourceProvider *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 83 + }, + "mj_unmountVFS": { + "name": "mj_unmountVFS", + "return_type": "int", + "params": [ + { + "name": "vfs", + "c_type": "mjVFS *", + "array_dim": null + }, + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 86 + }, + "mj_addFileVFS": { + "name": "mj_addFileVFS", + "return_type": "int", + "params": [ + { + "name": "vfs", + "c_type": "mjVFS *", + "array_dim": null + }, + { + "name": "directory", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 89 + }, + "mj_addBufferVFS": { + "name": "mj_addBufferVFS", + "return_type": "int", + "params": [ + { + "name": "vfs", + "c_type": "mjVFS *", + "array_dim": null + }, + { + "name": "name", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "buffer", + "c_type": "const void *", + "array_dim": null + }, + { + "name": "nbuffer", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 92 + }, + "mj_deleteFileVFS": { + "name": "mj_deleteFileVFS", + "return_type": "int", + "params": [ + { + "name": "vfs", + "c_type": "mjVFS *", + "array_dim": null + }, + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 95 + }, + "mj_containsBufferVFS": { + "name": "mj_containsBufferVFS", + "return_type": "int", + "params": [ + { + "name": "vfs", + "c_type": "mjVFS *", + "array_dim": null + }, + { + "name": "name", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 98 + }, + "mj_containsFileVFS": { + "name": "mj_containsFileVFS", + "return_type": "int", + "params": [ + { + "name": "vfs", + "c_type": "mjVFS *", + "array_dim": null + }, + { + "name": "directory", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 101 + }, + "mj_deleteVFS": { + "name": "mj_deleteVFS", + "return_type": "void", + "params": [ + { + "name": "vfs", + "c_type": "mjVFS *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 104 + }, + "mj_getCacheSize": { + "name": "mj_getCacheSize", + "return_type": "size_t", + "params": [ + { + "name": "cache", + "c_type": "const mjCache *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 109 + }, + "mj_getCacheCapacity": { + "name": "mj_getCacheCapacity", + "return_type": "size_t", + "params": [ + { + "name": "cache", + "c_type": "const mjCache *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 112 + }, + "mj_setCacheCapacity": { + "name": "mj_setCacheCapacity", + "return_type": "size_t", + "params": [ + { + "name": "cache", + "c_type": "mjCache *", + "array_dim": null + }, + { + "name": "size", + "c_type": "size_t", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 115 + }, + "mj_getCache": { + "name": "mj_getCache", + "return_type": "mjCache *", + "params": [], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 118 + }, + "mj_clearCache": { + "name": "mj_clearCache", + "return_type": "void", + "params": [ + { + "name": "cache", + "c_type": "mjCache *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 121 + }, + "mj_loadXML": { + "name": "mj_loadXML", + "return_type": "mjModel *", + "params": [ + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "vfs", + "c_type": "const mjVFS *", + "array_dim": null + }, + { + "name": "error", + "c_type": "char *", + "array_dim": null + }, + { + "name": "error_sz", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 129 + }, + "mj_parseXML": { + "name": "mj_parseXML", + "return_type": "mjSpec *", + "params": [ + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "vfs", + "c_type": "const mjVFS *", + "array_dim": null + }, + { + "name": "error", + "c_type": "char *", + "array_dim": null + }, + { + "name": "error_sz", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 133 + }, + "mj_parseXMLString": { + "name": "mj_parseXMLString", + "return_type": "mjSpec *", + "params": [ + { + "name": "xml", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "vfs", + "c_type": "const mjVFS *", + "array_dim": null + }, + { + "name": "error", + "c_type": "char *", + "array_dim": null + }, + { + "name": "error_sz", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 137 + }, + "mj_parse": { + "name": "mj_parse", + "return_type": "mjSpec *", + "params": [ + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "content_type", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "vfs", + "c_type": "const mjVFS *", + "array_dim": null + }, + { + "name": "error", + "c_type": "char *", + "array_dim": null + }, + { + "name": "error_sz", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 141 + }, + "mj_encode": { + "name": "mj_encode", + "return_type": "int", + "params": [ + { + "name": "s", + "c_type": "const mjSpec *", + "array_dim": null + }, + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "content_type", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "vfs", + "c_type": "const mjVFS *", + "array_dim": null + }, + { + "name": "error", + "c_type": "char *", + "array_dim": null + }, + { + "name": "error_sz", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 147 + }, + "mj_compile": { + "name": "mj_compile", + "return_type": "mjModel *", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + }, + { + "name": "vfs", + "c_type": "const mjVFS *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 153 + }, + "mj_copyBack": { + "name": "mj_copyBack", + "return_type": "int", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + }, + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 156 + }, + "mj_recompile": { + "name": "mj_recompile", + "return_type": "int", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + }, + { + "name": "vfs", + "c_type": "const mjVFS *", + "array_dim": null + }, + { + "name": "m", + "c_type": "mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 160 + }, + "mj_saveLastXML": { + "name": "mj_saveLastXML", + "return_type": "int", + "params": [ + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "error", + "c_type": "char *", + "array_dim": null + }, + { + "name": "error_sz", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 165 + }, + "mj_freeLastXML": { + "name": "mj_freeLastXML", + "return_type": "void", + "params": [], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 168 + }, + "mj_saveXMLString": { + "name": "mj_saveXMLString", + "return_type": "int", + "params": [ + { + "name": "s", + "c_type": "const mjSpec *", + "array_dim": null + }, + { + "name": "xml", + "c_type": "char *", + "array_dim": null + }, + { + "name": "xml_sz", + "c_type": "int", + "array_dim": null + }, + { + "name": "error", + "c_type": "char *", + "array_dim": null + }, + { + "name": "error_sz", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 173 + }, + "mj_saveXML": { + "name": "mj_saveXML", + "return_type": "int", + "params": [ + { + "name": "s", + "c_type": "const mjSpec *", + "array_dim": null + }, + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "error", + "c_type": "char *", + "array_dim": null + }, + { + "name": "error_sz", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 177 + }, + "mju_getXMLDependencies": { + "name": "mju_getXMLDependencies", + "return_type": "void", + "params": [ + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "dependencies", + "c_type": "mjStringVec *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 181 + }, + "mj_step": { + "name": "mj_step", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 186 + }, + "mj_step1": { + "name": "mj_step1", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 189 + }, + "mj_step2": { + "name": "mj_step2", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 192 + }, + "mj_forward": { + "name": "mj_forward", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 195 + }, + "mj_inverse": { + "name": "mj_inverse", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 198 + }, + "mj_forwardSkip": { + "name": "mj_forwardSkip", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "skipstage", + "c_type": "int", + "array_dim": null + }, + { + "name": "skipsensor", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 201 + }, + "mj_inverseSkip": { + "name": "mj_inverseSkip", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "skipstage", + "c_type": "int", + "array_dim": null + }, + { + "name": "skipsensor", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 204 + }, + "mj_defaultLROpt": { + "name": "mj_defaultLROpt", + "return_type": "void", + "params": [ + { + "name": "opt", + "c_type": "mjLROpt *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 210 + }, + "mj_defaultSolRefImp": { + "name": "mj_defaultSolRefImp", + "return_type": "void", + "params": [ + { + "name": "solref", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "solimp", + "c_type": "mjtNum *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 214 + }, + "mj_defaultOption": { + "name": "mj_defaultOption", + "return_type": "void", + "params": [ + { + "name": "opt", + "c_type": "mjOption *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 217 + }, + "mj_defaultVisual": { + "name": "mj_defaultVisual", + "return_type": "void", + "params": [ + { + "name": "vis", + "c_type": "mjVisual *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 220 + }, + "mj_copyModel": { + "name": "mj_copyModel", + "return_type": "mjModel *", + "params": [ + { + "name": "dest", + "c_type": "mjModel *", + "array_dim": null + }, + { + "name": "src", + "c_type": "const mjModel *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 224 + }, + "mj_saveModel": { + "name": "mj_saveModel", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "buffer", + "c_type": "void *", + "array_dim": null + }, + { + "name": "buffer_sz", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 228 + }, + "mj_loadModel": { + "name": "mj_loadModel", + "return_type": "mjModel *", + "params": [ + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "vfs", + "c_type": "const mjVFS *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 233 + }, + "mj_loadModelBuffer": { + "name": "mj_loadModelBuffer", + "return_type": "mjModel *", + "params": [ + { + "name": "buffer", + "c_type": "const void *", + "array_dim": null + }, + { + "name": "buffer_sz", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 236 + }, + "mj_deleteModel": { + "name": "mj_deleteModel", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "mjModel *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 239 + }, + "mj_sizeModel": { + "name": "mj_sizeModel", + "return_type": "mjtSize", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 242 + }, + "mj_makeData": { + "name": "mj_makeData", + "return_type": "mjData *", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 246 + }, + "mj_copyData": { + "name": "mj_copyData", + "return_type": "mjData *", + "params": [ + { + "name": "dest", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "src", + "c_type": "const mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 250 + }, + "mjv_copyData": { + "name": "mjv_copyData", + "return_type": "mjData *", + "params": [ + { + "name": "dest", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "src", + "c_type": "const mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 253 + }, + "mj_resetData": { + "name": "mj_resetData", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 256 + }, + "mj_resetDataDebug": { + "name": "mj_resetDataDebug", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "debug_value", + "c_type": "unsigned char", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 259 + }, + "mj_resetDataKeyframe": { + "name": "mj_resetDataKeyframe", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "key", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 262 + }, + "mj_markStack": { + "name": "mj_markStack", + "return_type": "void", + "params": [ + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 267 + }, + "mj_freeStack": { + "name": "mj_freeStack", + "return_type": "void", + "params": [ + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 271 + }, + "mj_stackAllocByte": { + "name": "mj_stackAllocByte", + "return_type": "void *", + "params": [ + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "bytes", + "c_type": "size_t", + "array_dim": null + }, + { + "name": "alignment", + "c_type": "size_t", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 277 + }, + "mj_stackAllocNum": { + "name": "mj_stackAllocNum", + "return_type": "mjtNum *", + "params": [ + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "size", + "c_type": "size_t", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 280 + }, + "mj_stackAllocInt": { + "name": "mj_stackAllocInt", + "return_type": "int *", + "params": [ + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "size", + "c_type": "size_t", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 283 + }, + "mj_deleteData": { + "name": "mj_deleteData", + "return_type": "void", + "params": [ + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 286 + }, + "mj_resetCallbacks": { + "name": "mj_resetCallbacks", + "return_type": "void", + "params": [], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 289 + }, + "mj_setConst": { + "name": "mj_setConst", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 292 + }, + "mj_setLengthRange": { + "name": "mj_setLengthRange", + "return_type": "int", + "params": [ + { + "name": "m", + "c_type": "mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "index", + "c_type": "int", + "array_dim": null + }, + { + "name": "opt", + "c_type": "const mjLROpt *", + "array_dim": null + }, + { + "name": "error", + "c_type": "char *", + "array_dim": null + }, + { + "name": "error_sz", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 296 + }, + "mj_makeSpec": { + "name": "mj_makeSpec", + "return_type": "mjSpec *", + "params": [], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 300 + }, + "mj_copySpec": { + "name": "mj_copySpec", + "return_type": "mjSpec *", + "params": [ + { + "name": "s", + "c_type": "const mjSpec *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 303 + }, + "mj_deleteSpec": { + "name": "mj_deleteSpec", + "return_type": "void", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 306 + }, + "mjs_activatePlugin": { + "name": "mjs_activatePlugin", + "return_type": "int", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + }, + { + "name": "name", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 309 + }, + "mjs_setDeepCopy": { + "name": "mjs_setDeepCopy", + "return_type": "int", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + }, + { + "name": "deepcopy", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 312 + }, + "mj_printFormattedModel": { + "name": "mj_printFormattedModel", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "float_format", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 319 + }, + "mj_printModel": { + "name": "mj_printModel", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 322 + }, + "mj_printFormattedData": { + "name": "mj_printFormattedData", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "float_format", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 326 + }, + "mj_printData": { + "name": "mj_printData", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 330 + }, + "mju_printMat": { + "name": "mju_printMat", + "return_type": "void", + "params": [ + { + "name": "mat", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "nr", + "c_type": "int", + "array_dim": null + }, + { + "name": "nc", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 333 + }, + "mju_printMatSparse": { + "name": "mju_printMatSparse", + "return_type": "void", + "params": [ + { + "name": "mat", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "nr", + "c_type": "int", + "array_dim": null + }, + { + "name": "rownnz", + "c_type": "const int *", + "array_dim": null + }, + { + "name": "rowadr", + "c_type": "const int *", + "array_dim": null + }, + { + "name": "colind", + "c_type": "const int *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 336 + }, + "mj_printSchema": { + "name": "mj_printSchema", + "return_type": "int", + "params": [ + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "buffer", + "c_type": "char *", + "array_dim": null + }, + { + "name": "buffer_sz", + "c_type": "int", + "array_dim": null + }, + { + "name": "flg_html", + "c_type": "int", + "array_dim": null + }, + { + "name": "flg_pad", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 340 + }, + "mj_printScene": { + "name": "mj_printScene", + "return_type": "void", + "params": [ + { + "name": "s", + "c_type": "const mjvScene *", + "array_dim": null + }, + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 344 + }, + "mj_printFormattedScene": { + "name": "mj_printFormattedScene", + "return_type": "void", + "params": [ + { + "name": "s", + "c_type": "const mjvScene *", + "array_dim": null + }, + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "float_format", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 348 + }, + "mj_fwdKinematics": { + "name": "mj_fwdKinematics", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 355 + }, + "mj_fwdPosition": { + "name": "mj_fwdPosition", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 358 + }, + "mj_fwdVelocity": { + "name": "mj_fwdVelocity", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 361 + }, + "mj_fwdActuation": { + "name": "mj_fwdActuation", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 364 + }, + "mj_fwdAcceleration": { + "name": "mj_fwdAcceleration", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 367 + }, + "mj_fwdConstraint": { + "name": "mj_fwdConstraint", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 370 + }, + "mj_Euler": { + "name": "mj_Euler", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 373 + }, + "mj_RungeKutta": { + "name": "mj_RungeKutta", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "N", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 376 + }, + "mj_implicit": { + "name": "mj_implicit", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 379 + }, + "mj_invPosition": { + "name": "mj_invPosition", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 382 + }, + "mj_invVelocity": { + "name": "mj_invVelocity", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 385 + }, + "mj_invConstraint": { + "name": "mj_invConstraint", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 388 + }, + "mj_compareFwdInv": { + "name": "mj_compareFwdInv", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 391 + }, + "mj_sensorPos": { + "name": "mj_sensorPos", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 397 + }, + "mj_sensorVel": { + "name": "mj_sensorVel", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 400 + }, + "mj_sensorAcc": { + "name": "mj_sensorAcc", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 403 + }, + "mj_energyPos": { + "name": "mj_energyPos", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 406 + }, + "mj_energyVel": { + "name": "mj_energyVel", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 409 + }, + "mj_checkPos": { + "name": "mj_checkPos", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 412 + }, + "mj_checkVel": { + "name": "mj_checkVel", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 415 + }, + "mj_checkAcc": { + "name": "mj_checkAcc", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 418 + }, + "mj_kinematics": { + "name": "mj_kinematics", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 421 + }, + "mj_comPos": { + "name": "mj_comPos", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 424 + }, + "mj_camlight": { + "name": "mj_camlight", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 427 + }, + "mj_flex": { + "name": "mj_flex", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 430 + }, + "mj_tendon": { + "name": "mj_tendon", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 433 + }, + "mj_transmission": { + "name": "mj_transmission", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 436 + }, + "mj_crb": { + "name": "mj_crb", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 439 + }, + "mj_makeM": { + "name": "mj_makeM", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 442 + }, + "mj_factorM": { + "name": "mj_factorM", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 445 + }, + "mj_solveM": { + "name": "mj_solveM", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "x", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "y", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 448 + }, + "mj_solveM2": { + "name": "mj_solveM2", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "x", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "y", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "sqrtInvD", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 451 + }, + "mj_comVel": { + "name": "mj_comVel", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 455 + }, + "mj_passive": { + "name": "mj_passive", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 458 + }, + "mj_subtreeVel": { + "name": "mj_subtreeVel", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 461 + }, + "mj_rne": { + "name": "mj_rne", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "flg_acc", + "c_type": "int", + "array_dim": null + }, + { + "name": "result", + "c_type": "mjtNum *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 464 + }, + "mj_rnePostConstraint": { + "name": "mj_rnePostConstraint", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 467 + }, + "mj_maxContact": { + "name": "mj_maxContact", + "return_type": "int", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "g1", + "c_type": "int", + "array_dim": null + }, + { + "name": "g2", + "c_type": "int", + "array_dim": null + }, + { + "name": "has_margin", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 472 + }, + "mj_collision": { + "name": "mj_collision", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 475 + }, + "mj_makeConstraint": { + "name": "mj_makeConstraint", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 478 + }, + "mj_island": { + "name": "mj_island", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 481 + }, + "mj_projectConstraint": { + "name": "mj_projectConstraint", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 484 + }, + "mj_referenceConstraint": { + "name": "mj_referenceConstraint", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 487 + }, + "mj_constraintUpdate": { + "name": "mj_constraintUpdate", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "jar", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "cost", + "c_type": "mjtNum [1]", + "array_dim": 1 + }, + { + "name": "flg_coneHessian", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 492 + }, + "mj_stateSize": { + "name": "mj_stateSize", + "return_type": "int", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "sig", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 499 + }, + "mj_getState": { + "name": "mj_getState", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "state", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "sig", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 502 + }, + "mj_extractState": { + "name": "mj_extractState", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "src", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "srcsig", + "c_type": "int", + "array_dim": null + }, + { + "name": "dst", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "dstsig", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 505 + }, + "mj_setState": { + "name": "mj_setState", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "state", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "sig", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 509 + }, + "mj_copyState": { + "name": "mj_copyState", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "src", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "dst", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "sig", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 512 + }, + "mj_readCtrl": { + "name": "mj_readCtrl", + "return_type": "mjtNum", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "id", + "c_type": "int", + "array_dim": null + }, + { + "name": "time", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "interp", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 517 + }, + "mj_readSensor": { + "name": "mj_readSensor", + "return_type": "const mjtNum *", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "id", + "c_type": "int", + "array_dim": null + }, + { + "name": "time", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "result", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "interp", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 523 + }, + "mj_initCtrlHistory": { + "name": "mj_initCtrlHistory", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "id", + "c_type": "int", + "array_dim": null + }, + { + "name": "times", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "values", + "c_type": "const mjtNum *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 528 + }, + "mj_initSensorHistory": { + "name": "mj_initSensorHistory", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "id", + "c_type": "int", + "array_dim": null + }, + { + "name": "times", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "values", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "phase", + "c_type": "mjtNum", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 534 + }, + "mj_setKeyframe": { + "name": "mj_setKeyframe", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "k", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 538 + }, + "mj_addContact": { + "name": "mj_addContact", + "return_type": "int", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "con", + "c_type": "const mjContact *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 541 + }, + "mj_isPyramidal": { + "name": "mj_isPyramidal", + "return_type": "int", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 544 + }, + "mj_isSparse": { + "name": "mj_isSparse", + "return_type": "int", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 547 + }, + "mj_isDual": { + "name": "mj_isDual", + "return_type": "int", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 550 + }, + "mj_mulJacVec": { + "name": "mj_mulJacVec", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "vec", + "c_type": "const mjtNum *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 553 + }, + "mj_mulJacTVec": { + "name": "mj_mulJacTVec", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "vec", + "c_type": "const mjtNum *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 556 + }, + "mj_jac": { + "name": "mj_jac", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "jacp", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "jacr", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "point", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "body", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 560 + }, + "mj_jacBody": { + "name": "mj_jacBody", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "jacp", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "jacr", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "body", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 565 + }, + "mj_jacBodyCom": { + "name": "mj_jacBodyCom", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "jacp", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "jacr", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "body", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 569 + }, + "mj_jacSubtreeCom": { + "name": "mj_jacSubtreeCom", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "jacp", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "body", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 572 + }, + "mj_jacGeom": { + "name": "mj_jacGeom", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "jacp", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "jacr", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "geom", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 576 + }, + "mj_jacSite": { + "name": "mj_jacSite", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "jacp", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "jacr", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "site", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 580 + }, + "mj_jacPointAxis": { + "name": "mj_jacPointAxis", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "jacPoint", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "jacAxis", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "point", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "axis", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "body", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 584 + }, + "mj_jacDot": { + "name": "mj_jacDot", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "jacp", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "jacr", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "point", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "body", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 589 + }, + "mj_angmomMat": { + "name": "mj_angmomMat", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "mat", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "body", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 593 + }, + "mj_name2id": { + "name": "mj_name2id", + "return_type": "int", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "type", + "c_type": "int", + "array_dim": null + }, + { + "name": "name", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 596 + }, + "mj_id2name": { + "name": "mj_id2name", + "return_type": "const char *", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "type", + "c_type": "int", + "array_dim": null + }, + { + "name": "id", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 599 + }, + "mj_fullM": { + "name": "mj_fullM", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "dst", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "M", + "c_type": "const mjtNum *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 602 + }, + "mj_mulM": { + "name": "mj_mulM", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "vec", + "c_type": "const mjtNum *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 605 + }, + "mj_mulM2": { + "name": "mj_mulM2", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "vec", + "c_type": "const mjtNum *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 608 + }, + "mj_addM": { + "name": "mj_addM", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "dst", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "rownnz", + "c_type": "int *", + "array_dim": null + }, + { + "name": "rowadr", + "c_type": "int *", + "array_dim": null + }, + { + "name": "colind", + "c_type": "int *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 613 + }, + "mj_applyFT": { + "name": "mj_applyFT", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "force", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "torque", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "point", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "body", + "c_type": "int", + "array_dim": null + }, + { + "name": "qfrc_target", + "c_type": "mjtNum *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 617 + }, + "mj_objectVelocity": { + "name": "mj_objectVelocity", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "objtype", + "c_type": "int", + "array_dim": null + }, + { + "name": "objid", + "c_type": "int", + "array_dim": null + }, + { + "name": "res", + "c_type": "mjtNum [6]", + "array_dim": 6 + }, + { + "name": "flg_local", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 621 + }, + "mj_objectAcceleration": { + "name": "mj_objectAcceleration", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "objtype", + "c_type": "int", + "array_dim": null + }, + { + "name": "objid", + "c_type": "int", + "array_dim": null + }, + { + "name": "res", + "c_type": "mjtNum [6]", + "array_dim": 6 + }, + { + "name": "flg_local", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 625 + }, + "mj_geomDistance": { + "name": "mj_geomDistance", + "return_type": "mjtNum", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "geom1", + "c_type": "int", + "array_dim": null + }, + { + "name": "geom2", + "c_type": "int", + "array_dim": null + }, + { + "name": "distmax", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "fromto", + "c_type": "mjtNum [6]", + "array_dim": 6 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 630 + }, + "mj_contactForce": { + "name": "mj_contactForce", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "id", + "c_type": "int", + "array_dim": null + }, + { + "name": "result", + "c_type": "mjtNum [6]", + "array_dim": 6 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 634 + }, + "mj_differentiatePos": { + "name": "mj_differentiatePos", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "qvel", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "dt", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "qpos1", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "qpos2", + "c_type": "const mjtNum *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 637 + }, + "mj_integratePos": { + "name": "mj_integratePos", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "qpos", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "qvel", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "dt", + "c_type": "mjtNum", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 641 + }, + "mj_normalizeQuat": { + "name": "mj_normalizeQuat", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "qpos", + "c_type": "mjtNum *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 644 + }, + "mj_local2Global": { + "name": "mj_local2Global", + "return_type": "void", + "params": [ + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "xpos", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "xmat", + "c_type": "mjtNum [9]", + "array_dim": 9 + }, + { + "name": "pos", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "quat", + "c_type": "const mjtNum [4]", + "array_dim": 4 + }, + { + "name": "body", + "c_type": "int", + "array_dim": null + }, + { + "name": "sameframe", + "c_type": "mjtByte", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 647 + }, + "mj_getTotalmass": { + "name": "mj_getTotalmass", + "return_type": "mjtNum", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 651 + }, + "mj_setTotalmass": { + "name": "mj_setTotalmass", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "mjModel *", + "array_dim": null + }, + { + "name": "newmass", + "c_type": "mjtNum", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 654 + }, + "mj_getPluginConfig": { + "name": "mj_getPluginConfig", + "return_type": "const char *", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "plugin_id", + "c_type": "int", + "array_dim": null + }, + { + "name": "attrib", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 658 + }, + "mj_loadPluginLibrary": { + "name": "mj_loadPluginLibrary", + "return_type": "void", + "params": [ + { + "name": "path", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 661 + }, + "mj_loadAllPluginLibraries": { + "name": "mj_loadAllPluginLibraries", + "return_type": "void", + "params": [ + { + "name": "directory", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "callback", + "c_type": "mjfPluginLibraryLoadCallback", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 666 + }, + "mj_version": { + "name": "mj_version", + "return_type": "int", + "params": [], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 669 + }, + "mj_versionString": { + "name": "mj_versionString", + "return_type": "const char *", + "params": [], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 672 + }, + "mj_ray": { + "name": "mj_ray", + "return_type": "mjtNum", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "pnt", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vec", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "geomgroup", + "c_type": "const mjtByte *", + "array_dim": null + }, + { + "name": "flg_static", + "c_type": "mjtByte", + "array_dim": null + }, + { + "name": "bodyexclude", + "c_type": "int", + "array_dim": null + }, + { + "name": "geomid", + "c_type": "int [1]", + "array_dim": 1 + }, + { + "name": "normal", + "c_type": "mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 681 + }, + "mj_multiRay": { + "name": "mj_multiRay", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "pnt", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vec", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "geomgroup", + "c_type": "const mjtByte *", + "array_dim": null + }, + { + "name": "flg_static", + "c_type": "mjtByte", + "array_dim": null + }, + { + "name": "bodyexclude", + "c_type": "int", + "array_dim": null + }, + { + "name": "geomid", + "c_type": "int *", + "array_dim": null + }, + { + "name": "dist", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "normal", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "nray", + "c_type": "int", + "array_dim": null + }, + { + "name": "cutoff", + "c_type": "mjtNum", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 689 + }, + "mj_rayHfield": { + "name": "mj_rayHfield", + "return_type": "mjtNum", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "geomid", + "c_type": "int", + "array_dim": null + }, + { + "name": "pnt", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vec", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "normal", + "c_type": "mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 695 + }, + "mj_rayMesh": { + "name": "mj_rayMesh", + "return_type": "mjtNum", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "geomid", + "c_type": "int", + "array_dim": null + }, + { + "name": "pnt", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vec", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "normal", + "c_type": "mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 700 + }, + "mju_rayGeom": { + "name": "mju_rayGeom", + "return_type": "mjtNum", + "params": [ + { + "name": "pos", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "mat", + "c_type": "const mjtNum [9]", + "array_dim": 9 + }, + { + "name": "size", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "pnt", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vec", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "geomtype", + "c_type": "int", + "array_dim": null + }, + { + "name": "normal", + "c_type": "mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 705 + }, + "mj_rayFlex": { + "name": "mj_rayFlex", + "return_type": "mjtNum", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "flex_layer", + "c_type": "int", + "array_dim": null + }, + { + "name": "flg_vert", + "c_type": "mjtByte", + "array_dim": null + }, + { + "name": "flg_edge", + "c_type": "mjtByte", + "array_dim": null + }, + { + "name": "flg_face", + "c_type": "mjtByte", + "array_dim": null + }, + { + "name": "flg_skin", + "c_type": "mjtByte", + "array_dim": null + }, + { + "name": "flexid", + "c_type": "int", + "array_dim": null + }, + { + "name": "pnt", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vec", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vertid", + "c_type": "int [1]", + "array_dim": 1 + }, + { + "name": "normal", + "c_type": "mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 712 + }, + "mju_raySkin": { + "name": "mju_raySkin", + "return_type": "mjtNum", + "params": [ + { + "name": "nface", + "c_type": "int", + "array_dim": null + }, + { + "name": "nvert", + "c_type": "int", + "array_dim": null + }, + { + "name": "face", + "c_type": "const int *", + "array_dim": null + }, + { + "name": "vert", + "c_type": "const float *", + "array_dim": null + }, + { + "name": "pnt", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vec", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vertid", + "c_type": "int [1]", + "array_dim": 1 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 720 + }, + "mjv_defaultCamera": { + "name": "mjv_defaultCamera", + "return_type": "void", + "params": [ + { + "name": "cam", + "c_type": "mjvCamera *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 726 + }, + "mjv_defaultFreeCamera": { + "name": "mjv_defaultFreeCamera", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "cam", + "c_type": "mjvCamera *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 729 + }, + "mjv_defaultPerturb": { + "name": "mjv_defaultPerturb", + "return_type": "void", + "params": [ + { + "name": "pert", + "c_type": "mjvPerturb *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 732 + }, + "mjv_room2model": { + "name": "mjv_room2model", + "return_type": "void", + "params": [ + { + "name": "modelpos", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "modelquat", + "c_type": "mjtNum [4]", + "array_dim": 4 + }, + { + "name": "roompos", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "roomquat", + "c_type": "const mjtNum [4]", + "array_dim": 4 + }, + { + "name": "scn", + "c_type": "const mjvScene *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 735 + }, + "mjv_model2room": { + "name": "mjv_model2room", + "return_type": "void", + "params": [ + { + "name": "roompos", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "roomquat", + "c_type": "mjtNum [4]", + "array_dim": 4 + }, + { + "name": "modelpos", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "modelquat", + "c_type": "const mjtNum [4]", + "array_dim": 4 + }, + { + "name": "scn", + "c_type": "const mjvScene *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 739 + }, + "mjv_cameraInModel": { + "name": "mjv_cameraInModel", + "return_type": "void", + "params": [ + { + "name": "headpos", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "forward", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "up", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "scn", + "c_type": "const mjvScene *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 743 + }, + "mjv_cameraInRoom": { + "name": "mjv_cameraInRoom", + "return_type": "void", + "params": [ + { + "name": "headpos", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "forward", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "up", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "scn", + "c_type": "const mjvScene *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 747 + }, + "mjv_frustumHeight": { + "name": "mjv_frustumHeight", + "return_type": "mjtNum", + "params": [ + { + "name": "scn", + "c_type": "const mjvScene *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 751 + }, + "mjv_alignToCamera": { + "name": "mjv_alignToCamera", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vec", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "forward", + "c_type": "const mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 754 + }, + "mjv_moveCamera": { + "name": "mjv_moveCamera", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "action", + "c_type": "int", + "array_dim": null + }, + { + "name": "reldx", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "reldy", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "scn", + "c_type": "const mjvScene *", + "array_dim": null + }, + { + "name": "cam", + "c_type": "mjvCamera *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 757 + }, + "mjv_movePerturb": { + "name": "mjv_movePerturb", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "action", + "c_type": "int", + "array_dim": null + }, + { + "name": "reldx", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "reldy", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "scn", + "c_type": "const mjvScene *", + "array_dim": null + }, + { + "name": "pert", + "c_type": "mjvPerturb *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 761 + }, + "mjv_moveModel": { + "name": "mjv_moveModel", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "action", + "c_type": "int", + "array_dim": null + }, + { + "name": "reldx", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "reldy", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "roomup", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "scn", + "c_type": "mjvScene *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 765 + }, + "mjv_initPerturb": { + "name": "mjv_initPerturb", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "scn", + "c_type": "const mjvScene *", + "array_dim": null + }, + { + "name": "pert", + "c_type": "mjvPerturb *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 769 + }, + "mjv_applyPerturbPose": { + "name": "mjv_applyPerturbPose", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "pert", + "c_type": "const mjvPerturb *", + "array_dim": null + }, + { + "name": "flg_paused", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 773 + }, + "mjv_applyPerturbForce": { + "name": "mjv_applyPerturbForce", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "pert", + "c_type": "const mjvPerturb *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 777 + }, + "mjv_averageCamera": { + "name": "mjv_averageCamera", + "return_type": "mjvGLCamera", + "params": [ + { + "name": "cam1", + "c_type": "const mjvGLCamera *", + "array_dim": null + }, + { + "name": "cam2", + "c_type": "const mjvGLCamera *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 780 + }, + "mjv_select": { + "name": "mjv_select", + "return_type": "int", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "vopt", + "c_type": "const mjvOption *", + "array_dim": null + }, + { + "name": "aspectratio", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "relx", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "rely", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "scn", + "c_type": "const mjvScene *", + "array_dim": null + }, + { + "name": "selpnt", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "geomid", + "c_type": "int [1]", + "array_dim": 1 + }, + { + "name": "flexid", + "c_type": "int [1]", + "array_dim": 1 + }, + { + "name": "skinid", + "c_type": "int [1]", + "array_dim": 1 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 784 + }, + "mjv_defaultOption": { + "name": "mjv_defaultOption", + "return_type": "void", + "params": [ + { + "name": "opt", + "c_type": "mjvOption *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 793 + }, + "mjv_defaultFigure": { + "name": "mjv_defaultFigure", + "return_type": "void", + "params": [ + { + "name": "fig", + "c_type": "mjvFigure *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 796 + }, + "mjv_initGeom": { + "name": "mjv_initGeom", + "return_type": "void", + "params": [ + { + "name": "geom", + "c_type": "mjvGeom *", + "array_dim": null + }, + { + "name": "type", + "c_type": "int", + "array_dim": null + }, + { + "name": "size", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "pos", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "mat", + "c_type": "const mjtNum [9]", + "array_dim": 9 + }, + { + "name": "rgba", + "c_type": "const float [4]", + "array_dim": 4 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 800 + }, + "mjv_connector": { + "name": "mjv_connector", + "return_type": "void", + "params": [ + { + "name": "geom", + "c_type": "mjvGeom *", + "array_dim": null + }, + { + "name": "type", + "c_type": "int", + "array_dim": null + }, + { + "name": "width", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "from", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "to", + "c_type": "const mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 806 + }, + "mjv_defaultScene": { + "name": "mjv_defaultScene", + "return_type": "void", + "params": [ + { + "name": "scn", + "c_type": "mjvScene *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 810 + }, + "mjv_makeScene": { + "name": "mjv_makeScene", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "scn", + "c_type": "mjvScene *", + "array_dim": null + }, + { + "name": "maxgeom", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 813 + }, + "mjv_freeScene": { + "name": "mjv_freeScene", + "return_type": "void", + "params": [ + { + "name": "scn", + "c_type": "mjvScene *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 816 + }, + "mjv_updateScene": { + "name": "mjv_updateScene", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "opt", + "c_type": "const mjvOption *", + "array_dim": null + }, + { + "name": "pert", + "c_type": "const mjvPerturb *", + "array_dim": null + }, + { + "name": "cam", + "c_type": "mjvCamera *", + "array_dim": null + }, + { + "name": "catmask", + "c_type": "int", + "array_dim": null + }, + { + "name": "scn", + "c_type": "mjvScene *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 819 + }, + "mjv_copyModel": { + "name": "mjv_copyModel", + "return_type": "void", + "params": [ + { + "name": "dest", + "c_type": "mjModel *", + "array_dim": null + }, + { + "name": "src", + "c_type": "const mjModel *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 824 + }, + "mjv_addGeoms": { + "name": "mjv_addGeoms", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "opt", + "c_type": "const mjvOption *", + "array_dim": null + }, + { + "name": "pert", + "c_type": "const mjvPerturb *", + "array_dim": null + }, + { + "name": "catmask", + "c_type": "int", + "array_dim": null + }, + { + "name": "scn", + "c_type": "mjvScene *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 827 + }, + "mjv_makeLights": { + "name": "mjv_makeLights", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "scn", + "c_type": "mjvScene *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 831 + }, + "mjv_updateCamera": { + "name": "mjv_updateCamera", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "cam", + "c_type": "mjvCamera *", + "array_dim": null + }, + { + "name": "scn", + "c_type": "mjvScene *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 834 + }, + "mjv_updateSkin": { + "name": "mjv_updateSkin", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "scn", + "c_type": "mjvScene *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 837 + }, + "mjv_cameraFrame": { + "name": "mjv_cameraFrame", + "return_type": "void", + "params": [ + { + "name": "headpos", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "forward", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "up", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "right", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "cam", + "c_type": "const mjvCamera *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 841 + }, + "mjv_cameraFrustum": { + "name": "mjv_cameraFrustum", + "return_type": "void", + "params": [ + { + "name": "zver", + "c_type": "float [2]", + "array_dim": 2 + }, + { + "name": "zhor", + "c_type": "float [2]", + "array_dim": 2 + }, + { + "name": "zclip", + "c_type": "float [2]", + "array_dim": 2 + }, + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "cam", + "c_type": "const mjvCamera *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 846 + }, + "mjr_defaultContext": { + "name": "mjr_defaultContext", + "return_type": "void", + "params": [ + { + "name": "con", + "c_type": "mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 853 + }, + "mjr_makeContext": { + "name": "mjr_makeContext", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "con", + "c_type": "mjrContext *", + "array_dim": null + }, + { + "name": "fontscale", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 856 + }, + "mjr_changeFont": { + "name": "mjr_changeFont", + "return_type": "void", + "params": [ + { + "name": "fontscale", + "c_type": "int", + "array_dim": null + }, + { + "name": "con", + "c_type": "mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 859 + }, + "mjr_addAux": { + "name": "mjr_addAux", + "return_type": "void", + "params": [ + { + "name": "index", + "c_type": "int", + "array_dim": null + }, + { + "name": "width", + "c_type": "int", + "array_dim": null + }, + { + "name": "height", + "c_type": "int", + "array_dim": null + }, + { + "name": "samples", + "c_type": "int", + "array_dim": null + }, + { + "name": "con", + "c_type": "mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 862 + }, + "mjr_freeContext": { + "name": "mjr_freeContext", + "return_type": "void", + "params": [ + { + "name": "con", + "c_type": "mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 865 + }, + "mjr_resizeOffscreen": { + "name": "mjr_resizeOffscreen", + "return_type": "void", + "params": [ + { + "name": "width", + "c_type": "int", + "array_dim": null + }, + { + "name": "height", + "c_type": "int", + "array_dim": null + }, + { + "name": "con", + "c_type": "mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 868 + }, + "mjr_uploadTexture": { + "name": "mjr_uploadTexture", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "con", + "c_type": "const mjrContext *", + "array_dim": null + }, + { + "name": "texid", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 871 + }, + "mjr_uploadMesh": { + "name": "mjr_uploadMesh", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "con", + "c_type": "const mjrContext *", + "array_dim": null + }, + { + "name": "meshid", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 874 + }, + "mjr_uploadHField": { + "name": "mjr_uploadHField", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "con", + "c_type": "const mjrContext *", + "array_dim": null + }, + { + "name": "hfieldid", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 877 + }, + "mjr_restoreBuffer": { + "name": "mjr_restoreBuffer", + "return_type": "void", + "params": [ + { + "name": "con", + "c_type": "const mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 880 + }, + "mjr_setBuffer": { + "name": "mjr_setBuffer", + "return_type": "void", + "params": [ + { + "name": "framebuffer", + "c_type": "int", + "array_dim": null + }, + { + "name": "con", + "c_type": "mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 884 + }, + "mjr_readPixels": { + "name": "mjr_readPixels", + "return_type": "void", + "params": [ + { + "name": "rgb", + "c_type": "unsigned char *", + "array_dim": null + }, + { + "name": "depth", + "c_type": "float *", + "array_dim": null + }, + { + "name": "viewport", + "c_type": "mjrRect", + "array_dim": null + }, + { + "name": "con", + "c_type": "const mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 888 + }, + "mjr_drawPixels": { + "name": "mjr_drawPixels", + "return_type": "void", + "params": [ + { + "name": "rgb", + "c_type": "const unsigned char *", + "array_dim": null + }, + { + "name": "depth", + "c_type": "const float *", + "array_dim": null + }, + { + "name": "viewport", + "c_type": "mjrRect", + "array_dim": null + }, + { + "name": "con", + "c_type": "const mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 893 + }, + "mjr_blitBuffer": { + "name": "mjr_blitBuffer", + "return_type": "void", + "params": [ + { + "name": "src", + "c_type": "mjrRect", + "array_dim": null + }, + { + "name": "dst", + "c_type": "mjrRect", + "array_dim": null + }, + { + "name": "flg_color", + "c_type": "int", + "array_dim": null + }, + { + "name": "flg_depth", + "c_type": "int", + "array_dim": null + }, + { + "name": "con", + "c_type": "const mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 898 + }, + "mjr_setAux": { + "name": "mjr_setAux", + "return_type": "void", + "params": [ + { + "name": "index", + "c_type": "int", + "array_dim": null + }, + { + "name": "con", + "c_type": "const mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 902 + }, + "mjr_blitAux": { + "name": "mjr_blitAux", + "return_type": "void", + "params": [ + { + "name": "index", + "c_type": "int", + "array_dim": null + }, + { + "name": "src", + "c_type": "mjrRect", + "array_dim": null + }, + { + "name": "left", + "c_type": "int", + "array_dim": null + }, + { + "name": "bottom", + "c_type": "int", + "array_dim": null + }, + { + "name": "con", + "c_type": "const mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 905 + }, + "mjr_text": { + "name": "mjr_text", + "return_type": "void", + "params": [ + { + "name": "font", + "c_type": "int", + "array_dim": null + }, + { + "name": "txt", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "con", + "c_type": "const mjrContext *", + "array_dim": null + }, + { + "name": "x", + "c_type": "float", + "array_dim": null + }, + { + "name": "y", + "c_type": "float", + "array_dim": null + }, + { + "name": "r", + "c_type": "float", + "array_dim": null + }, + { + "name": "g", + "c_type": "float", + "array_dim": null + }, + { + "name": "b", + "c_type": "float", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 908 + }, + "mjr_overlay": { + "name": "mjr_overlay", + "return_type": "void", + "params": [ + { + "name": "font", + "c_type": "int", + "array_dim": null + }, + { + "name": "gridpos", + "c_type": "int", + "array_dim": null + }, + { + "name": "viewport", + "c_type": "mjrRect", + "array_dim": null + }, + { + "name": "overlay", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "overlay2", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "con", + "c_type": "const mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 912 + }, + "mjr_maxViewport": { + "name": "mjr_maxViewport", + "return_type": "mjrRect", + "params": [ + { + "name": "con", + "c_type": "const mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 916 + }, + "mjr_rectangle": { + "name": "mjr_rectangle", + "return_type": "void", + "params": [ + { + "name": "viewport", + "c_type": "mjrRect", + "array_dim": null + }, + { + "name": "r", + "c_type": "float", + "array_dim": null + }, + { + "name": "g", + "c_type": "float", + "array_dim": null + }, + { + "name": "b", + "c_type": "float", + "array_dim": null + }, + { + "name": "a", + "c_type": "float", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 919 + }, + "mjr_label": { + "name": "mjr_label", + "return_type": "void", + "params": [ + { + "name": "viewport", + "c_type": "mjrRect", + "array_dim": null + }, + { + "name": "font", + "c_type": "int", + "array_dim": null + }, + { + "name": "txt", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "r", + "c_type": "float", + "array_dim": null + }, + { + "name": "g", + "c_type": "float", + "array_dim": null + }, + { + "name": "b", + "c_type": "float", + "array_dim": null + }, + { + "name": "a", + "c_type": "float", + "array_dim": null + }, + { + "name": "rt", + "c_type": "float", + "array_dim": null + }, + { + "name": "gt", + "c_type": "float", + "array_dim": null + }, + { + "name": "bt", + "c_type": "float", + "array_dim": null + }, + { + "name": "con", + "c_type": "const mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 922 + }, + "mjr_figure": { + "name": "mjr_figure", + "return_type": "void", + "params": [ + { + "name": "viewport", + "c_type": "mjrRect", + "array_dim": null + }, + { + "name": "fig", + "c_type": "mjvFigure *", + "array_dim": null + }, + { + "name": "con", + "c_type": "const mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 927 + }, + "mjr_render": { + "name": "mjr_render", + "return_type": "void", + "params": [ + { + "name": "viewport", + "c_type": "mjrRect", + "array_dim": null + }, + { + "name": "scn", + "c_type": "mjvScene *", + "array_dim": null + }, + { + "name": "con", + "c_type": "const mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 930 + }, + "mjr_finish": { + "name": "mjr_finish", + "return_type": "void", + "params": [], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 933 + }, + "mjr_getError": { + "name": "mjr_getError", + "return_type": "int", + "params": [], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 936 + }, + "mjr_findRect": { + "name": "mjr_findRect", + "return_type": "int", + "params": [ + { + "name": "x", + "c_type": "int", + "array_dim": null + }, + { + "name": "y", + "c_type": "int", + "array_dim": null + }, + { + "name": "nrect", + "c_type": "int", + "array_dim": null + }, + { + "name": "rect", + "c_type": "const mjrRect *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 939 + }, + "mjui_themeSpacing": { + "name": "mjui_themeSpacing", + "return_type": "mjuiThemeSpacing", + "params": [ + { + "name": "ind", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 945 + }, + "mjui_themeColor": { + "name": "mjui_themeColor", + "return_type": "mjuiThemeColor", + "params": [ + { + "name": "ind", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 948 + }, + "mjui_add": { + "name": "mjui_add", + "return_type": "void", + "params": [ + { + "name": "ui", + "c_type": "mjUI *", + "array_dim": null + }, + { + "name": "def", + "c_type": "const mjuiDef *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 951 + }, + "mjui_addToSection": { + "name": "mjui_addToSection", + "return_type": "void", + "params": [ + { + "name": "ui", + "c_type": "mjUI *", + "array_dim": null + }, + { + "name": "sect", + "c_type": "int", + "array_dim": null + }, + { + "name": "def", + "c_type": "const mjuiDef *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 954 + }, + "mjui_resize": { + "name": "mjui_resize", + "return_type": "void", + "params": [ + { + "name": "ui", + "c_type": "mjUI *", + "array_dim": null + }, + { + "name": "con", + "c_type": "const mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 957 + }, + "mjui_update": { + "name": "mjui_update", + "return_type": "void", + "params": [ + { + "name": "section", + "c_type": "int", + "array_dim": null + }, + { + "name": "item", + "c_type": "int", + "array_dim": null + }, + { + "name": "ui", + "c_type": "const mjUI *", + "array_dim": null + }, + { + "name": "state", + "c_type": "const mjuiState *", + "array_dim": null + }, + { + "name": "con", + "c_type": "const mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 960 + }, + "mjui_event": { + "name": "mjui_event", + "return_type": "mjuiItem *", + "params": [ + { + "name": "ui", + "c_type": "mjUI *", + "array_dim": null + }, + { + "name": "state", + "c_type": "mjuiState *", + "array_dim": null + }, + { + "name": "con", + "c_type": "const mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 964 + }, + "mjui_render": { + "name": "mjui_render", + "return_type": "void", + "params": [ + { + "name": "ui", + "c_type": "mjUI *", + "array_dim": null + }, + { + "name": "state", + "c_type": "const mjuiState *", + "array_dim": null + }, + { + "name": "con", + "c_type": "const mjrContext *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 967 + }, + "mju_error": { + "name": "mju_error", + "return_type": "void", + "params": [ + { + "name": "msg", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 973 + }, + "mju_error_i": { + "name": "mju_error_i", + "return_type": "void", + "params": [ + { + "name": "msg", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "i", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 976 + }, + "mju_error_s": { + "name": "mju_error_s", + "return_type": "void", + "params": [ + { + "name": "msg", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "text", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 979 + }, + "mju_warning": { + "name": "mju_warning", + "return_type": "void", + "params": [ + { + "name": "msg", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 982 + }, + "mju_warning_i": { + "name": "mju_warning_i", + "return_type": "void", + "params": [ + { + "name": "msg", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "i", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 985 + }, + "mju_warning_s": { + "name": "mju_warning_s", + "return_type": "void", + "params": [ + { + "name": "msg", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "text", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 988 + }, + "mju_clearHandlers": { + "name": "mju_clearHandlers", + "return_type": "void", + "params": [], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 991 + }, + "mju_malloc": { + "name": "mju_malloc", + "return_type": "void *", + "params": [ + { + "name": "size", + "c_type": "size_t", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 994 + }, + "mju_free": { + "name": "mju_free", + "return_type": "void", + "params": [ + { + "name": "ptr", + "c_type": "void *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 997 + }, + "mj_warning": { + "name": "mj_warning", + "return_type": "void", + "params": [ + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "warning", + "c_type": "int", + "array_dim": null + }, + { + "name": "info", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1000 + }, + "mju_writeLog": { + "name": "mju_writeLog", + "return_type": "void", + "params": [ + { + "name": "type", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "msg", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1003 + }, + "mjs_getError": { + "name": "mjs_getError", + "return_type": "const char *", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1006 + }, + "mjs_isWarning": { + "name": "mjs_isWarning", + "return_type": "int", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1009 + }, + "mju_zero3": { + "name": "mju_zero3", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1053 + }, + "mju_copy3": { + "name": "mju_copy3", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "data", + "c_type": "const mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1056 + }, + "mju_scl3": { + "name": "mju_scl3", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vec", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "scl", + "c_type": "mjtNum", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1059 + }, + "mju_add3": { + "name": "mju_add3", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vec1", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vec2", + "c_type": "const mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1062 + }, + "mju_sub3": { + "name": "mju_sub3", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vec1", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vec2", + "c_type": "const mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1065 + }, + "mju_addTo3": { + "name": "mju_addTo3", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vec", + "c_type": "const mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1068 + }, + "mju_subFrom3": { + "name": "mju_subFrom3", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vec", + "c_type": "const mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1071 + }, + "mju_addToScl3": { + "name": "mju_addToScl3", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vec", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "scl", + "c_type": "mjtNum", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1074 + }, + "mju_addScl3": { + "name": "mju_addScl3", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vec1", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vec2", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "scl", + "c_type": "mjtNum", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1077 + }, + "mju_normalize3": { + "name": "mju_normalize3", + "return_type": "mjtNum", + "params": [ + { + "name": "vec", + "c_type": "mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1080 + }, + "mju_norm3": { + "name": "mju_norm3", + "return_type": "mjtNum", + "params": [ + { + "name": "vec", + "c_type": "const mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1083 + }, + "mju_dot3": { + "name": "mju_dot3", + "return_type": "mjtNum", + "params": [ + { + "name": "vec1", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vec2", + "c_type": "const mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1086 + }, + "mju_dist3": { + "name": "mju_dist3", + "return_type": "mjtNum", + "params": [ + { + "name": "pos1", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "pos2", + "c_type": "const mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1089 + }, + "mju_mulMatVec3": { + "name": "mju_mulMatVec3", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "mat", + "c_type": "const mjtNum [9]", + "array_dim": 9 + }, + { + "name": "vec", + "c_type": "const mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1092 + }, + "mju_mulMatTVec3": { + "name": "mju_mulMatTVec3", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "mat", + "c_type": "const mjtNum [9]", + "array_dim": 9 + }, + { + "name": "vec", + "c_type": "const mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1095 + }, + "mju_cross": { + "name": "mju_cross", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "a", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "b", + "c_type": "const mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1098 + }, + "mju_zero4": { + "name": "mju_zero4", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [4]", + "array_dim": 4 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1101 + }, + "mju_unit4": { + "name": "mju_unit4", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [4]", + "array_dim": 4 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1104 + }, + "mju_copy4": { + "name": "mju_copy4", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [4]", + "array_dim": 4 + }, + { + "name": "data", + "c_type": "const mjtNum [4]", + "array_dim": 4 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1107 + }, + "mju_normalize4": { + "name": "mju_normalize4", + "return_type": "mjtNum", + "params": [ + { + "name": "vec", + "c_type": "mjtNum [4]", + "array_dim": 4 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1110 + }, + "mju_zero": { + "name": "mju_zero", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1113 + }, + "mju_fill": { + "name": "mju_fill", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "val", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1116 + }, + "mju_copy": { + "name": "mju_copy", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "vec", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1119 + }, + "mju_sum": { + "name": "mju_sum", + "return_type": "mjtNum", + "params": [ + { + "name": "vec", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1122 + }, + "mju_L1": { + "name": "mju_L1", + "return_type": "mjtNum", + "params": [ + { + "name": "vec", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1125 + }, + "mju_scl": { + "name": "mju_scl", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "vec", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "scl", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1128 + }, + "mju_add": { + "name": "mju_add", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "vec1", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "vec2", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1131 + }, + "mju_sub": { + "name": "mju_sub", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "vec1", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "vec2", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1134 + }, + "mju_addTo": { + "name": "mju_addTo", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "vec", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1137 + }, + "mju_subFrom": { + "name": "mju_subFrom", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "vec", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1140 + }, + "mju_addToScl": { + "name": "mju_addToScl", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "vec", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "scl", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1143 + }, + "mju_addScl": { + "name": "mju_addScl", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "vec1", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "vec2", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "scl", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1146 + }, + "mju_normalize": { + "name": "mju_normalize", + "return_type": "mjtNum", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1149 + }, + "mju_norm": { + "name": "mju_norm", + "return_type": "mjtNum", + "params": [ + { + "name": "res", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1152 + }, + "mju_dot": { + "name": "mju_dot", + "return_type": "mjtNum", + "params": [ + { + "name": "vec1", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "vec2", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1155 + }, + "mju_mulMatVec": { + "name": "mju_mulMatVec", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "mat", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "vec", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "nr", + "c_type": "int", + "array_dim": null + }, + { + "name": "nc", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1158 + }, + "mju_mulMatTVec": { + "name": "mju_mulMatTVec", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "mat", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "vec", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "nr", + "c_type": "int", + "array_dim": null + }, + { + "name": "nc", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1161 + }, + "mju_mulVecMatVec": { + "name": "mju_mulVecMatVec", + "return_type": "mjtNum", + "params": [ + { + "name": "vec1", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "mat", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "vec2", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1164 + }, + "mju_transpose": { + "name": "mju_transpose", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "mat", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "nr", + "c_type": "int", + "array_dim": null + }, + { + "name": "nc", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1167 + }, + "mju_symmetrize": { + "name": "mju_symmetrize", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "mat", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1170 + }, + "mju_eye": { + "name": "mju_eye", + "return_type": "void", + "params": [ + { + "name": "mat", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1173 + }, + "mju_mulMatMat": { + "name": "mju_mulMatMat", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "mat1", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "mat2", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "r1", + "c_type": "int", + "array_dim": null + }, + { + "name": "c1", + "c_type": "int", + "array_dim": null + }, + { + "name": "c2", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1176 + }, + "mju_mulMatMatT": { + "name": "mju_mulMatMatT", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "mat1", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "mat2", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "r1", + "c_type": "int", + "array_dim": null + }, + { + "name": "c1", + "c_type": "int", + "array_dim": null + }, + { + "name": "r2", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1180 + }, + "mju_mulMatTMat": { + "name": "mju_mulMatTMat", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "mat1", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "mat2", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "r1", + "c_type": "int", + "array_dim": null + }, + { + "name": "c1", + "c_type": "int", + "array_dim": null + }, + { + "name": "c2", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1184 + }, + "mju_sqrMatTD": { + "name": "mju_sqrMatTD", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "mat", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "diag", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "nr", + "c_type": "int", + "array_dim": null + }, + { + "name": "nc", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1188 + }, + "mju_transformSpatial": { + "name": "mju_transformSpatial", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [6]", + "array_dim": 6 + }, + { + "name": "vec", + "c_type": "const mjtNum [6]", + "array_dim": 6 + }, + { + "name": "flg_force", + "c_type": "int", + "array_dim": null + }, + { + "name": "newpos", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "oldpos", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "rotnew2old", + "c_type": "const mjtNum [9]", + "array_dim": 9 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1193 + }, + "mju_dense2sparse": { + "name": "mju_dense2sparse", + "return_type": "int", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "mat", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "nr", + "c_type": "int", + "array_dim": null + }, + { + "name": "nc", + "c_type": "int", + "array_dim": null + }, + { + "name": "rownnz", + "c_type": "int *", + "array_dim": null + }, + { + "name": "rowadr", + "c_type": "int *", + "array_dim": null + }, + { + "name": "colind", + "c_type": "int *", + "array_dim": null + }, + { + "name": "nnz", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1202 + }, + "mju_sparse2dense": { + "name": "mju_sparse2dense", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "mat", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "nr", + "c_type": "int", + "array_dim": null + }, + { + "name": "nc", + "c_type": "int", + "array_dim": null + }, + { + "name": "rownnz", + "c_type": "const int *", + "array_dim": null + }, + { + "name": "rowadr", + "c_type": "const int *", + "array_dim": null + }, + { + "name": "colind", + "c_type": "const int *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1206 + }, + "mju_sym2dense": { + "name": "mju_sym2dense", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "mat", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + }, + { + "name": "rownnz", + "c_type": "const int *", + "array_dim": null + }, + { + "name": "rowadr", + "c_type": "const int *", + "array_dim": null + }, + { + "name": "colind", + "c_type": "const int *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1210 + }, + "mju_rotVecQuat": { + "name": "mju_rotVecQuat", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "vec", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "quat", + "c_type": "const mjtNum [4]", + "array_dim": 4 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1217 + }, + "mju_negQuat": { + "name": "mju_negQuat", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [4]", + "array_dim": 4 + }, + { + "name": "quat", + "c_type": "const mjtNum [4]", + "array_dim": 4 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1220 + }, + "mju_mulQuat": { + "name": "mju_mulQuat", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [4]", + "array_dim": 4 + }, + { + "name": "quat1", + "c_type": "const mjtNum [4]", + "array_dim": 4 + }, + { + "name": "quat2", + "c_type": "const mjtNum [4]", + "array_dim": 4 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1223 + }, + "mju_mulQuatAxis": { + "name": "mju_mulQuatAxis", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [4]", + "array_dim": 4 + }, + { + "name": "quat", + "c_type": "const mjtNum [4]", + "array_dim": 4 + }, + { + "name": "axis", + "c_type": "const mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1226 + }, + "mju_axisAngle2Quat": { + "name": "mju_axisAngle2Quat", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [4]", + "array_dim": 4 + }, + { + "name": "axis", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "angle", + "c_type": "mjtNum", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1229 + }, + "mju_quat2Vel": { + "name": "mju_quat2Vel", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "quat", + "c_type": "const mjtNum [4]", + "array_dim": 4 + }, + { + "name": "dt", + "c_type": "mjtNum", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1232 + }, + "mju_subQuat": { + "name": "mju_subQuat", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "qa", + "c_type": "const mjtNum [4]", + "array_dim": 4 + }, + { + "name": "qb", + "c_type": "const mjtNum [4]", + "array_dim": 4 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1235 + }, + "mju_quat2Mat": { + "name": "mju_quat2Mat", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [9]", + "array_dim": 9 + }, + { + "name": "quat", + "c_type": "const mjtNum [4]", + "array_dim": 4 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1238 + }, + "mju_mat2Quat": { + "name": "mju_mat2Quat", + "return_type": "void", + "params": [ + { + "name": "quat", + "c_type": "mjtNum [4]", + "array_dim": 4 + }, + { + "name": "mat", + "c_type": "const mjtNum [9]", + "array_dim": 9 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1241 + }, + "mju_derivQuat": { + "name": "mju_derivQuat", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [4]", + "array_dim": 4 + }, + { + "name": "quat", + "c_type": "const mjtNum [4]", + "array_dim": 4 + }, + { + "name": "vel", + "c_type": "const mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1244 + }, + "mju_quatIntegrate": { + "name": "mju_quatIntegrate", + "return_type": "void", + "params": [ + { + "name": "quat", + "c_type": "mjtNum [4]", + "array_dim": 4 + }, + { + "name": "vel", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "scale", + "c_type": "mjtNum", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1247 + }, + "mju_quatZ2Vec": { + "name": "mju_quatZ2Vec", + "return_type": "void", + "params": [ + { + "name": "quat", + "c_type": "mjtNum [4]", + "array_dim": 4 + }, + { + "name": "vec", + "c_type": "const mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1250 + }, + "mju_mat2Rot": { + "name": "mju_mat2Rot", + "return_type": "int", + "params": [ + { + "name": "quat", + "c_type": "mjtNum [4]", + "array_dim": 4 + }, + { + "name": "mat", + "c_type": "const mjtNum [9]", + "array_dim": 9 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1254 + }, + "mju_euler2Quat": { + "name": "mju_euler2Quat", + "return_type": "void", + "params": [ + { + "name": "quat", + "c_type": "mjtNum [4]", + "array_dim": 4 + }, + { + "name": "euler", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "seq", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1258 + }, + "mju_mulPose": { + "name": "mju_mulPose", + "return_type": "void", + "params": [ + { + "name": "posres", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "quatres", + "c_type": "mjtNum [4]", + "array_dim": 4 + }, + { + "name": "pos1", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "quat1", + "c_type": "const mjtNum [4]", + "array_dim": 4 + }, + { + "name": "pos2", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "quat2", + "c_type": "const mjtNum [4]", + "array_dim": 4 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1264 + }, + "mju_negPose": { + "name": "mju_negPose", + "return_type": "void", + "params": [ + { + "name": "posres", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "quatres", + "c_type": "mjtNum [4]", + "array_dim": 4 + }, + { + "name": "pos", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "quat", + "c_type": "const mjtNum [4]", + "array_dim": 4 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1269 + }, + "mju_trnVecPose": { + "name": "mju_trnVecPose", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "pos", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "quat", + "c_type": "const mjtNum [4]", + "array_dim": 4 + }, + { + "name": "vec", + "c_type": "const mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1273 + }, + "mju_cholFactor": { + "name": "mju_cholFactor", + "return_type": "int", + "params": [ + { + "name": "mat", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + }, + { + "name": "mindiag", + "c_type": "mjtNum", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1280 + }, + "mju_cholSolve": { + "name": "mju_cholSolve", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "mat", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "vec", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1283 + }, + "mju_cholUpdate": { + "name": "mju_cholUpdate", + "return_type": "int", + "params": [ + { + "name": "mat", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "x", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + }, + { + "name": "flg_plus", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1286 + }, + "mju_cholFactorBand": { + "name": "mju_cholFactorBand", + "return_type": "mjtNum", + "params": [ + { + "name": "mat", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "ntotal", + "c_type": "int", + "array_dim": null + }, + { + "name": "nband", + "c_type": "int", + "array_dim": null + }, + { + "name": "ndense", + "c_type": "int", + "array_dim": null + }, + { + "name": "diagadd", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "diagmul", + "c_type": "mjtNum", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1294 + }, + "mju_cholSolveBand": { + "name": "mju_cholSolveBand", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "mat", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "vec", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "ntotal", + "c_type": "int", + "array_dim": null + }, + { + "name": "nband", + "c_type": "int", + "array_dim": null + }, + { + "name": "ndense", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1298 + }, + "mju_band2Dense": { + "name": "mju_band2Dense", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "mat", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "ntotal", + "c_type": "int", + "array_dim": null + }, + { + "name": "nband", + "c_type": "int", + "array_dim": null + }, + { + "name": "ndense", + "c_type": "int", + "array_dim": null + }, + { + "name": "flg_sym", + "c_type": "mjtByte", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1302 + }, + "mju_dense2Band": { + "name": "mju_dense2Band", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "mat", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "ntotal", + "c_type": "int", + "array_dim": null + }, + { + "name": "nband", + "c_type": "int", + "array_dim": null + }, + { + "name": "ndense", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1306 + }, + "mju_bandMulMatVec": { + "name": "mju_bandMulMatVec", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "mat", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "vec", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "ntotal", + "c_type": "int", + "array_dim": null + }, + { + "name": "nband", + "c_type": "int", + "array_dim": null + }, + { + "name": "ndense", + "c_type": "int", + "array_dim": null + }, + { + "name": "nvec", + "c_type": "int", + "array_dim": null + }, + { + "name": "flg_sym", + "c_type": "mjtByte", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1309 + }, + "mju_bandDiag": { + "name": "mju_bandDiag", + "return_type": "int", + "params": [ + { + "name": "i", + "c_type": "int", + "array_dim": null + }, + { + "name": "ntotal", + "c_type": "int", + "array_dim": null + }, + { + "name": "nband", + "c_type": "int", + "array_dim": null + }, + { + "name": "ndense", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1313 + }, + "mju_eig3": { + "name": "mju_eig3", + "return_type": "int", + "params": [ + { + "name": "eigval", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "eigvec", + "c_type": "mjtNum [9]", + "array_dim": 9 + }, + { + "name": "quat", + "c_type": "mjtNum [4]", + "array_dim": 4 + }, + { + "name": "mat", + "c_type": "const mjtNum [9]", + "array_dim": 9 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1316 + }, + "mju_boxQP": { + "name": "mju_boxQP", + "return_type": "int", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "R", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "index", + "c_type": "int *", + "array_dim": null + }, + { + "name": "H", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "g", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + }, + { + "name": "lower", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "upper", + "c_type": "const mjtNum *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1340 + }, + "mju_boxQPmalloc": { + "name": "mju_boxQPmalloc", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum **", + "array_dim": null + }, + { + "name": "R", + "c_type": "mjtNum **", + "array_dim": null + }, + { + "name": "index", + "c_type": "int **", + "array_dim": null + }, + { + "name": "H", + "c_type": "mjtNum **", + "array_dim": null + }, + { + "name": "g", + "c_type": "mjtNum **", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + }, + { + "name": "lower", + "c_type": "mjtNum **", + "array_dim": null + }, + { + "name": "upper", + "c_type": "mjtNum **", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1346 + }, + "mju_muscleGain": { + "name": "mju_muscleGain", + "return_type": "mjtNum", + "params": [ + { + "name": "len", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "vel", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "lengthrange", + "c_type": "const mjtNum [2]", + "array_dim": 2 + }, + { + "name": "acc0", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "prm", + "c_type": "const mjtNum [9]", + "array_dim": 9 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1353 + }, + "mju_muscleBias": { + "name": "mju_muscleBias", + "return_type": "mjtNum", + "params": [ + { + "name": "len", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "lengthrange", + "c_type": "const mjtNum [2]", + "array_dim": 2 + }, + { + "name": "acc0", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "prm", + "c_type": "const mjtNum [9]", + "array_dim": 9 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1357 + }, + "mju_muscleDynamics": { + "name": "mju_muscleDynamics", + "return_type": "mjtNum", + "params": [ + { + "name": "ctrl", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "act", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "prm", + "c_type": "const mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1361 + }, + "mju_encodePyramid": { + "name": "mju_encodePyramid", + "return_type": "void", + "params": [ + { + "name": "pyramid", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "force", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "mu", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "dim", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1364 + }, + "mju_decodePyramid": { + "name": "mju_decodePyramid", + "return_type": "void", + "params": [ + { + "name": "force", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "pyramid", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "mu", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "dim", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1367 + }, + "mju_springDamper": { + "name": "mju_springDamper", + "return_type": "mjtNum", + "params": [ + { + "name": "pos0", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "vel0", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "Kp", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "Kv", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "dt", + "c_type": "mjtNum", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1370 + }, + "mju_min": { + "name": "mju_min", + "return_type": "mjtNum", + "params": [ + { + "name": "a", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "b", + "c_type": "mjtNum", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1373 + }, + "mju_max": { + "name": "mju_max", + "return_type": "mjtNum", + "params": [ + { + "name": "a", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "b", + "c_type": "mjtNum", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1376 + }, + "mju_clip": { + "name": "mju_clip", + "return_type": "mjtNum", + "params": [ + { + "name": "x", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "min", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "max", + "c_type": "mjtNum", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1379 + }, + "mju_sign": { + "name": "mju_sign", + "return_type": "mjtNum", + "params": [ + { + "name": "x", + "c_type": "mjtNum", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1382 + }, + "mju_round": { + "name": "mju_round", + "return_type": "int", + "params": [ + { + "name": "x", + "c_type": "mjtNum", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1385 + }, + "mju_type2Str": { + "name": "mju_type2Str", + "return_type": "const char *", + "params": [ + { + "name": "type", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1388 + }, + "mju_str2Type": { + "name": "mju_str2Type", + "return_type": "int", + "params": [ + { + "name": "str", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1391 + }, + "mju_writeNumBytes": { + "name": "mju_writeNumBytes", + "return_type": "const char *", + "params": [ + { + "name": "nbytes", + "c_type": "size_t", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1394 + }, + "mju_warningText": { + "name": "mju_warningText", + "return_type": "const char *", + "params": [ + { + "name": "warning", + "c_type": "int", + "array_dim": null + }, + { + "name": "info", + "c_type": "size_t", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1397 + }, + "mju_isBad": { + "name": "mju_isBad", + "return_type": "int", + "params": [ + { + "name": "x", + "c_type": "mjtNum", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1400 + }, + "mju_isZero": { + "name": "mju_isZero", + "return_type": "int", + "params": [ + { + "name": "vec", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1403 + }, + "mju_standardNormal": { + "name": "mju_standardNormal", + "return_type": "mjtNum", + "params": [ + { + "name": "num2", + "c_type": "mjtNum *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1406 + }, + "mju_f2n": { + "name": "mju_f2n", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "vec", + "c_type": "const float *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1409 + }, + "mju_n2f": { + "name": "mju_n2f", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "float *", + "array_dim": null + }, + { + "name": "vec", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1412 + }, + "mju_d2n": { + "name": "mju_d2n", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "vec", + "c_type": "const double *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1415 + }, + "mju_n2d": { + "name": "mju_n2d", + "return_type": "void", + "params": [ + { + "name": "res", + "c_type": "double *", + "array_dim": null + }, + { + "name": "vec", + "c_type": "const mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1418 + }, + "mju_insertionSort": { + "name": "mju_insertionSort", + "return_type": "void", + "params": [ + { + "name": "list", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1421 + }, + "mju_insertionSortInt": { + "name": "mju_insertionSortInt", + "return_type": "void", + "params": [ + { + "name": "list", + "c_type": "int *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1424 + }, + "mju_Halton": { + "name": "mju_Halton", + "return_type": "mjtNum", + "params": [ + { + "name": "index", + "c_type": "int", + "array_dim": null + }, + { + "name": "base", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1427 + }, + "mju_strncpy": { + "name": "mju_strncpy", + "return_type": "char *", + "params": [ + { + "name": "dst", + "c_type": "char *", + "array_dim": null + }, + { + "name": "src", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "n", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1430 + }, + "mju_sigmoid": { + "name": "mju_sigmoid", + "return_type": "mjtNum", + "params": [ + { + "name": "x", + "c_type": "mjtNum", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1433 + }, + "mjc_getSDF": { + "name": "mjc_getSDF", + "return_type": "const mjpPlugin *", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "id", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1439 + }, + "mjc_distance": { + "name": "mjc_distance", + "return_type": "mjtNum", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "s", + "c_type": "const mjSDF *", + "array_dim": null + }, + { + "name": "x", + "c_type": "const mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1442 + }, + "mjc_gradient": { + "name": "mjc_gradient", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "const mjData *", + "array_dim": null + }, + { + "name": "s", + "c_type": "const mjSDF *", + "array_dim": null + }, + { + "name": "gradient", + "c_type": "mjtNum [3]", + "array_dim": 3 + }, + { + "name": "x", + "c_type": "const mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1445 + }, + "mjd_transitionFD": { + "name": "mjd_transitionFD", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "eps", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "flg_centered", + "c_type": "mjtByte", + "array_dim": null + }, + { + "name": "A", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "B", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "C", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "D", + "c_type": "mjtNum *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1460 + }, + "mjd_inverseFD": { + "name": "mjd_inverseFD", + "return_type": "void", + "params": [ + { + "name": "m", + "c_type": "const mjModel *", + "array_dim": null + }, + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "eps", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "flg_actuation", + "c_type": "mjtByte", + "array_dim": null + }, + { + "name": "DfDq", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "DfDv", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "DfDa", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "DsDq", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "DsDv", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "DsDa", + "c_type": "mjtNum *", + "array_dim": null + }, + { + "name": "DmDq", + "c_type": "mjtNum *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1479 + }, + "mjd_subQuat": { + "name": "mjd_subQuat", + "return_type": "void", + "params": [ + { + "name": "qa", + "c_type": "const mjtNum [4]", + "array_dim": 4 + }, + { + "name": "qb", + "c_type": "const mjtNum [4]", + "array_dim": 4 + }, + { + "name": "Da", + "c_type": "mjtNum [9]", + "array_dim": 9 + }, + { + "name": "Db", + "c_type": "mjtNum [9]", + "array_dim": 9 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1486 + }, + "mjd_quatIntegrate": { + "name": "mjd_quatIntegrate", + "return_type": "void", + "params": [ + { + "name": "vel", + "c_type": "const mjtNum [3]", + "array_dim": 3 + }, + { + "name": "scale", + "c_type": "mjtNum", + "array_dim": null + }, + { + "name": "Dquat", + "c_type": "mjtNum [9]", + "array_dim": 9 + }, + { + "name": "Dvel", + "c_type": "mjtNum [9]", + "array_dim": 9 + }, + { + "name": "Dscale", + "c_type": "mjtNum [3]", + "array_dim": 3 + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1490 + }, + "mjp_defaultPlugin": { + "name": "mjp_defaultPlugin", + "return_type": "void", + "params": [ + { + "name": "plugin", + "c_type": "mjpPlugin *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1497 + }, + "mjp_registerPlugin": { + "name": "mjp_registerPlugin", + "return_type": "int", + "params": [ + { + "name": "plugin", + "c_type": "const mjpPlugin *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1505 + }, + "mjp_pluginCount": { + "name": "mjp_pluginCount", + "return_type": "int", + "params": [], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1508 + }, + "mjp_getPlugin": { + "name": "mjp_getPlugin", + "return_type": "const mjpPlugin *", + "params": [ + { + "name": "name", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "slot", + "c_type": "int *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1511 + }, + "mjp_getPluginAtSlot": { + "name": "mjp_getPluginAtSlot", + "return_type": "const mjpPlugin *", + "params": [ + { + "name": "slot", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1514 + }, + "mjp_defaultResourceProvider": { + "name": "mjp_defaultResourceProvider", + "return_type": "void", + "params": [ + { + "name": "provider", + "c_type": "mjpResourceProvider *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1517 + }, + "mjp_registerResourceProvider": { + "name": "mjp_registerResourceProvider", + "return_type": "int", + "params": [ + { + "name": "provider", + "c_type": "const mjpResourceProvider *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1522 + }, + "mjp_resourceProviderCount": { + "name": "mjp_resourceProviderCount", + "return_type": "int", + "params": [], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1525 + }, + "mjp_getResourceProvider": { + "name": "mjp_getResourceProvider", + "return_type": "const mjpResourceProvider *", + "params": [ + { + "name": "resource_name", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1529 + }, + "mjp_getResourceProviderAtSlot": { + "name": "mjp_getResourceProviderAtSlot", + "return_type": "const mjpResourceProvider *", + "params": [ + { + "name": "slot", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1533 + }, + "mjp_registerDecoder": { + "name": "mjp_registerDecoder", + "return_type": "void", + "params": [ + { + "name": "decoder", + "c_type": "const mjpDecoder *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1538 + }, + "mjp_defaultDecoder": { + "name": "mjp_defaultDecoder", + "return_type": "void", + "params": [ + { + "name": "decoder", + "c_type": "mjpDecoder *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1541 + }, + "mjp_findDecoder": { + "name": "mjp_findDecoder", + "return_type": "const mjpDecoder *", + "params": [ + { + "name": "resource", + "c_type": "const mjResource *", + "array_dim": null + }, + { + "name": "content_type", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1545 + }, + "mjp_registerEncoder": { + "name": "mjp_registerEncoder", + "return_type": "void", + "params": [ + { + "name": "encoder", + "c_type": "const mjpEncoder *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1550 + }, + "mjp_defaultEncoder": { + "name": "mjp_defaultEncoder", + "return_type": "void", + "params": [ + { + "name": "encoder", + "c_type": "mjpEncoder *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1553 + }, + "mjp_findEncoder": { + "name": "mjp_findEncoder", + "return_type": "const mjpEncoder *", + "params": [ + { + "name": "filename", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "content_type", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1557 + }, + "mju_openResource": { + "name": "mju_openResource", + "return_type": "mjResource *", + "params": [ + { + "name": "dir", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "name", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "vfs", + "c_type": "const mjVFS *", + "array_dim": null + }, + { + "name": "error", + "c_type": "char *", + "array_dim": null + }, + { + "name": "nerror", + "c_type": "size_t", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1566 + }, + "mju_closeResource": { + "name": "mju_closeResource", + "return_type": "void", + "params": [ + { + "name": "resource", + "c_type": "mjResource *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1570 + }, + "mju_readResource": { + "name": "mju_readResource", + "return_type": "int", + "params": [ + { + "name": "resource", + "c_type": "mjResource *", + "array_dim": null + }, + { + "name": "buffer", + "c_type": "const void **", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1574 + }, + "mju_getResourceDir": { + "name": "mju_getResourceDir", + "return_type": "void", + "params": [ + { + "name": "resource", + "c_type": "mjResource *", + "array_dim": null + }, + { + "name": "dir", + "c_type": "const char **", + "array_dim": null + }, + { + "name": "ndir", + "c_type": "int *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1577 + }, + "mju_isModifiedResource": { + "name": "mju_isModifiedResource", + "return_type": "int", + "params": [ + { + "name": "resource", + "c_type": "const mjResource *", + "array_dim": null + }, + { + "name": "timestamp", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1581 + }, + "mju_decodeResource": { + "name": "mju_decodeResource", + "return_type": "mjSpec *", + "params": [ + { + "name": "resource", + "c_type": "mjResource *", + "array_dim": null + }, + { + "name": "content_type", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "vfs", + "c_type": "const mjVFS *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1586 + }, + "mju_threadPoolCreate": { + "name": "mju_threadPoolCreate", + "return_type": "mjThreadPool *", + "params": [ + { + "name": "number_of_threads", + "c_type": "size_t", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1593 + }, + "mju_bindThreadPool": { + "name": "mju_bindThreadPool", + "return_type": "void", + "params": [ + { + "name": "d", + "c_type": "mjData *", + "array_dim": null + }, + { + "name": "thread_pool", + "c_type": "void *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1596 + }, + "mju_threadPoolEnqueue": { + "name": "mju_threadPoolEnqueue", + "return_type": "void", + "params": [ + { + "name": "thread_pool", + "c_type": "mjThreadPool *", + "array_dim": null + }, + { + "name": "task", + "c_type": "mjTask *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1599 + }, + "mju_threadPoolDestroy": { + "name": "mju_threadPoolDestroy", + "return_type": "void", + "params": [ + { + "name": "thread_pool", + "c_type": "mjThreadPool *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1602 + }, + "mju_defaultTask": { + "name": "mju_defaultTask", + "return_type": "void", + "params": [ + { + "name": "task", + "c_type": "mjTask *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1605 + }, + "mju_taskJoin": { + "name": "mju_taskJoin", + "return_type": "void", + "params": [ + { + "name": "task", + "c_type": "mjTask *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1608 + }, + "mjs_attach": { + "name": "mjs_attach", + "return_type": "mjsElement *", + "params": [ + { + "name": "parent", + "c_type": "mjsElement *", + "array_dim": null + }, + { + "name": "child", + "c_type": "const mjsElement *", + "array_dim": null + }, + { + "name": "prefix", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "suffix", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1614 + }, + "mjs_addBody": { + "name": "mjs_addBody", + "return_type": "mjsBody *", + "params": [ + { + "name": "body", + "c_type": "mjsBody *", + "array_dim": null + }, + { + "name": "def", + "c_type": "const mjsDefault *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1622 + }, + "mjs_addSite": { + "name": "mjs_addSite", + "return_type": "mjsSite *", + "params": [ + { + "name": "body", + "c_type": "mjsBody *", + "array_dim": null + }, + { + "name": "def", + "c_type": "const mjsDefault *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1626 + }, + "mjs_addJoint": { + "name": "mjs_addJoint", + "return_type": "mjsJoint *", + "params": [ + { + "name": "body", + "c_type": "mjsBody *", + "array_dim": null + }, + { + "name": "def", + "c_type": "const mjsDefault *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1630 + }, + "mjs_addFreeJoint": { + "name": "mjs_addFreeJoint", + "return_type": "mjsJoint *", + "params": [ + { + "name": "body", + "c_type": "mjsBody *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1633 + }, + "mjs_addGeom": { + "name": "mjs_addGeom", + "return_type": "mjsGeom *", + "params": [ + { + "name": "body", + "c_type": "mjsBody *", + "array_dim": null + }, + { + "name": "def", + "c_type": "const mjsDefault *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1637 + }, + "mjs_addCamera": { + "name": "mjs_addCamera", + "return_type": "mjsCamera *", + "params": [ + { + "name": "body", + "c_type": "mjsBody *", + "array_dim": null + }, + { + "name": "def", + "c_type": "const mjsDefault *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1641 + }, + "mjs_addLight": { + "name": "mjs_addLight", + "return_type": "mjsLight *", + "params": [ + { + "name": "body", + "c_type": "mjsBody *", + "array_dim": null + }, + { + "name": "def", + "c_type": "const mjsDefault *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1645 + }, + "mjs_addFrame": { + "name": "mjs_addFrame", + "return_type": "mjsFrame *", + "params": [ + { + "name": "body", + "c_type": "mjsBody *", + "array_dim": null + }, + { + "name": "parentframe", + "c_type": "mjsFrame *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1648 + }, + "mjs_delete": { + "name": "mjs_delete", + "return_type": "int", + "params": [ + { + "name": "spec", + "c_type": "mjSpec *", + "array_dim": null + }, + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1651 + }, + "mjs_addActuator": { + "name": "mjs_addActuator", + "return_type": "mjsActuator *", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + }, + { + "name": "def", + "c_type": "const mjsDefault *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1658 + }, + "mjs_addSensor": { + "name": "mjs_addSensor", + "return_type": "mjsSensor *", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1661 + }, + "mjs_addFlex": { + "name": "mjs_addFlex", + "return_type": "mjsFlex *", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1664 + }, + "mjs_addPair": { + "name": "mjs_addPair", + "return_type": "mjsPair *", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + }, + { + "name": "def", + "c_type": "const mjsDefault *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1668 + }, + "mjs_addExclude": { + "name": "mjs_addExclude", + "return_type": "mjsExclude *", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1671 + }, + "mjs_addEquality": { + "name": "mjs_addEquality", + "return_type": "mjsEquality *", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + }, + { + "name": "def", + "c_type": "const mjsDefault *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1675 + }, + "mjs_addTendon": { + "name": "mjs_addTendon", + "return_type": "mjsTendon *", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + }, + { + "name": "def", + "c_type": "const mjsDefault *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1679 + }, + "mjs_wrapSite": { + "name": "mjs_wrapSite", + "return_type": "mjsWrap *", + "params": [ + { + "name": "tendon", + "c_type": "mjsTendon *", + "array_dim": null + }, + { + "name": "name", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1682 + }, + "mjs_wrapGeom": { + "name": "mjs_wrapGeom", + "return_type": "mjsWrap *", + "params": [ + { + "name": "tendon", + "c_type": "mjsTendon *", + "array_dim": null + }, + { + "name": "name", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "sidesite", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1685 + }, + "mjs_wrapJoint": { + "name": "mjs_wrapJoint", + "return_type": "mjsWrap *", + "params": [ + { + "name": "tendon", + "c_type": "mjsTendon *", + "array_dim": null + }, + { + "name": "name", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "coef", + "c_type": "double", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1688 + }, + "mjs_wrapPulley": { + "name": "mjs_wrapPulley", + "return_type": "mjsWrap *", + "params": [ + { + "name": "tendon", + "c_type": "mjsTendon *", + "array_dim": null + }, + { + "name": "divisor", + "c_type": "double", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1691 + }, + "mjs_addNumeric": { + "name": "mjs_addNumeric", + "return_type": "mjsNumeric *", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1694 + }, + "mjs_addText": { + "name": "mjs_addText", + "return_type": "mjsText *", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1697 + }, + "mjs_addTuple": { + "name": "mjs_addTuple", + "return_type": "mjsTuple *", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1700 + }, + "mjs_addKey": { + "name": "mjs_addKey", + "return_type": "mjsKey *", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1703 + }, + "mjs_addPlugin": { + "name": "mjs_addPlugin", + "return_type": "mjsPlugin *", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1706 + }, + "mjs_addDefault": { + "name": "mjs_addDefault", + "return_type": "mjsDefault *", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + }, + { + "name": "classname", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "parent", + "c_type": "const mjsDefault *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1710 + }, + "mjs_setToMotor": { + "name": "mjs_setToMotor", + "return_type": "const char *", + "params": [ + { + "name": "actuator", + "c_type": "mjsActuator *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1716 + }, + "mjs_setToPosition": { + "name": "mjs_setToPosition", + "return_type": "const char *", + "params": [ + { + "name": "actuator", + "c_type": "mjsActuator *", + "array_dim": null + }, + { + "name": "kp", + "c_type": "double", + "array_dim": null + }, + { + "name": "kv", + "c_type": "double [1]", + "array_dim": 1 + }, + { + "name": "dampratio", + "c_type": "double [1]", + "array_dim": 1 + }, + { + "name": "timeconst", + "c_type": "double [1]", + "array_dim": 1 + }, + { + "name": "inheritrange", + "c_type": "double", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1719 + }, + "mjs_setToIntVelocity": { + "name": "mjs_setToIntVelocity", + "return_type": "const char *", + "params": [ + { + "name": "actuator", + "c_type": "mjsActuator *", + "array_dim": null + }, + { + "name": "kp", + "c_type": "double", + "array_dim": null + }, + { + "name": "kv", + "c_type": "double [1]", + "array_dim": 1 + }, + { + "name": "dampratio", + "c_type": "double [1]", + "array_dim": 1 + }, + { + "name": "timeconst", + "c_type": "double [1]", + "array_dim": 1 + }, + { + "name": "inheritrange", + "c_type": "double", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1723 + }, + "mjs_setToVelocity": { + "name": "mjs_setToVelocity", + "return_type": "const char *", + "params": [ + { + "name": "actuator", + "c_type": "mjsActuator *", + "array_dim": null + }, + { + "name": "kv", + "c_type": "double", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1727 + }, + "mjs_setToDamper": { + "name": "mjs_setToDamper", + "return_type": "const char *", + "params": [ + { + "name": "actuator", + "c_type": "mjsActuator *", + "array_dim": null + }, + { + "name": "kv", + "c_type": "double", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1730 + }, + "mjs_setToCylinder": { + "name": "mjs_setToCylinder", + "return_type": "const char *", + "params": [ + { + "name": "actuator", + "c_type": "mjsActuator *", + "array_dim": null + }, + { + "name": "timeconst", + "c_type": "double", + "array_dim": null + }, + { + "name": "bias", + "c_type": "double", + "array_dim": null + }, + { + "name": "area", + "c_type": "double", + "array_dim": null + }, + { + "name": "diameter", + "c_type": "double", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1733 + }, + "mjs_setToMuscle": { + "name": "mjs_setToMuscle", + "return_type": "const char *", + "params": [ + { + "name": "actuator", + "c_type": "mjsActuator *", + "array_dim": null + }, + { + "name": "timeconst", + "c_type": "double [2]", + "array_dim": 2 + }, + { + "name": "tausmooth", + "c_type": "double", + "array_dim": null + }, + { + "name": "range", + "c_type": "double [2]", + "array_dim": 2 + }, + { + "name": "force", + "c_type": "double", + "array_dim": null + }, + { + "name": "scale", + "c_type": "double", + "array_dim": null + }, + { + "name": "lmin", + "c_type": "double", + "array_dim": null + }, + { + "name": "lmax", + "c_type": "double", + "array_dim": null + }, + { + "name": "vmax", + "c_type": "double", + "array_dim": null + }, + { + "name": "fpmax", + "c_type": "double", + "array_dim": null + }, + { + "name": "fvmax", + "c_type": "double", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1737 + }, + "mjs_setToAdhesion": { + "name": "mjs_setToAdhesion", + "return_type": "const char *", + "params": [ + { + "name": "actuator", + "c_type": "mjsActuator *", + "array_dim": null + }, + { + "name": "gain", + "c_type": "double", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1742 + }, + "mjs_setToDCMotor": { + "name": "mjs_setToDCMotor", + "return_type": "const char *", + "params": [ + { + "name": "actuator", + "c_type": "mjsActuator *", + "array_dim": null + }, + { + "name": "motorconst", + "c_type": "double [2]", + "array_dim": 2 + }, + { + "name": "resistance", + "c_type": "double", + "array_dim": null + }, + { + "name": "nominal", + "c_type": "double [3]", + "array_dim": 3 + }, + { + "name": "saturation", + "c_type": "double [3]", + "array_dim": 3 + }, + { + "name": "inductance", + "c_type": "double [2]", + "array_dim": 2 + }, + { + "name": "cogging", + "c_type": "double [3]", + "array_dim": 3 + }, + { + "name": "controller", + "c_type": "double [6]", + "array_dim": 6 + }, + { + "name": "thermal", + "c_type": "double [6]", + "array_dim": 6 + }, + { + "name": "lugre", + "c_type": "double [5]", + "array_dim": 5 + }, + { + "name": "input_mode", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1746 + }, + "mjs_addMesh": { + "name": "mjs_addMesh", + "return_type": "mjsMesh *", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + }, + { + "name": "def", + "c_type": "const mjsDefault *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1756 + }, + "mjs_addHField": { + "name": "mjs_addHField", + "return_type": "mjsHField *", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1759 + }, + "mjs_addSkin": { + "name": "mjs_addSkin", + "return_type": "mjsSkin *", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1762 + }, + "mjs_addTexture": { + "name": "mjs_addTexture", + "return_type": "mjsTexture *", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1765 + }, + "mjs_addMaterial": { + "name": "mjs_addMaterial", + "return_type": "mjsMaterial *", + "params": [ + { + "name": "s", + "c_type": "mjSpec *", + "array_dim": null + }, + { + "name": "def", + "c_type": "const mjsDefault *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1769 + }, + "mjs_makeMesh": { + "name": "mjs_makeMesh", + "return_type": "int", + "params": [ + { + "name": "mesh", + "c_type": "mjsMesh *", + "array_dim": null + }, + { + "name": "builtin", + "c_type": "mjtMeshBuiltin", + "array_dim": null + }, + { + "name": "params", + "c_type": "double *", + "array_dim": null + }, + { + "name": "nparams", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1772 + }, + "mjs_getSpec": { + "name": "mjs_getSpec", + "return_type": "mjSpec *", + "params": [ + { + "name": "element", + "c_type": "const mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1777 + }, + "mjs_getOriginSpec": { + "name": "mjs_getOriginSpec", + "return_type": "mjSpec *", + "params": [ + { + "name": "element", + "c_type": "const mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1781 + }, + "mjs_getCompiler": { + "name": "mjs_getCompiler", + "return_type": "mjsCompiler *", + "params": [ + { + "name": "element", + "c_type": "const mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1784 + }, + "mjs_findSpec": { + "name": "mjs_findSpec", + "return_type": "mjSpec *", + "params": [ + { + "name": "spec", + "c_type": "const mjSpec *", + "array_dim": null + }, + { + "name": "name", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1787 + }, + "mjs_findBody": { + "name": "mjs_findBody", + "return_type": "mjsBody *", + "params": [ + { + "name": "s", + "c_type": "const mjSpec *", + "array_dim": null + }, + { + "name": "name", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1790 + }, + "mjs_findElement": { + "name": "mjs_findElement", + "return_type": "mjsElement *", + "params": [ + { + "name": "s", + "c_type": "const mjSpec *", + "array_dim": null + }, + { + "name": "type", + "c_type": "mjtObj", + "array_dim": null + }, + { + "name": "name", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1793 + }, + "mjs_findChild": { + "name": "mjs_findChild", + "return_type": "mjsBody *", + "params": [ + { + "name": "body", + "c_type": "const mjsBody *", + "array_dim": null + }, + { + "name": "name", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1796 + }, + "mjs_getParent": { + "name": "mjs_getParent", + "return_type": "mjsBody *", + "params": [ + { + "name": "element", + "c_type": "const mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1799 + }, + "mjs_getFrame": { + "name": "mjs_getFrame", + "return_type": "mjsFrame *", + "params": [ + { + "name": "element", + "c_type": "const mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1802 + }, + "mjs_findFrame": { + "name": "mjs_findFrame", + "return_type": "mjsFrame *", + "params": [ + { + "name": "s", + "c_type": "const mjSpec *", + "array_dim": null + }, + { + "name": "name", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1805 + }, + "mjs_getDefault": { + "name": "mjs_getDefault", + "return_type": "mjsDefault *", + "params": [ + { + "name": "element", + "c_type": "const mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1808 + }, + "mjs_findDefault": { + "name": "mjs_findDefault", + "return_type": "mjsDefault *", + "params": [ + { + "name": "s", + "c_type": "const mjSpec *", + "array_dim": null + }, + { + "name": "classname", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1811 + }, + "mjs_getSpecDefault": { + "name": "mjs_getSpecDefault", + "return_type": "mjsDefault *", + "params": [ + { + "name": "s", + "c_type": "const mjSpec *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1814 + }, + "mjs_getId": { + "name": "mjs_getId", + "return_type": "int", + "params": [ + { + "name": "element", + "c_type": "const mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1817 + }, + "mjs_firstChild": { + "name": "mjs_firstChild", + "return_type": "mjsElement *", + "params": [ + { + "name": "body", + "c_type": "const mjsBody *", + "array_dim": null + }, + { + "name": "type", + "c_type": "mjtObj", + "array_dim": null + }, + { + "name": "recurse", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1820 + }, + "mjs_nextChild": { + "name": "mjs_nextChild", + "return_type": "mjsElement *", + "params": [ + { + "name": "body", + "c_type": "const mjsBody *", + "array_dim": null + }, + { + "name": "child", + "c_type": "const mjsElement *", + "array_dim": null + }, + { + "name": "recurse", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1824 + }, + "mjs_firstElement": { + "name": "mjs_firstElement", + "return_type": "mjsElement *", + "params": [ + { + "name": "s", + "c_type": "const mjSpec *", + "array_dim": null + }, + { + "name": "type", + "c_type": "mjtObj", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1827 + }, + "mjs_nextElement": { + "name": "mjs_nextElement", + "return_type": "mjsElement *", + "params": [ + { + "name": "s", + "c_type": "const mjSpec *", + "array_dim": null + }, + { + "name": "element", + "c_type": "const mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1830 + }, + "mjs_getWrapTarget": { + "name": "mjs_getWrapTarget", + "return_type": "mjsElement *", + "params": [ + { + "name": "wrap", + "c_type": "const mjsWrap *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1833 + }, + "mjs_getWrapSideSite": { + "name": "mjs_getWrapSideSite", + "return_type": "mjsSite *", + "params": [ + { + "name": "wrap", + "c_type": "const mjsWrap *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1836 + }, + "mjs_getWrapDivisor": { + "name": "mjs_getWrapDivisor", + "return_type": "double", + "params": [ + { + "name": "wrap", + "c_type": "const mjsWrap *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1839 + }, + "mjs_getWrapCoef": { + "name": "mjs_getWrapCoef", + "return_type": "double", + "params": [ + { + "name": "wrap", + "c_type": "const mjsWrap *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1842 + }, + "mjs_setName": { + "name": "mjs_setName", + "return_type": "int", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + }, + { + "name": "name", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1847 + }, + "mjs_setBuffer": { + "name": "mjs_setBuffer", + "return_type": "void", + "params": [ + { + "name": "dest", + "c_type": "mjByteVec *", + "array_dim": null + }, + { + "name": "array", + "c_type": "const void *", + "array_dim": null + }, + { + "name": "size", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1850 + }, + "mjs_setString": { + "name": "mjs_setString", + "return_type": "void", + "params": [ + { + "name": "dest", + "c_type": "mjString *", + "array_dim": null + }, + { + "name": "text", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1853 + }, + "mjs_setStringVec": { + "name": "mjs_setStringVec", + "return_type": "void", + "params": [ + { + "name": "dest", + "c_type": "mjStringVec *", + "array_dim": null + }, + { + "name": "text", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1856 + }, + "mjs_setInStringVec": { + "name": "mjs_setInStringVec", + "return_type": "mjtByte", + "params": [ + { + "name": "dest", + "c_type": "mjStringVec *", + "array_dim": null + }, + { + "name": "i", + "c_type": "int", + "array_dim": null + }, + { + "name": "text", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1859 + }, + "mjs_appendString": { + "name": "mjs_appendString", + "return_type": "void", + "params": [ + { + "name": "dest", + "c_type": "mjStringVec *", + "array_dim": null + }, + { + "name": "text", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1862 + }, + "mjs_setInt": { + "name": "mjs_setInt", + "return_type": "void", + "params": [ + { + "name": "dest", + "c_type": "mjIntVec *", + "array_dim": null + }, + { + "name": "array", + "c_type": "const int *", + "array_dim": null + }, + { + "name": "size", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1865 + }, + "mjs_appendIntVec": { + "name": "mjs_appendIntVec", + "return_type": "void", + "params": [ + { + "name": "dest", + "c_type": "mjIntVecVec *", + "array_dim": null + }, + { + "name": "array", + "c_type": "const int *", + "array_dim": null + }, + { + "name": "size", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1868 + }, + "mjs_setFloat": { + "name": "mjs_setFloat", + "return_type": "void", + "params": [ + { + "name": "dest", + "c_type": "mjFloatVec *", + "array_dim": null + }, + { + "name": "array", + "c_type": "const float *", + "array_dim": null + }, + { + "name": "size", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1871 + }, + "mjs_appendFloatVec": { + "name": "mjs_appendFloatVec", + "return_type": "void", + "params": [ + { + "name": "dest", + "c_type": "mjFloatVecVec *", + "array_dim": null + }, + { + "name": "array", + "c_type": "const float *", + "array_dim": null + }, + { + "name": "size", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1874 + }, + "mjs_setDouble": { + "name": "mjs_setDouble", + "return_type": "void", + "params": [ + { + "name": "dest", + "c_type": "mjDoubleVec *", + "array_dim": null + }, + { + "name": "array", + "c_type": "const double *", + "array_dim": null + }, + { + "name": "size", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1877 + }, + "mjs_setPluginAttributes": { + "name": "mjs_setPluginAttributes", + "return_type": "void", + "params": [ + { + "name": "plugin", + "c_type": "mjsPlugin *", + "array_dim": null + }, + { + "name": "attributes", + "c_type": "void *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1880 + }, + "mjs_getName": { + "name": "mjs_getName", + "return_type": "mjString *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1886 + }, + "mjs_getString": { + "name": "mjs_getString", + "return_type": "const char *", + "params": [ + { + "name": "source", + "c_type": "const mjString *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1889 + }, + "mjs_getDouble": { + "name": "mjs_getDouble", + "return_type": "const double *", + "params": [ + { + "name": "source", + "c_type": "const mjDoubleVec *", + "array_dim": null + }, + { + "name": "size", + "c_type": "int *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1893 + }, + "mjs_getWrapNum": { + "name": "mjs_getWrapNum", + "return_type": "int", + "params": [ + { + "name": "tendonspec", + "c_type": "const mjsTendon *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1896 + }, + "mjs_getWrap": { + "name": "mjs_getWrap", + "return_type": "mjsWrap *", + "params": [ + { + "name": "tendonspec", + "c_type": "const mjsTendon *", + "array_dim": null + }, + { + "name": "i", + "c_type": "int", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1899 + }, + "mjs_getPluginAttributes": { + "name": "mjs_getPluginAttributes", + "return_type": "const void *", + "params": [ + { + "name": "plugin", + "c_type": "const mjsPlugin *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1902 + }, + "mjs_setDefault": { + "name": "mjs_setDefault", + "return_type": "void", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + }, + { + "name": "def", + "c_type": "const mjsDefault *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1908 + }, + "mjs_setFrame": { + "name": "mjs_setFrame", + "return_type": "int", + "params": [ + { + "name": "dest", + "c_type": "mjsElement *", + "array_dim": null + }, + { + "name": "frame", + "c_type": "mjsFrame *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1911 + }, + "mjs_resolveOrientation": { + "name": "mjs_resolveOrientation", + "return_type": "const char *", + "params": [ + { + "name": "quat", + "c_type": "double [4]", + "array_dim": 4 + }, + { + "name": "degree", + "c_type": "mjtByte", + "array_dim": null + }, + { + "name": "sequence", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "orientation", + "c_type": "const mjsOrientation *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1914 + }, + "mjs_bodyToFrame": { + "name": "mjs_bodyToFrame", + "return_type": "mjsFrame *", + "params": [ + { + "name": "body", + "c_type": "mjsBody **", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1918 + }, + "mjs_setUserValue": { + "name": "mjs_setUserValue", + "return_type": "void", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + }, + { + "name": "key", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "data", + "c_type": "const void *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1921 + }, + "mjs_setUserValueWithCleanup": { + "name": "mjs_setUserValueWithCleanup", + "return_type": "void", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + }, + { + "name": "key", + "c_type": "const char *", + "array_dim": null + }, + { + "name": "data", + "c_type": "const void *", + "array_dim": null + }, + { + "name": "cleanup", + "c_type": "void (*)(const void *)", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1926 + }, + "mjs_getUserValue": { + "name": "mjs_getUserValue", + "return_type": "const void *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + }, + { + "name": "key", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1931 + }, + "mjs_deleteUserValue": { + "name": "mjs_deleteUserValue", + "return_type": "void", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + }, + { + "name": "key", + "c_type": "const char *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1934 + }, + "mjs_sensorDim": { + "name": "mjs_sensorDim", + "return_type": "int", + "params": [ + { + "name": "sensor", + "c_type": "const mjsSensor *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1937 + }, + "mjs_defaultSpec": { + "name": "mjs_defaultSpec", + "return_type": "void", + "params": [ + { + "name": "spec", + "c_type": "mjSpec *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1942 + }, + "mjs_defaultOrientation": { + "name": "mjs_defaultOrientation", + "return_type": "void", + "params": [ + { + "name": "orient", + "c_type": "mjsOrientation *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1945 + }, + "mjs_defaultBody": { + "name": "mjs_defaultBody", + "return_type": "void", + "params": [ + { + "name": "body", + "c_type": "mjsBody *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1948 + }, + "mjs_defaultFrame": { + "name": "mjs_defaultFrame", + "return_type": "void", + "params": [ + { + "name": "frame", + "c_type": "mjsFrame *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1951 + }, + "mjs_defaultJoint": { + "name": "mjs_defaultJoint", + "return_type": "void", + "params": [ + { + "name": "joint", + "c_type": "mjsJoint *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1954 + }, + "mjs_defaultGeom": { + "name": "mjs_defaultGeom", + "return_type": "void", + "params": [ + { + "name": "geom", + "c_type": "mjsGeom *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1957 + }, + "mjs_defaultSite": { + "name": "mjs_defaultSite", + "return_type": "void", + "params": [ + { + "name": "site", + "c_type": "mjsSite *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1960 + }, + "mjs_defaultCamera": { + "name": "mjs_defaultCamera", + "return_type": "void", + "params": [ + { + "name": "camera", + "c_type": "mjsCamera *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1963 + }, + "mjs_defaultLight": { + "name": "mjs_defaultLight", + "return_type": "void", + "params": [ + { + "name": "light", + "c_type": "mjsLight *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1966 + }, + "mjs_defaultFlex": { + "name": "mjs_defaultFlex", + "return_type": "void", + "params": [ + { + "name": "flex", + "c_type": "mjsFlex *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1969 + }, + "mjs_defaultMesh": { + "name": "mjs_defaultMesh", + "return_type": "void", + "params": [ + { + "name": "mesh", + "c_type": "mjsMesh *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1972 + }, + "mjs_defaultHField": { + "name": "mjs_defaultHField", + "return_type": "void", + "params": [ + { + "name": "hfield", + "c_type": "mjsHField *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1975 + }, + "mjs_defaultSkin": { + "name": "mjs_defaultSkin", + "return_type": "void", + "params": [ + { + "name": "skin", + "c_type": "mjsSkin *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1978 + }, + "mjs_defaultTexture": { + "name": "mjs_defaultTexture", + "return_type": "void", + "params": [ + { + "name": "texture", + "c_type": "mjsTexture *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1981 + }, + "mjs_defaultMaterial": { + "name": "mjs_defaultMaterial", + "return_type": "void", + "params": [ + { + "name": "material", + "c_type": "mjsMaterial *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1984 + }, + "mjs_defaultPair": { + "name": "mjs_defaultPair", + "return_type": "void", + "params": [ + { + "name": "pair", + "c_type": "mjsPair *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1987 + }, + "mjs_defaultEquality": { + "name": "mjs_defaultEquality", + "return_type": "void", + "params": [ + { + "name": "equality", + "c_type": "mjsEquality *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1990 + }, + "mjs_defaultTendon": { + "name": "mjs_defaultTendon", + "return_type": "void", + "params": [ + { + "name": "tendon", + "c_type": "mjsTendon *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1993 + }, + "mjs_defaultActuator": { + "name": "mjs_defaultActuator", + "return_type": "void", + "params": [ + { + "name": "actuator", + "c_type": "mjsActuator *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1996 + }, + "mjs_defaultSensor": { + "name": "mjs_defaultSensor", + "return_type": "void", + "params": [ + { + "name": "sensor", + "c_type": "mjsSensor *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1999 + }, + "mjs_defaultNumeric": { + "name": "mjs_defaultNumeric", + "return_type": "void", + "params": [ + { + "name": "numeric", + "c_type": "mjsNumeric *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2002 + }, + "mjs_defaultText": { + "name": "mjs_defaultText", + "return_type": "void", + "params": [ + { + "name": "text", + "c_type": "mjsText *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2005 + }, + "mjs_defaultTuple": { + "name": "mjs_defaultTuple", + "return_type": "void", + "params": [ + { + "name": "tuple", + "c_type": "mjsTuple *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2008 + }, + "mjs_defaultKey": { + "name": "mjs_defaultKey", + "return_type": "void", + "params": [ + { + "name": "key", + "c_type": "mjsKey *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2011 + }, + "mjs_defaultPlugin": { + "name": "mjs_defaultPlugin", + "return_type": "void", + "params": [ + { + "name": "plugin", + "c_type": "mjsPlugin *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2014 + }, + "mjs_asBody": { + "name": "mjs_asBody", + "return_type": "mjsBody *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2020 + }, + "mjs_asGeom": { + "name": "mjs_asGeom", + "return_type": "mjsGeom *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2023 + }, + "mjs_asJoint": { + "name": "mjs_asJoint", + "return_type": "mjsJoint *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2026 + }, + "mjs_asSite": { + "name": "mjs_asSite", + "return_type": "mjsSite *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2029 + }, + "mjs_asCamera": { + "name": "mjs_asCamera", + "return_type": "mjsCamera *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2032 + }, + "mjs_asLight": { + "name": "mjs_asLight", + "return_type": "mjsLight *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2035 + }, + "mjs_asFrame": { + "name": "mjs_asFrame", + "return_type": "mjsFrame *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2038 + }, + "mjs_asActuator": { + "name": "mjs_asActuator", + "return_type": "mjsActuator *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2041 + }, + "mjs_asSensor": { + "name": "mjs_asSensor", + "return_type": "mjsSensor *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2044 + }, + "mjs_asFlex": { + "name": "mjs_asFlex", + "return_type": "mjsFlex *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2047 + }, + "mjs_asPair": { + "name": "mjs_asPair", + "return_type": "mjsPair *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2050 + }, + "mjs_asEquality": { + "name": "mjs_asEquality", + "return_type": "mjsEquality *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2053 + }, + "mjs_asExclude": { + "name": "mjs_asExclude", + "return_type": "mjsExclude *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2056 + }, + "mjs_asTendon": { + "name": "mjs_asTendon", + "return_type": "mjsTendon *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2059 + }, + "mjs_asNumeric": { + "name": "mjs_asNumeric", + "return_type": "mjsNumeric *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2062 + }, + "mjs_asText": { + "name": "mjs_asText", + "return_type": "mjsText *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2065 + }, + "mjs_asTuple": { + "name": "mjs_asTuple", + "return_type": "mjsTuple *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2068 + }, + "mjs_asKey": { + "name": "mjs_asKey", + "return_type": "mjsKey *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2071 + }, + "mjs_asMesh": { + "name": "mjs_asMesh", + "return_type": "mjsMesh *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2074 + }, + "mjs_asHField": { + "name": "mjs_asHField", + "return_type": "mjsHField *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2077 + }, + "mjs_asSkin": { + "name": "mjs_asSkin", + "return_type": "mjsSkin *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2080 + }, + "mjs_asTexture": { + "name": "mjs_asTexture", + "return_type": "mjsTexture *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2083 + }, + "mjs_asMaterial": { + "name": "mjs_asMaterial", + "return_type": "mjsMaterial *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2086 + }, + "mjs_asPlugin": { + "name": "mjs_asPlugin", + "return_type": "mjsPlugin *", + "params": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 2089 + } + }, + "enums": { + "mjtDisableBit": { + "name": "mjtDisableBit", + "members": { + "mjDSBL_CONSTRAINT": 1, + "mjDSBL_EQUALITY": 2, + "mjDSBL_FRICTIONLOSS": 4, + "mjDSBL_LIMIT": 8, + "mjDSBL_CONTACT": 16, + "mjDSBL_SPRING": 32, + "mjDSBL_DAMPER": 64, + "mjDSBL_GRAVITY": 128, + "mjDSBL_CLAMPCTRL": 256, + "mjDSBL_WARMSTART": 512, + "mjDSBL_FILTERPARENT": 1024, + "mjDSBL_ACTUATION": 2048, + "mjDSBL_REFSAFE": 4096, + "mjDSBL_SENSOR": 8192, + "mjDSBL_MIDPHASE": 16384, + "mjDSBL_EULERDAMP": 32768, + "mjDSBL_AUTORESET": 65536, + "mjDSBL_NATIVECCD": 131072, + "mjDSBL_ISLAND": 262144, + "mjDSBL_MULTICCD": 524288, + "mjNDISABLE": 20 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 53 + }, + "mjtEnableBit": { + "name": "mjtEnableBit", + "members": { + "mjENBL_OVERRIDE": 1, + "mjENBL_ENERGY": 2, + "mjENBL_FWDINV": 4, + "mjENBL_INVDISCRETE": 8, + "mjENBL_SLEEP": 16, + "mjNENABLE": 5 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 79 + }, + "mjtJoint": { + "name": "mjtJoint", + "members": { + "mjJNT_FREE": 0, + "mjJNT_BALL": 1, + "mjJNT_SLIDE": 2, + "mjJNT_HINGE": 3 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 91 + }, + "mjtGeom": { + "name": "mjtGeom", + "members": { + "mjGEOM_PLANE": 0, + "mjGEOM_HFIELD": 1, + "mjGEOM_SPHERE": 2, + "mjGEOM_CAPSULE": 3, + "mjGEOM_ELLIPSOID": 4, + "mjGEOM_CYLINDER": 5, + "mjGEOM_BOX": 6, + "mjGEOM_MESH": 7, + "mjGEOM_SDF": 8, + "mjNGEOMTYPES": 9, + "mjGEOM_ARROW": 100, + "mjGEOM_ARROW1": 101, + "mjGEOM_ARROW2": 102, + "mjGEOM_LINE": 103, + "mjGEOM_LINEBOX": 104, + "mjGEOM_FLEX": 105, + "mjGEOM_SKIN": 106, + "mjGEOM_LABEL": 107, + "mjGEOM_TRIANGLE": 108, + "mjGEOM_NONE": 1001 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 99 + }, + "mjtProjection": { + "name": "mjtProjection", + "members": { + "mjPROJ_PERSPECTIVE": 0, + "mjPROJ_ORTHOGRAPHIC": 1 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 128 + }, + "mjtCamLight": { + "name": "mjtCamLight", + "members": { + "mjCAMLIGHT_FIXED": 0, + "mjCAMLIGHT_TRACK": 1, + "mjCAMLIGHT_TRACKCOM": 2, + "mjCAMLIGHT_TARGETBODY": 3, + "mjCAMLIGHT_TARGETBODYCOM": 4 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 134 + }, + "mjtLightType": { + "name": "mjtLightType", + "members": { + "mjLIGHT_SPOT": 0, + "mjLIGHT_DIRECTIONAL": 1, + "mjLIGHT_POINT": 2, + "mjLIGHT_IMAGE": 3 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 143 + }, + "mjtTexture": { + "name": "mjtTexture", + "members": { + "mjTEXTURE_2D": 0, + "mjTEXTURE_CUBE": 1, + "mjTEXTURE_SKYBOX": 2 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 151 + }, + "mjtTextureRole": { + "name": "mjtTextureRole", + "members": { + "mjTEXROLE_USER": 0, + "mjTEXROLE_RGB": 1, + "mjTEXROLE_OCCLUSION": 2, + "mjTEXROLE_ROUGHNESS": 3, + "mjTEXROLE_METALLIC": 4, + "mjTEXROLE_NORMAL": 5, + "mjTEXROLE_OPACITY": 6, + "mjTEXROLE_EMISSIVE": 7, + "mjTEXROLE_RGBA": 8, + "mjTEXROLE_ORM": 9, + "mjNTEXROLE": 10 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 158 + }, + "mjtColorSpace": { + "name": "mjtColorSpace", + "members": { + "mjCOLORSPACE_AUTO": 0, + "mjCOLORSPACE_LINEAR": 1, + "mjCOLORSPACE_SRGB": 2 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 173 + }, + "mjtIntegrator": { + "name": "mjtIntegrator", + "members": { + "mjINT_EULER": 0, + "mjINT_RK4": 1, + "mjINT_IMPLICIT": 2, + "mjINT_IMPLICITFAST": 3 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 180 + }, + "mjtCone": { + "name": "mjtCone", + "members": { + "mjCONE_PYRAMIDAL": 0, + "mjCONE_ELLIPTIC": 1 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 188 + }, + "mjtJacobian": { + "name": "mjtJacobian", + "members": { + "mjJAC_DENSE": 0, + "mjJAC_SPARSE": 1, + "mjJAC_AUTO": 2 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 194 + }, + "mjtSolver": { + "name": "mjtSolver", + "members": { + "mjSOL_PGS": 0, + "mjSOL_CG": 1, + "mjSOL_NEWTON": 2 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 201 + }, + "mjtEq": { + "name": "mjtEq", + "members": { + "mjEQ_CONNECT": 0, + "mjEQ_WELD": 1, + "mjEQ_JOINT": 2, + "mjEQ_TENDON": 3, + "mjEQ_FLEX": 4, + "mjEQ_FLEXVERT": 5, + "mjEQ_FLEXSTRAIN": 6, + "mjEQ_DISTANCE": 7 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 208 + }, + "mjtWrap": { + "name": "mjtWrap", + "members": { + "mjWRAP_NONE": 0, + "mjWRAP_JOINT": 1, + "mjWRAP_PULLEY": 2, + "mjWRAP_SITE": 3, + "mjWRAP_SPHERE": 4, + "mjWRAP_CYLINDER": 5 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 220 + }, + "mjtTrn": { + "name": "mjtTrn", + "members": { + "mjTRN_JOINT": 0, + "mjTRN_JOINTINPARENT": 1, + "mjTRN_SLIDERCRANK": 2, + "mjTRN_TENDON": 3, + "mjTRN_SITE": 4, + "mjTRN_BODY": 5, + "mjTRN_UNDEFINED": 1000 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 230 + }, + "mjtDyn": { + "name": "mjtDyn", + "members": { + "mjDYN_NONE": 0, + "mjDYN_INTEGRATOR": 1, + "mjDYN_FILTER": 2, + "mjDYN_FILTEREXACT": 3, + "mjDYN_MUSCLE": 4, + "mjDYN_DCMOTOR": 5, + "mjDYN_USER": 6 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 242 + }, + "mjtGain": { + "name": "mjtGain", + "members": { + "mjGAIN_FIXED": 0, + "mjGAIN_AFFINE": 1, + "mjGAIN_MUSCLE": 2, + "mjGAIN_DCMOTOR": 3, + "mjGAIN_USER": 4 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 253 + }, + "mjtBias": { + "name": "mjtBias", + "members": { + "mjBIAS_NONE": 0, + "mjBIAS_AFFINE": 1, + "mjBIAS_MUSCLE": 2, + "mjBIAS_DCMOTOR": 3, + "mjBIAS_USER": 4 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 262 + }, + "mjtObj": { + "name": "mjtObj", + "members": { + "mjOBJ_UNKNOWN": 0, + "mjOBJ_BODY": 1, + "mjOBJ_XBODY": 2, + "mjOBJ_JOINT": 3, + "mjOBJ_DOF": 4, + "mjOBJ_GEOM": 5, + "mjOBJ_SITE": 6, + "mjOBJ_CAMERA": 7, + "mjOBJ_LIGHT": 8, + "mjOBJ_FLEX": 9, + "mjOBJ_MESH": 10, + "mjOBJ_SKIN": 11, + "mjOBJ_HFIELD": 12, + "mjOBJ_TEXTURE": 13, + "mjOBJ_MATERIAL": 14, + "mjOBJ_PAIR": 15, + "mjOBJ_EXCLUDE": 16, + "mjOBJ_EQUALITY": 17, + "mjOBJ_TENDON": 18, + "mjOBJ_ACTUATOR": 19, + "mjOBJ_SENSOR": 20, + "mjOBJ_NUMERIC": 21, + "mjOBJ_TEXT": 22, + "mjOBJ_TUPLE": 23, + "mjOBJ_KEY": 24, + "mjOBJ_PLUGIN": 25, + "mjNOBJECT": 26, + "mjOBJ_FRAME": 100, + "mjOBJ_DEFAULT": 101, + "mjOBJ_MODEL": 102 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 271 + }, + "mjtSensor": { + "name": "mjtSensor", + "members": { + "mjSENS_TOUCH": 0, + "mjSENS_ACCELEROMETER": 1, + "mjSENS_VELOCIMETER": 2, + "mjSENS_GYRO": 3, + "mjSENS_FORCE": 4, + "mjSENS_TORQUE": 5, + "mjSENS_MAGNETOMETER": 6, + "mjSENS_RANGEFINDER": 7, + "mjSENS_CAMPROJECTION": 8, + "mjSENS_JOINTPOS": 9, + "mjSENS_JOINTVEL": 10, + "mjSENS_TENDONPOS": 11, + "mjSENS_TENDONVEL": 12, + "mjSENS_ACTUATORPOS": 13, + "mjSENS_ACTUATORVEL": 14, + "mjSENS_ACTUATORFRC": 15, + "mjSENS_JOINTACTFRC": 16, + "mjSENS_TENDONACTFRC": 17, + "mjSENS_BALLQUAT": 18, + "mjSENS_BALLANGVEL": 19, + "mjSENS_JOINTLIMITPOS": 20, + "mjSENS_JOINTLIMITVEL": 21, + "mjSENS_JOINTLIMITFRC": 22, + "mjSENS_TENDONLIMITPOS": 23, + "mjSENS_TENDONLIMITVEL": 24, + "mjSENS_TENDONLIMITFRC": 25, + "mjSENS_FRAMEPOS": 26, + "mjSENS_FRAMEQUAT": 27, + "mjSENS_FRAMEXAXIS": 28, + "mjSENS_FRAMEYAXIS": 29, + "mjSENS_FRAMEZAXIS": 30, + "mjSENS_FRAMELINVEL": 31, + "mjSENS_FRAMEANGVEL": 32, + "mjSENS_FRAMELINACC": 33, + "mjSENS_FRAMEANGACC": 34, + "mjSENS_SUBTREECOM": 35, + "mjSENS_SUBTREELINVEL": 36, + "mjSENS_SUBTREEANGMOM": 37, + "mjSENS_INSIDESITE": 38, + "mjSENS_GEOMDIST": 39, + "mjSENS_GEOMNORMAL": 40, + "mjSENS_GEOMFROMTO": 41, + "mjSENS_CONTACT": 42, + "mjSENS_E_POTENTIAL": 43, + "mjSENS_E_KINETIC": 44, + "mjSENS_CLOCK": 45, + "mjSENS_TACTILE": 46, + "mjSENS_PLUGIN": 47, + "mjSENS_USER": 48 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 308 + }, + "mjtStage": { + "name": "mjtStage", + "members": { + "mjSTAGE_NONE": 0, + "mjSTAGE_POS": 1, + "mjSTAGE_VEL": 2, + "mjSTAGE_ACC": 3 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 384 + }, + "mjtDataType": { + "name": "mjtDataType", + "members": { + "mjDATATYPE_REAL": 0, + "mjDATATYPE_POSITIVE": 1, + "mjDATATYPE_AXIS": 2, + "mjDATATYPE_QUATERNION": 3 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 392 + }, + "mjtConDataField": { + "name": "mjtConDataField", + "members": { + "mjCONDATA_FOUND": 0, + "mjCONDATA_FORCE": 1, + "mjCONDATA_TORQUE": 2, + "mjCONDATA_DIST": 3, + "mjCONDATA_POS": 4, + "mjCONDATA_NORMAL": 5, + "mjCONDATA_TANGENT": 6, + "mjNCONDATA": 7 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 400 + }, + "mjtRayDataField": { + "name": "mjtRayDataField", + "members": { + "mjRAYDATA_DIST": 0, + "mjRAYDATA_DIR": 1, + "mjRAYDATA_ORIGIN": 2, + "mjRAYDATA_POINT": 3, + "mjRAYDATA_NORMAL": 4, + "mjRAYDATA_DEPTH": 5, + "mjNRAYDATA": 6 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 413 + }, + "mjtCamOutBit": { + "name": "mjtCamOutBit", + "members": { + "mjCAMOUT_RGB": 1, + "mjCAMOUT_DEPTH": 2, + "mjCAMOUT_DIST": 4, + "mjCAMOUT_NORMAL": 8, + "mjCAMOUT_SEG": 16, + "mjNCAMOUT": 5 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 425 + }, + "mjtSameFrame": { + "name": "mjtSameFrame", + "members": { + "mjSAMEFRAME_NONE": 0, + "mjSAMEFRAME_BODY": 1, + "mjSAMEFRAME_INERTIA": 2, + "mjSAMEFRAME_BODYROT": 3, + "mjSAMEFRAME_INERTIAROT": 4 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 436 + }, + "mjtSleepPolicy": { + "name": "mjtSleepPolicy", + "members": { + "mjSLEEP_AUTO": 0, + "mjSLEEP_AUTO_NEVER": 1, + "mjSLEEP_AUTO_ALLOWED": 2, + "mjSLEEP_NEVER": 3, + "mjSLEEP_ALLOWED": 4, + "mjSLEEP_INIT": 5 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 445 + }, + "mjtLRMode": { + "name": "mjtLRMode", + "members": { + "mjLRMODE_NONE": 0, + "mjLRMODE_MUSCLE": 1, + "mjLRMODE_MUSCLEUSER": 2, + "mjLRMODE_ALL": 3 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 455 + }, + "mjtFlexSelf": { + "name": "mjtFlexSelf", + "members": { + "mjFLEXSELF_NONE": 0, + "mjFLEXSELF_NARROW": 1, + "mjFLEXSELF_BVH": 2, + "mjFLEXSELF_SAP": 3, + "mjFLEXSELF_AUTO": 4 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 463 + }, + "mjtSDFType": { + "name": "mjtSDFType", + "members": { + "mjSDFTYPE_SINGLE": 0, + "mjSDFTYPE_INTERSECTION": 1, + "mjSDFTYPE_MIDSURFACE": 2, + "mjSDFTYPE_COLLISION": 3 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 472 + }, + "mjtGeomInertia": { + "name": "mjtGeomInertia", + "members": { + "mjINERTIA_VOLUME": 0, + "mjINERTIA_SHELL": 1 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 60 + }, + "mjtMeshInertia": { + "name": "mjtMeshInertia", + "members": { + "mjMESH_INERTIA_CONVEX": 0, + "mjMESH_INERTIA_EXACT": 1, + "mjMESH_INERTIA_LEGACY": 2, + "mjMESH_INERTIA_SHELL": 3 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 66 + }, + "mjtMeshBuiltin": { + "name": "mjtMeshBuiltin", + "members": { + "mjMESH_BUILTIN_NONE": 0, + "mjMESH_BUILTIN_SPHERE": 1, + "mjMESH_BUILTIN_HEMISPHERE": 2, + "mjMESH_BUILTIN_CONE": 3, + "mjMESH_BUILTIN_SUPERSPHERE": 4, + "mjMESH_BUILTIN_SUPERTORUS": 5, + "mjMESH_BUILTIN_WEDGE": 6, + "mjMESH_BUILTIN_PLATE": 7 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 74 + }, + "mjtBuiltin": { + "name": "mjtBuiltin", + "members": { + "mjBUILTIN_NONE": 0, + "mjBUILTIN_GRADIENT": 1, + "mjBUILTIN_CHECKER": 2, + "mjBUILTIN_FLAT": 3 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 86 + }, + "mjtMark": { + "name": "mjtMark", + "members": { + "mjMARK_NONE": 0, + "mjMARK_EDGE": 1, + "mjMARK_CROSS": 2, + "mjMARK_RANDOM": 3 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 94 + }, + "mjtLimited": { + "name": "mjtLimited", + "members": { + "mjLIMITED_FALSE": 0, + "mjLIMITED_TRUE": 1, + "mjLIMITED_AUTO": 2 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 102 + }, + "mjtAlignFree": { + "name": "mjtAlignFree", + "members": { + "mjALIGNFREE_FALSE": 0, + "mjALIGNFREE_TRUE": 1, + "mjALIGNFREE_AUTO": 2 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 109 + }, + "mjtInertiaFromGeom": { + "name": "mjtInertiaFromGeom", + "members": { + "mjINERTIAFROMGEOM_FALSE": 0, + "mjINERTIAFROMGEOM_TRUE": 1, + "mjINERTIAFROMGEOM_AUTO": 2 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 116 + }, + "mjtOrientation": { + "name": "mjtOrientation", + "members": { + "mjORIENTATION_QUAT": 0, + "mjORIENTATION_AXISANGLE": 1, + "mjORIENTATION_XYAXES": 2, + "mjORIENTATION_ZAXIS": 3, + "mjORIENTATION_EULER": 4 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 123 + }, + "mjtTaskStatus": { + "name": "mjtTaskStatus", + "members": { + "mjTASK_NEW": 0, + "mjTASK_QUEUED": 1, + "mjTASK_COMPLETED": 2 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjthread.h", + "line": 20 + }, + "mjtState": { + "name": "mjtState", + "members": { + "mjSTATE_TIME": 1, + "mjSTATE_QPOS": 2, + "mjSTATE_QVEL": 4, + "mjSTATE_ACT": 8, + "mjSTATE_HISTORY": 16, + "mjSTATE_WARMSTART": 32, + "mjSTATE_CTRL": 64, + "mjSTATE_QFRC_APPLIED": 128, + "mjSTATE_XFRC_APPLIED": 256, + "mjSTATE_EQ_ACTIVE": 512, + "mjSTATE_MOCAP_POS": 1024, + "mjSTATE_MOCAP_QUAT": 2048, + "mjSTATE_USERDATA": 4096, + "mjSTATE_PLUGIN": 8192, + "mjNSTATE": 14, + "mjSTATE_PHYSICS": 30, + "mjSTATE_FULLPHYSICS": 8223, + "mjSTATE_USER": 8128, + "mjSTATE_INTEGRATION": 16383 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjdata.h", + "line": 27 + }, + "mjtConstraint": { + "name": "mjtConstraint", + "members": { + "mjCNSTR_EQUALITY": 0, + "mjCNSTR_FRICTION_DOF": 1, + "mjCNSTR_FRICTION_TENDON": 2, + "mjCNSTR_LIMIT_JOINT": 3, + "mjCNSTR_LIMIT_TENDON": 4, + "mjCNSTR_CONTACT_FRICTIONLESS": 5, + "mjCNSTR_CONTACT_PYRAMIDAL": 6, + "mjCNSTR_CONTACT_ELLIPTIC": 7 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjdata.h", + "line": 55 + }, + "mjtConstraintState": { + "name": "mjtConstraintState", + "members": { + "mjCNSTRSTATE_SATISFIED": 0, + "mjCNSTRSTATE_QUADRATIC": 1, + "mjCNSTRSTATE_LINEARNEG": 2, + "mjCNSTRSTATE_LINEARPOS": 3, + "mjCNSTRSTATE_CONE": 4 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjdata.h", + "line": 67 + }, + "mjtWarning": { + "name": "mjtWarning", + "members": { + "mjWARN_INERTIA": 0, + "mjWARN_CONTACTFULL": 1, + "mjWARN_CNSTRFULL": 2, + "mjWARN_BADQPOS": 3, + "mjWARN_BADQVEL": 4, + "mjWARN_BADQACC": 5, + "mjWARN_BADCTRL": 6, + "mjNWARNING": 7 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjdata.h", + "line": 76 + }, + "mjtTimer": { + "name": "mjtTimer", + "members": { + "mjTIMER_STEP": 0, + "mjTIMER_FORWARD": 1, + "mjTIMER_INVERSE": 2, + "mjTIMER_POSITION": 3, + "mjTIMER_VELOCITY": 4, + "mjTIMER_ACTUATION": 5, + "mjTIMER_CONSTRAINT": 6, + "mjTIMER_ADVANCE": 7, + "mjTIMER_POS_KINEMATICS": 8, + "mjTIMER_POS_INERTIA": 9, + "mjTIMER_POS_COLLISION": 10, + "mjTIMER_POS_MAKE": 11, + "mjTIMER_POS_PROJECT": 12, + "mjTIMER_COL_BROAD": 13, + "mjTIMER_COL_NARROW": 14, + "mjNTIMER": 15 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjdata.h", + "line": 89 + }, + "mjtSleepState": { + "name": "mjtSleepState", + "members": { + "mjS_STATIC": -1, + "mjS_ASLEEP": 0, + "mjS_AWAKE": 1 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjdata.h", + "line": 117 + }, + "mjtCatBit": { + "name": "mjtCatBit", + "members": { + "mjCAT_STATIC": 1, + "mjCAT_DYNAMIC": 2, + "mjCAT_DECOR": 4, + "mjCAT_ALL": 7 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 33 + }, + "mjtMouse": { + "name": "mjtMouse", + "members": { + "mjMOUSE_NONE": 0, + "mjMOUSE_ROTATE_V": 1, + "mjMOUSE_ROTATE_H": 2, + "mjMOUSE_MOVE_V": 3, + "mjMOUSE_MOVE_H": 4, + "mjMOUSE_ZOOM": 5, + "mjMOUSE_MOVE_V_REL": 6, + "mjMOUSE_MOVE_H_REL": 7 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 41 + }, + "mjtPertBit": { + "name": "mjtPertBit", + "members": { + "mjPERT_TRANSLATE": 1, + "mjPERT_ROTATE": 2 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 53 + }, + "mjtCamera": { + "name": "mjtCamera", + "members": { + "mjCAMERA_FREE": 0, + "mjCAMERA_TRACKING": 1, + "mjCAMERA_FIXED": 2, + "mjCAMERA_USER": 3 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 59 + }, + "mjtLabel": { + "name": "mjtLabel", + "members": { + "mjLABEL_NONE": 0, + "mjLABEL_BODY": 1, + "mjLABEL_JOINT": 2, + "mjLABEL_GEOM": 3, + "mjLABEL_SITE": 4, + "mjLABEL_CAMERA": 5, + "mjLABEL_LIGHT": 6, + "mjLABEL_TENDON": 7, + "mjLABEL_ACTUATOR": 8, + "mjLABEL_CONSTRAINT": 9, + "mjLABEL_FLEX": 10, + "mjLABEL_SKIN": 11, + "mjLABEL_SELECTION": 12, + "mjLABEL_SELPNT": 13, + "mjLABEL_CONTACTPOINT": 14, + "mjLABEL_CONTACTFORCE": 15, + "mjLABEL_ISLAND": 16, + "mjNLABEL": 17 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 67 + }, + "mjtFrame": { + "name": "mjtFrame", + "members": { + "mjFRAME_NONE": 0, + "mjFRAME_BODY": 1, + "mjFRAME_GEOM": 2, + "mjFRAME_SITE": 3, + "mjFRAME_CAMERA": 4, + "mjFRAME_LIGHT": 5, + "mjFRAME_CONTACT": 6, + "mjFRAME_WORLD": 7, + "mjNFRAME": 8 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 90 + }, + "mjtVisFlag": { + "name": "mjtVisFlag", + "members": { + "mjVIS_CONVEXHULL": 0, + "mjVIS_TEXTURE": 1, + "mjVIS_JOINT": 2, + "mjVIS_CAMERA": 3, + "mjVIS_ACTUATOR": 4, + "mjVIS_ACTIVATION": 5, + "mjVIS_LIGHT": 6, + "mjVIS_TENDON": 7, + "mjVIS_RANGEFINDER": 8, + "mjVIS_CONSTRAINT": 9, + "mjVIS_INERTIA": 10, + "mjVIS_SCLINERTIA": 11, + "mjVIS_PERTFORCE": 12, + "mjVIS_PERTOBJ": 13, + "mjVIS_CONTACTPOINT": 14, + "mjVIS_ISLAND": 15, + "mjVIS_CONTACTFORCE": 16, + "mjVIS_CONTACTSPLIT": 17, + "mjVIS_TRANSPARENT": 18, + "mjVIS_AUTOCONNECT": 19, + "mjVIS_COM": 20, + "mjVIS_SELECT": 21, + "mjVIS_STATIC": 22, + "mjVIS_SKIN": 23, + "mjVIS_FLEXVERT": 24, + "mjVIS_FLEXEDGE": 25, + "mjVIS_FLEXFACE": 26, + "mjVIS_FLEXSKIN": 27, + "mjVIS_BODYBVH": 28, + "mjVIS_MESHBVH": 29, + "mjVIS_SDFITER": 30, + "mjNVISFLAG": 31 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 104 + }, + "mjtRndFlag": { + "name": "mjtRndFlag", + "members": { + "mjRND_SHADOW": 0, + "mjRND_WIREFRAME": 1, + "mjRND_REFLECTION": 2, + "mjRND_ADDITIVE": 3, + "mjRND_SKYBOX": 4, + "mjRND_FOG": 5, + "mjRND_HAZE": 6, + "mjRND_DEPTH": 7, + "mjRND_SEGMENT": 8, + "mjRND_IDCOLOR": 9, + "mjRND_CULL_FACE": 10, + "mjNRNDFLAG": 11 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 141 + }, + "mjtStereo": { + "name": "mjtStereo", + "members": { + "mjSTEREO_NONE": 0, + "mjSTEREO_QUADBUFFERED": 1, + "mjSTEREO_SIDEBYSIDE": 2 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 158 + }, + "mjtPluginCapabilityBit": { + "name": "mjtPluginCapabilityBit", + "members": { + "mjPLUGIN_ACTUATOR": 1, + "mjPLUGIN_SENSOR": 2, + "mjPLUGIN_PASSIVE": 4, + "mjPLUGIN_SDF": 8 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjplugin.h", + "line": 107 + }, + "mjtGridPos": { + "name": "mjtGridPos", + "members": { + "mjGRID_TOPLEFT": 0, + "mjGRID_TOPRIGHT": 1, + "mjGRID_BOTTOMLEFT": 2, + "mjGRID_BOTTOMRIGHT": 3, + "mjGRID_TOP": 4, + "mjGRID_BOTTOM": 5, + "mjGRID_LEFT": 6, + "mjGRID_RIGHT": 7 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjrender.h", + "line": 30 + }, + "mjtFramebuffer": { + "name": "mjtFramebuffer", + "members": { + "mjFB_WINDOW": 0, + "mjFB_OFFSCREEN": 1 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjrender.h", + "line": 42 + }, + "mjtDepthMap": { + "name": "mjtDepthMap", + "members": { + "mjDEPTH_ZERONEAR": 0, + "mjDEPTH_ZEROFAR": 1 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjrender.h", + "line": 47 + }, + "mjtFontScale": { + "name": "mjtFontScale", + "members": { + "mjFONTSCALE_50": 50, + "mjFONTSCALE_100": 100, + "mjFONTSCALE_150": 150, + "mjFONTSCALE_200": 200, + "mjFONTSCALE_250": 250, + "mjFONTSCALE_300": 300 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjrender.h", + "line": 52 + }, + "mjtFont": { + "name": "mjtFont", + "members": { + "mjFONT_NORMAL": 0, + "mjFONT_SHADOW": 1, + "mjFONT_BIG": 2 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjrender.h", + "line": 62 + }, + "mjtButton": { + "name": "mjtButton", + "members": { + "mjBUTTON_NONE": 0, + "mjBUTTON_LEFT": 1, + "mjBUTTON_RIGHT": 2, + "mjBUTTON_MIDDLE": 3 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 65 + }, + "mjtEvent": { + "name": "mjtEvent", + "members": { + "mjEVENT_NONE": 0, + "mjEVENT_MOVE": 1, + "mjEVENT_PRESS": 2, + "mjEVENT_RELEASE": 3, + "mjEVENT_SCROLL": 4, + "mjEVENT_KEY": 5, + "mjEVENT_RESIZE": 6, + "mjEVENT_REDRAW": 7, + "mjEVENT_FILESDROP": 8 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 73 + }, + "mjtItem": { + "name": "mjtItem", + "members": { + "mjITEM_END": -2, + "mjITEM_SECTION": -1, + "mjITEM_SEPARATOR": 0, + "mjITEM_STATIC": 1, + "mjITEM_BUTTON": 2, + "mjITEM_CHECKINT": 3, + "mjITEM_CHECKBYTE": 4, + "mjITEM_RADIO": 5, + "mjITEM_RADIOLINE": 6, + "mjITEM_SELECT": 7, + "mjITEM_SLIDERINT": 8, + "mjITEM_SLIDERNUM": 9, + "mjITEM_EDITINT": 10, + "mjITEM_EDITNUM": 11, + "mjITEM_EDITFLOAT": 12, + "mjITEM_EDITTXT": 13, + "mjNITEM": 14 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 86 + }, + "mjtSection": { + "name": "mjtSection", + "members": { + "mjSECT_CLOSED": 0, + "mjSECT_OPEN": 1, + "mjSECT_FIXED": 2 + }, + "member_docs": {}, + "underlying_type": "int", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 110 + } + }, + "structs": { + "mjLROpt": { + "name": "mjLROpt", + "fields": [ + { + "name": "mode", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "useexisting", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "uselimit", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "accel", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "maxforce", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "timeconst", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "timestep", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "inttotal", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "interval", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "tolrange", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 482 + }, + "mjCache": { + "name": "mjCache", + "fields": [ + { + "name": "impl_", + "c_type": "void *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 501 + }, + "mjVFS": { + "name": "mjVFS", + "fields": [ + { + "name": "impl_", + "c_type": "void *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 508 + }, + "mjOption": { + "name": "mjOption", + "fields": [ + { + "name": "timestep", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "impratio", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "tolerance", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ls_tolerance", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "noslip_tolerance", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ccd_tolerance", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "sleep_tolerance", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "gravity", + "c_type": "mjtNum [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "wind", + "c_type": "mjtNum [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "magnetic", + "c_type": "mjtNum [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "density", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "viscosity", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "o_margin", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "o_solref", + "c_type": "mjtNum [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "o_solimp", + "c_type": "mjtNum [5]", + "array_dim": 5, + "is_pointer": false, + "doc": "" + }, + { + "name": "o_friction", + "c_type": "mjtNum [5]", + "array_dim": 5, + "is_pointer": false, + "doc": "" + }, + { + "name": "integrator", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "cone", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "jacobian", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "solver", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "iterations", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ls_iterations", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "noslip_iterations", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ccd_iterations", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "disableflags", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "enableflags", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "disableactuator", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "sdf_initpoints", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "sdf_iterations", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 515 + }, + "mjVisual": { + "name": "mjVisual", + "fields": [ + { + "name": "global", + "c_type": "struct (anonymous struct at C:\\Users\\jonat\\Documents\\Unreal Projects\\url_proj\\Plugins\\UnrealRoboticsLab\\third_party\\install\\MuJoCo\\include\\mujoco/mjmodel.h:565:3)", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "quality", + "c_type": "struct (anonymous struct at C:\\Users\\jonat\\Documents\\Unreal Projects\\url_proj\\Plugins\\UnrealRoboticsLab\\third_party\\install\\MuJoCo\\include\\mujoco/mjmodel.h:581:3)", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "headlight", + "c_type": "struct (anonymous struct at C:\\Users\\jonat\\Documents\\Unreal Projects\\url_proj\\Plugins\\UnrealRoboticsLab\\third_party\\install\\MuJoCo\\include\\mujoco/mjmodel.h:589:3)", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "map", + "c_type": "struct (anonymous struct at C:\\Users\\jonat\\Documents\\Unreal Projects\\url_proj\\Plugins\\UnrealRoboticsLab\\third_party\\install\\MuJoCo\\include\\mujoco/mjmodel.h:596:3)", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "scale", + "c_type": "struct (anonymous struct at C:\\Users\\jonat\\Documents\\Unreal Projects\\url_proj\\Plugins\\UnrealRoboticsLab\\third_party\\install\\MuJoCo\\include\\mujoco/mjmodel.h:612:3)", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "rgba", + "c_type": "struct (anonymous struct at C:\\Users\\jonat\\Documents\\Unreal Projects\\url_proj\\Plugins\\UnrealRoboticsLab\\third_party\\install\\MuJoCo\\include\\mujoco/mjmodel.h:632:3)", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 564 + }, + "mjStatistic": { + "name": "mjStatistic", + "fields": [ + { + "name": "meaninertia", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "meanmass", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "meansize", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "extent", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "center", + "c_type": "mjtNum [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 665 + }, + "mjModel": { + "name": "mjModel", + "fields": [ + { + "name": "nq", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nv", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nu", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "na", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nbody", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nbvh", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nbvhstatic", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nbvhdynamic", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "noct", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "njnt", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ntree", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nM", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nB", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nC", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nD", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ngeom", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nsite", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ncam", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nlight", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nflex", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nflexnode", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nflexvert", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nflexedge", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nflexelem", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nflexelemdata", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nflexstiffness", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nflexbending", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nflexelemedge", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nflexshelldata", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nflexevpair", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nflextexcoord", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nJfe", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nJfv", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nmesh", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nmeshvert", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nmeshnormal", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nmeshtexcoord", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nmeshface", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nmeshgraph", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nmeshpoly", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nmeshpolyvert", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nmeshpolymap", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nskin", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nskinvert", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nskintexvert", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nskinface", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nskinbone", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nskinbonevert", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nhfield", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nhfielddata", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ntex", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ntexdata", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nmat", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "npair", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nexclude", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "neq", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ntendon", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nJten", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nwrap", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nsensor", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nnumeric", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nnumericdata", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ntext", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ntextdata", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ntuple", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ntupledata", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nkey", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nmocap", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nplugin", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "npluginattr", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nuser_body", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nuser_jnt", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nuser_geom", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nuser_site", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nuser_cam", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nuser_tendon", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nuser_actuator", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nuser_sensor", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nnames", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "npaths", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nnames_map", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nJmom", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ngravcomp", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nemax", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "njmax", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nconmax", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nuserdata", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nsensordata", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "npluginstate", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nhistory", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "narena", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nbuffer", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "opt", + "c_type": "mjOption", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "vis", + "c_type": "mjVisual", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "stat", + "c_type": "mjStatistic", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "buffer", + "c_type": "void *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qpos0", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qpos_spring", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_parentid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_rootid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_weldid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_mocapid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_jntnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_jntadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_dofnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_dofadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_treeid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_geomnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_geomadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_simple", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_sameframe", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_pos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_quat", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_ipos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_iquat", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_mass", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_subtreemass", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_inertia", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_invweight0", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_gravcomp", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_margin", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_user", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_plugin", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_contype", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_conaffinity", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_bvhadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_bvhnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "bvh_depth", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "bvh_child", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "bvh_nodeid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "bvh_aabb", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "oct_depth", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "oct_child", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "oct_aabb", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "oct_coeff", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "jnt_type", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "jnt_qposadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "jnt_dofadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "jnt_bodyid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "jnt_actuatorid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "jnt_group", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "jnt_limited", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "jnt_actfrclimited", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "jnt_actgravcomp", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "jnt_solref", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "jnt_solimp", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "jnt_pos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "jnt_axis", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "jnt_stiffness", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "jnt_stiffnesspoly", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "jnt_range", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "jnt_actfrcrange", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "jnt_margin", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "jnt_user", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "dof_bodyid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "dof_jntid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "dof_parentid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "dof_treeid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "dof_Madr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "dof_simplenum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "dof_solref", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "dof_solimp", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "dof_frictionloss", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "dof_armature", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "dof_damping", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "dof_dampingpoly", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "dof_invweight0", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "dof_M0", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "dof_length", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tree_bodyadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tree_bodynum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tree_dofadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tree_dofnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tree_sleep_policy", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_type", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_contype", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_conaffinity", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_condim", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_bodyid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_dataid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_matid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_group", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_priority", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_plugin", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_sameframe", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_solmix", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_solref", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_solimp", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_size", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_aabb", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_rbound", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_pos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_quat", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_friction", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_margin", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_gap", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_fluid", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_user", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_rgba", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "site_type", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "site_bodyid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "site_matid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "site_group", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "site_sameframe", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "site_size", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "site_pos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "site_quat", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "site_user", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "site_rgba", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cam_mode", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cam_bodyid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cam_targetbodyid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cam_pos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cam_quat", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cam_poscom0", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cam_pos0", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cam_mat0", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cam_projection", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cam_fovy", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cam_ipd", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cam_resolution", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cam_output", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cam_sensorsize", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cam_intrinsic", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cam_user", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_mode", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_bodyid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_targetbodyid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_type", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_texid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_castshadow", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_bulbradius", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_intensity", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_range", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_active", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_pos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_dir", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_poscom0", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_pos0", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_dir0", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_attenuation", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_cutoff", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_exponent", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_ambient", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_diffuse", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_specular", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_contype", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_conaffinity", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_condim", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_priority", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_solmix", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_solref", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_solimp", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_friction", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_margin", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_gap", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_internal", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_selfcollide", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_activelayers", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_passive", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_dim", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_matid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_group", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_interp", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_bandwidth", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_cellnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_nodeadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_nodenum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_vertadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_vertnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_edgeadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_edgenum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_elemadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_elemnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_elemdataadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_stiffnessadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_elemedgeadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_bendingadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_shellnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_shelldataadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_evpairadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_evpairnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_texcoordadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_nodebodyid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_vertbodyid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_vertedgeadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_vertedgenum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_vertedge", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_edge", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_edgeflap", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_elem", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_elemtexcoord", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_elemedge", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_elemlayer", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_shell", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_evpair", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_vert", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_vert0", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_vertmetric", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_node", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_node0", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexedge_length0", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexedge_invweight0", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_radius", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_size", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_stiffness", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_bending", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_damping", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_edgestiffness", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_edgedamping", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_edgeequality", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_rigid", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexedge_rigid", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_centered", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_flatskin", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_bvhadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_bvhnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexedge_J_rownnz", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexedge_J_rowadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexedge_J_colind", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexvert_J_rownnz", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexvert_J_rowadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexvert_J_colind", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_rgba", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex_texcoord", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_vertadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_vertnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_faceadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_facenum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_bvhadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_bvhnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_octadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_octnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_normaladr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_normalnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_texcoordadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_texcoordnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_graphadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_vert", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_normal", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_texcoord", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_face", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_facenormal", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_facetexcoord", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_graph", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_scale", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_pos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_quat", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_pathadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_polynum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_polyadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_polynormal", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_polyvertadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_polyvertnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_polyvert", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_polymapadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_polymapnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh_polymap", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_matid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_group", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_rgba", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_inflate", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_vertadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_vertnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_texcoordadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_faceadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_facenum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_boneadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_bonenum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_vert", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_texcoord", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_face", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_bonevertadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_bonevertnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_bonebindpos", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_bonebindquat", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_bonebodyid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_bonevertid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_bonevertweight", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skin_pathadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "hfield_size", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "hfield_nrow", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "hfield_ncol", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "hfield_adr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "hfield_data", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "hfield_pathadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tex_type", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tex_colorspace", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tex_height", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tex_width", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tex_nchannel", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tex_adr", + "c_type": "mjtSize *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tex_data", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tex_pathadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mat_texid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mat_texuniform", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mat_texrepeat", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mat_emission", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mat_specular", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mat_shininess", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mat_reflectance", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mat_metallic", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mat_roughness", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mat_rgba", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "pair_dim", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "pair_geom1", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "pair_geom2", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "pair_signature", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "pair_solref", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "pair_solreffriction", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "pair_solimp", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "pair_margin", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "pair_gap", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "pair_friction", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "exclude_signature", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "eq_type", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "eq_obj1id", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "eq_obj2id", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "eq_objtype", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "eq_active0", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "eq_solref", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "eq_solimp", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "eq_data", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_adr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_num", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_matid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_actuatorid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_group", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_treenum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_treeid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "ten_J_rownnz", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "ten_J_rowadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "ten_J_colind", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_limited", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_actfrclimited", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_width", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_solref_lim", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_solimp_lim", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_solref_fri", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_solimp_fri", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_range", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_actfrcrange", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_margin", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_stiffness", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_stiffnesspoly", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_damping", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_dampingpoly", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_armature", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_frictionloss", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_lengthspring", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_length0", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_invweight0", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_user", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_rgba", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "wrap_type", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "wrap_objid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "wrap_prm", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_trntype", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_dyntype", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_gaintype", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_biastype", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_trnid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_damping", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_dampingpoly", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_armature", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_actadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_actnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_group", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_history", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_historyadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_delay", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_ctrllimited", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_forcelimited", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_actlimited", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_dynprm", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_gainprm", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_biasprm", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_actearly", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_ctrlrange", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_forcerange", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_actrange", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_gear", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_cranklength", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_acc0", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_length0", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_lengthrange", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_user", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_plugin", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sensor_type", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sensor_datatype", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sensor_needstage", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sensor_objtype", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sensor_objid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sensor_reftype", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sensor_refid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sensor_intprm", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sensor_dim", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sensor_adr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sensor_cutoff", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sensor_noise", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sensor_history", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sensor_historyadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sensor_delay", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sensor_interval", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sensor_user", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sensor_plugin", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "plugin", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "plugin_stateadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "plugin_statenum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "plugin_attr", + "c_type": "char *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "plugin_attradr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "numeric_adr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "numeric_size", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "numeric_data", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "text_adr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "text_size", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "text_data", + "c_type": "char *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tuple_adr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tuple_size", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tuple_objtype", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tuple_objid", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tuple_objprm", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "key_time", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "key_qpos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "key_qvel", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "key_act", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "key_mpos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "key_mquat", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "key_ctrl", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_bodyadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_jntadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_geomadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_siteadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_camadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_lightadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_flexadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_meshadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_skinadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_hfieldadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_texadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_matadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_pairadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_excludeadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_eqadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_tendonadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_actuatoradr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_sensoradr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_numericadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_textadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_tupleadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_keyadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name_pluginadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "names", + "c_type": "char *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "names_map", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "paths", + "c_type": "char *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "B_rownnz", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "B_rowadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "B_colind", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "M_rownnz", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "M_rowadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "M_colind", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mapM2M", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "D_rownnz", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "D_rowadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "D_diag", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "D_colind", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mapM2D", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mapD2M", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "signature", + "c_type": "uint64_t", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 677 + }, + "mjsElement": { + "name": "mjsElement", + "fields": [ + { + "name": "elemtype", + "c_type": "mjtObj", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "signature", + "c_type": "uint64_t", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 134 + }, + "mjsCompiler": { + "name": "mjsCompiler", + "fields": [ + { + "name": "autolimits", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "boundmass", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "boundinertia", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "settotalmass", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "balanceinertia", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "fitaabb", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "degree", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "eulerseq", + "c_type": "char [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "discardvisual", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "usethread", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "fusestatic", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "inertiafromgeom", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "inertiagrouprange", + "c_type": "int [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "saveinertial", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "alignfree", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "LRopt", + "c_type": "mjLROpt", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "meshdir", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "texturedir", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 140 + }, + "mjSpec": { + "name": "mjSpec", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "modelname", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "compiler", + "c_type": "mjsCompiler", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "strippath", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "option", + "c_type": "mjOption", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "visual", + "c_type": "mjVisual", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "stat", + "c_type": "mjStatistic", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "memory", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nemax", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nuserdata", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nuser_body", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nuser_jnt", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nuser_geom", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nuser_site", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nuser_cam", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nuser_tendon", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nuser_actuator", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nuser_sensor", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nkey", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "njmax", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nconmax", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nstack", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "comment", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "modelfiledir", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "hasImplicitPluginElem", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 162 + }, + "mjsOrientation": { + "name": "mjsOrientation", + "fields": [ + { + "name": "type", + "c_type": "mjtOrientation", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "axisangle", + "c_type": "double [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "xyaxes", + "c_type": "double [6]", + "array_dim": 6, + "is_pointer": false, + "doc": "" + }, + { + "name": "zaxis", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "euler", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 201 + }, + "mjsPlugin": { + "name": "mjsPlugin", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "plugin_name", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "active", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 210 + }, + "mjsBody": { + "name": "mjsBody", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "childclass", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "pos", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "quat", + "c_type": "double [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "alt", + "c_type": "mjsOrientation", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "mass", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ipos", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "iquat", + "c_type": "double [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "inertia", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "ialt", + "c_type": "mjsOrientation", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "fullinertia", + "c_type": "double [6]", + "array_dim": 6, + "is_pointer": false, + "doc": "" + }, + { + "name": "mocap", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "gravcomp", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "sleep", + "c_type": "mjtSleepPolicy", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "userdata", + "c_type": "mjDoubleVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "explicitinertial", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "plugin", + "c_type": "mjsPlugin", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 219 + }, + "mjsFrame": { + "name": "mjsFrame", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "childclass", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "pos", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "quat", + "c_type": "double [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "alt", + "c_type": "mjsOrientation", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 247 + }, + "mjsJoint": { + "name": "mjsJoint", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "type", + "c_type": "mjtJoint", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "pos", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "axis", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "ref", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "align", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "stiffness", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "springref", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "springdamper", + "c_type": "double [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "limited", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "range", + "c_type": "double [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "margin", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "solref_limit", + "c_type": "mjtNum [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "solimp_limit", + "c_type": "mjtNum [5]", + "array_dim": 5, + "is_pointer": false, + "doc": "" + }, + { + "name": "actfrclimited", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "actfrcrange", + "c_type": "double [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "armature", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "damping", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "frictionloss", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "solref_friction", + "c_type": "mjtNum [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "solimp_friction", + "c_type": "mjtNum [5]", + "array_dim": 5, + "is_pointer": false, + "doc": "" + }, + { + "name": "group", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "actgravcomp", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "userdata", + "c_type": "mjDoubleVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 257 + }, + "mjsGeom": { + "name": "mjsGeom", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "type", + "c_type": "mjtGeom", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "pos", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "quat", + "c_type": "double [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "alt", + "c_type": "mjsOrientation", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "fromto", + "c_type": "double [6]", + "array_dim": 6, + "is_pointer": false, + "doc": "" + }, + { + "name": "size", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "contype", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "conaffinity", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "condim", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "priority", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "friction", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "solmix", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "solref", + "c_type": "mjtNum [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "solimp", + "c_type": "mjtNum [5]", + "array_dim": 5, + "is_pointer": false, + "doc": "" + }, + { + "name": "margin", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "gap", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "mass", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "density", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "typeinertia", + "c_type": "mjtGeomInertia", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "fluid_ellipsoid", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "fluid_coefs", + "c_type": "mjtNum [5]", + "array_dim": 5, + "is_pointer": false, + "doc": "" + }, + { + "name": "material", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "rgba", + "c_type": "float [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "group", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "hfieldname", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "meshname", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "fitscale", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "userdata", + "c_type": "mjDoubleVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "plugin", + "c_type": "mjsPlugin", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 296 + }, + "mjsSite": { + "name": "mjsSite", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "pos", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "quat", + "c_type": "double [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "alt", + "c_type": "mjsOrientation", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "fromto", + "c_type": "double [6]", + "array_dim": 6, + "is_pointer": false, + "doc": "" + }, + { + "name": "size", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "type", + "c_type": "mjtGeom", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "material", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "group", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "rgba", + "c_type": "float [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "userdata", + "c_type": "mjDoubleVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 343 + }, + "mjsCamera": { + "name": "mjsCamera", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "pos", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "quat", + "c_type": "double [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "alt", + "c_type": "mjsOrientation", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "mode", + "c_type": "mjtCamLight", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "targetbody", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "proj", + "c_type": "mjtProjection", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "resolution", + "c_type": "int [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "output", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "fovy", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ipd", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "intrinsic", + "c_type": "float [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "sensor_size", + "c_type": "float [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "focal_length", + "c_type": "float [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "focal_pixel", + "c_type": "float [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "principal_length", + "c_type": "float [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "principal_pixel", + "c_type": "float [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "userdata", + "c_type": "mjDoubleVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 365 + }, + "mjsLight": { + "name": "mjsLight", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "pos", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "dir", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "mode", + "c_type": "mjtCamLight", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "targetbody", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "active", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "type", + "c_type": "mjtLightType", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "texture", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "castshadow", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "bulbradius", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "intensity", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "range", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "attenuation", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "cutoff", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "exponent", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ambient", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "diffuse", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "specular", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 394 + }, + "mjsFlex": { + "name": "mjsFlex", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "contype", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "conaffinity", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "condim", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "priority", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "friction", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "solmix", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "solref", + "c_type": "mjtNum [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "solimp", + "c_type": "mjtNum [5]", + "array_dim": 5, + "is_pointer": false, + "doc": "" + }, + { + "name": "margin", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "gap", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "dim", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "radius", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "size", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "internal", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "flatskin", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "selfcollide", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "passive", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "activelayers", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "group", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "edgestiffness", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "edgedamping", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "rgba", + "c_type": "float [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "material", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "young", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "poisson", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "damping", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "thickness", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "elastic2d", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "cellcount", + "c_type": "int [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "order", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nodebody", + "c_type": "mjStringVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "vertbody", + "c_type": "mjStringVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "node", + "c_type": "mjDoubleVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "vert", + "c_type": "mjDoubleVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "elem", + "c_type": "mjIntVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "texcoord", + "c_type": "mjFloatVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "elemtexcoord", + "c_type": "mjIntVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 423 + }, + "mjsMesh": { + "name": "mjsMesh", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "content_type", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "file", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "refpos", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "refquat", + "c_type": "double [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "scale", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "inertia", + "c_type": "mjtMeshInertia", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "smoothnormal", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "needsdf", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "maxhullvert", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "uservert", + "c_type": "mjFloatVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "usernormal", + "c_type": "mjFloatVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "usertexcoord", + "c_type": "mjFloatVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "userface", + "c_type": "mjIntVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "userfacenormal", + "c_type": "mjIntVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "userfacetexcoord", + "c_type": "mjIntVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "plugin", + "c_type": "mjsPlugin", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "material", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "octree_maxdepth", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 474 + }, + "mjsHField": { + "name": "mjsHField", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "content_type", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "file", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "size", + "c_type": "double [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "nrow", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ncol", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "userdata", + "c_type": "mjFloatVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 498 + }, + "mjsSkin": { + "name": "mjsSkin", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "file", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "material", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "rgba", + "c_type": "float [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "inflate", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "group", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "vert", + "c_type": "mjFloatVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "texcoord", + "c_type": "mjFloatVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "face", + "c_type": "mjIntVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "bodyname", + "c_type": "mjStringVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "bindpos", + "c_type": "mjFloatVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "bindquat", + "c_type": "mjFloatVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "vertid", + "c_type": "mjIntVecVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "vertweight", + "c_type": "mjFloatVecVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 511 + }, + "mjsTexture": { + "name": "mjsTexture", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "type", + "c_type": "mjtTexture", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "colorspace", + "c_type": "mjtColorSpace", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "builtin", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "mark", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "rgb1", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "rgb2", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "markrgb", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "random", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "height", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "width", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nchannel", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "content_type", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "file", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "gridsize", + "c_type": "int [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "gridlayout", + "c_type": "char [12]", + "array_dim": 12, + "is_pointer": false, + "doc": "" + }, + { + "name": "cubefiles", + "c_type": "mjStringVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "data", + "c_type": "mjByteVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "hflip", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "vflip", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 536 + }, + "mjsMaterial": { + "name": "mjsMaterial", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "textures", + "c_type": "mjStringVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "texuniform", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "texrepeat", + "c_type": "float [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "emission", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "specular", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "shininess", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "reflectance", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "metallic", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "roughness", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "rgba", + "c_type": "float [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 573 + }, + "mjsPair": { + "name": "mjsPair", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geomname1", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geomname2", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "condim", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "solref", + "c_type": "mjtNum [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "solreffriction", + "c_type": "mjtNum [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "solimp", + "c_type": "mjtNum [5]", + "array_dim": 5, + "is_pointer": false, + "doc": "" + }, + { + "name": "margin", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "gap", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "friction", + "c_type": "double [5]", + "array_dim": 5, + "is_pointer": false, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 589 + }, + "mjsExclude": { + "name": "mjsExclude", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "bodyname1", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "bodyname2", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 606 + }, + "mjsEquality": { + "name": "mjsEquality", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "type", + "c_type": "mjtEq", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "data", + "c_type": "double [11]", + "array_dim": 11, + "is_pointer": false, + "doc": "" + }, + { + "name": "active", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "name1", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "name2", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "objtype", + "c_type": "mjtObj", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "solref", + "c_type": "mjtNum [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "solimp", + "c_type": "mjtNum [5]", + "array_dim": 5, + "is_pointer": false, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 614 + }, + "mjsTendon": { + "name": "mjsTendon", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "stiffness", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "springlength", + "c_type": "double [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "damping", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "frictionloss", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "solref_friction", + "c_type": "mjtNum [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "solimp_friction", + "c_type": "mjtNum [5]", + "array_dim": 5, + "is_pointer": false, + "doc": "" + }, + { + "name": "armature", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "limited", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "actfrclimited", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "range", + "c_type": "double [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "actfrcrange", + "c_type": "double [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "margin", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "solref_limit", + "c_type": "mjtNum [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "solimp_limit", + "c_type": "mjtNum [5]", + "array_dim": 5, + "is_pointer": false, + "doc": "" + }, + { + "name": "material", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "width", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "rgba", + "c_type": "float [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "group", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "userdata", + "c_type": "mjDoubleVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 628 + }, + "mjsWrap": { + "name": "mjsWrap", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "type", + "c_type": "mjtWrap", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 661 + }, + "mjsActuator": { + "name": "mjsActuator", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "gaintype", + "c_type": "mjtGain", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "gainprm", + "c_type": "double [10]", + "array_dim": 10, + "is_pointer": false, + "doc": "" + }, + { + "name": "biastype", + "c_type": "mjtBias", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "biasprm", + "c_type": "double [10]", + "array_dim": 10, + "is_pointer": false, + "doc": "" + }, + { + "name": "dyntype", + "c_type": "mjtDyn", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "dynprm", + "c_type": "double [10]", + "array_dim": 10, + "is_pointer": false, + "doc": "" + }, + { + "name": "actdim", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "actearly", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "trntype", + "c_type": "mjtTrn", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "gear", + "c_type": "double [6]", + "array_dim": 6, + "is_pointer": false, + "doc": "" + }, + { + "name": "target", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "refsite", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "slidersite", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cranklength", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "lengthrange", + "c_type": "double [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "inheritrange", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "damping", + "c_type": "double [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "armature", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ctrllimited", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ctrlrange", + "c_type": "double [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "forcelimited", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "forcerange", + "c_type": "double [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "actlimited", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "actrange", + "c_type": "double [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "group", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nsample", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "interp", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "delay", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "userdata", + "c_type": "mjDoubleVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "plugin", + "c_type": "mjsPlugin", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 668 + }, + "mjsSensor": { + "name": "mjsSensor", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "type", + "c_type": "mjtSensor", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "objtype", + "c_type": "mjtObj", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "objname", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "reftype", + "c_type": "mjtObj", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "refname", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "intprm", + "c_type": "int [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "datatype", + "c_type": "mjtDataType", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "needstage", + "c_type": "mjtStage", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "dim", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "cutoff", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "noise", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nsample", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "interp", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "delay", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "interval", + "c_type": "double [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "userdata", + "c_type": "mjDoubleVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "plugin", + "c_type": "mjsPlugin", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 714 + }, + "mjsNumeric": { + "name": "mjsNumeric", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "data", + "c_type": "mjDoubleVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "size", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 747 + }, + "mjsText": { + "name": "mjsText", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "data", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 755 + }, + "mjsTuple": { + "name": "mjsTuple", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "objtype", + "c_type": "mjIntVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "objname", + "c_type": "mjStringVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "objprm", + "c_type": "mjDoubleVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 762 + }, + "mjsKey": { + "name": "mjsKey", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "time", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "qpos", + "c_type": "mjDoubleVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qvel", + "c_type": "mjDoubleVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "act", + "c_type": "mjDoubleVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mpos", + "c_type": "mjDoubleVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mquat", + "c_type": "mjDoubleVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "ctrl", + "c_type": "mjDoubleVec *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "info", + "c_type": "mjString *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 771 + }, + "mjsDefault": { + "name": "mjsDefault", + "fields": [ + { + "name": "element", + "c_type": "mjsElement *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "joint", + "c_type": "mjsJoint *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom", + "c_type": "mjsGeom *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "site", + "c_type": "mjsSite *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "camera", + "c_type": "mjsCamera *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light", + "c_type": "mjsLight *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flex", + "c_type": "mjsFlex *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mesh", + "c_type": "mjsMesh *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "material", + "c_type": "mjsMaterial *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "pair", + "c_type": "mjsPair *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "equality", + "c_type": "mjsEquality *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon", + "c_type": "mjsTendon *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator", + "c_type": "mjsActuator *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjspec.h", + "line": 784 + }, + "mjThreadPool": { + "name": "mjThreadPool", + "fields": [ + { + "name": "nworker", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjthread.h", + "line": 30 + }, + "mjTask": { + "name": "mjTask", + "fields": [ + { + "name": "func", + "c_type": "mjfTask", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "args", + "c_type": "void *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "status", + "c_type": "volatile int", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjthread.h", + "line": 35 + }, + "mjContact": { + "name": "mjContact", + "fields": [ + { + "name": "dist", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "pos", + "c_type": "mjtNum [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "frame", + "c_type": "mjtNum [9]", + "array_dim": 9, + "is_pointer": false, + "doc": "" + }, + { + "name": "includemargin", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "friction", + "c_type": "mjtNum [5]", + "array_dim": 5, + "is_pointer": false, + "doc": "" + }, + { + "name": "solref", + "c_type": "mjtNum [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "solreffriction", + "c_type": "mjtNum [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "solimp", + "c_type": "mjtNum [5]", + "array_dim": 5, + "is_pointer": false, + "doc": "" + }, + { + "name": "mu", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "H", + "c_type": "mjtNum [36]", + "array_dim": 36, + "is_pointer": false, + "doc": "" + }, + { + "name": "dim", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "geom1", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "geom2", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "geom", + "c_type": "int [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "flex", + "c_type": "int [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "elem", + "c_type": "int [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "vert", + "c_type": "int [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "exclude", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "efc_address", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjdata.h", + "line": 126 + }, + "mjWarningStat": { + "name": "mjWarningStat", + "fields": [ + { + "name": "lastinfo", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "number", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjdata.h", + "line": 163 + }, + "mjTimerStat": { + "name": "mjTimerStat", + "fields": [ + { + "name": "duration", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "number", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjdata.h", + "line": 170 + }, + "mjSolverStat": { + "name": "mjSolverStat", + "fields": [ + { + "name": "improvement", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "gradient", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "lineslope", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nactive", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nchange", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "neval", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nupdate", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjdata.h", + "line": 177 + }, + "mjData": { + "name": "mjData", + "fields": [ + { + "name": "narena", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nbuffer", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nplugin", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "pstack", + "c_type": "size_t", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "pbase", + "c_type": "size_t", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "parena", + "c_type": "size_t", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "maxuse_stack", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "maxuse_threadstack", + "c_type": "mjtSize [128]", + "array_dim": 128, + "is_pointer": false, + "doc": "" + }, + { + "name": "maxuse_arena", + "c_type": "mjtSize", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "maxuse_con", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "maxuse_efc", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "solver", + "c_type": "mjSolverStat [4000]", + "array_dim": 4000, + "is_pointer": false, + "doc": "" + }, + { + "name": "solver_niter", + "c_type": "int [20]", + "array_dim": 20, + "is_pointer": false, + "doc": "" + }, + { + "name": "solver_nnz", + "c_type": "int [20]", + "array_dim": 20, + "is_pointer": false, + "doc": "" + }, + { + "name": "solver_fwdinv", + "c_type": "mjtNum [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "warning", + "c_type": "mjWarningStat [7]", + "array_dim": 7, + "is_pointer": false, + "doc": "" + }, + { + "name": "timer", + "c_type": "mjTimerStat [15]", + "array_dim": 15, + "is_pointer": false, + "doc": "" + }, + { + "name": "ncon", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ne", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nf", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nl", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nefc", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nJ", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nA", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nisland", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nidof", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ntree_awake", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nbody_awake", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nparent_awake", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nv_awake", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "flg_energypos", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "flg_energyvel", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "flg_subtreevel", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "flg_rnepost", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "time", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "energy", + "c_type": "mjtNum [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "buffer", + "c_type": "void *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "arena", + "c_type": "void *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qpos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qvel", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "act", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "history", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qacc_warmstart", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "plugin_state", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "ctrl", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qfrc_applied", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "xfrc_applied", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "eq_active", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mocap_pos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "mocap_quat", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qacc", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "act_dot", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "userdata", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sensordata", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tree_asleep", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "plugin", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "plugin_data", + "c_type": "uintptr_t *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "xpos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "xquat", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "xmat", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "xipos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "ximat", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "xanchor", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "xaxis", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_xpos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geom_xmat", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "site_xpos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "site_xmat", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cam_xpos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cam_xmat", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_xpos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "light_xdir", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "subtree_com", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cdof", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cinert", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexvert_xpos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexelem_aabb", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexedge_J", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexedge_length", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexvert_J", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexvert_length", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "bvh_aabb_dyn", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "ten_wrapadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "ten_wrapnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "ten_J", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "ten_length", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "wrap_obj", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "wrap_xpos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_length", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "moment_rownnz", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "moment_rowadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "moment_colind", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_moment", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "crb", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qM", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "M", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qLD", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qLDiagInv", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "bvh_active", + "c_type": "mjtByte *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tree_awake", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_awake", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "body_awake_ind", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "parent_awake_ind", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "dof_awake_ind", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexedge_velocity", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "ten_velocity", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_velocity", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cvel", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cdof_dot", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qfrc_bias", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qfrc_spring", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qfrc_damper", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qfrc_gravcomp", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qfrc_fluid", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qfrc_passive", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "subtree_linvel", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "subtree_angmom", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qH", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qHDiagInv", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qDeriv", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qLU", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_force", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qfrc_actuator", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qfrc_smooth", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qacc_smooth", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qfrc_constraint", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "qfrc_inverse", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cacc", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cfrc_int", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "cfrc_ext", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "contact", + "c_type": "mjContact *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_type", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_id", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_J_rownnz", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_J_rowadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_J_rowsuper", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_J_colind", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_J", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_pos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_margin", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_frictionloss", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_diagApprox", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_KBIP", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_D", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_R", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tendon_efcadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "tree_island", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "island_ntree", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "island_itreeadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "map_itree2tree", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "dof_island", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "island_nv", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "island_idofadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "island_dofadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "map_dof2idof", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "map_idof2dof", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "ifrc_smooth", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iacc_smooth", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iM_rownnz", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iM_rowadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iM_colind", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iM", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iLD", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iLDiagInv", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iacc", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_island", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "island_ne", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "island_nf", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "island_nefc", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "island_iefcadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "map_efc2iefc", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "map_iefc2efc", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iefc_type", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iefc_id", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iefc_J_rownnz", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iefc_J_rowadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iefc_J_rowsuper", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iefc_J_colind", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iefc_J", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iefc_frictionloss", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iefc_D", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iefc_R", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_AR_rownnz", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_AR_rowadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_AR_colind", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_AR", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_vel", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_aref", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_b", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iefc_aref", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iefc_state", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "iefc_force", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_state", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "efc_force", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "ifrc_constraint", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "threadpool", + "c_type": "uintptr_t", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "signature", + "c_type": "uint64_t", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjdata.h", + "line": 191 + }, + "mjvPerturb": { + "name": "mjvPerturb", + "fields": [ + { + "name": "select", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "flexselect", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "skinselect", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "active", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "active2", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "refpos", + "c_type": "mjtNum [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "refquat", + "c_type": "mjtNum [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "refselpos", + "c_type": "mjtNum [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "localpos", + "c_type": "mjtNum [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "localmass", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "scale", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 167 + }, + "mjvCamera": { + "name": "mjvCamera", + "fields": [ + { + "name": "type", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "fixedcamid", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "trackbodyid", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "lookat", + "c_type": "mjtNum [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "distance", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "azimuth", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "elevation", + "c_type": "mjtNum", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "orthographic", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 185 + }, + "mjvGLCamera": { + "name": "mjvGLCamera", + "fields": [ + { + "name": "pos", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "forward", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "up", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "frustum_center", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "frustum_width", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "frustum_bottom", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "frustum_top", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "frustum_near", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "frustum_far", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "orthographic", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 205 + }, + "mjvGeom": { + "name": "mjvGeom", + "fields": [ + { + "name": "type", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "dataid", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "objtype", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "objid", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "category", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "matid", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "texcoord", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "segid", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "size", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "pos", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "mat", + "c_type": "float [9]", + "array_dim": 9, + "is_pointer": false, + "doc": "" + }, + { + "name": "rgba", + "c_type": "float [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "emission", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "specular", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "shininess", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "reflectance", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "label", + "c_type": "char [100]", + "array_dim": 100, + "is_pointer": false, + "doc": "" + }, + { + "name": "camdist", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "modelrbound", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "transparent", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 227 + }, + "mjvLight": { + "name": "mjvLight", + "fields": [ + { + "name": "id", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "pos", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "dir", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "type", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "texid", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "attenuation", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "cutoff", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "exponent", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ambient", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "diffuse", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "specular", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "headlight", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "castshadow", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "bulbradius", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "intensity", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "range", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 262 + }, + "mjvOption": { + "name": "mjvOption", + "fields": [ + { + "name": "label", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "frame", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "geomgroup", + "c_type": "mjtByte [6]", + "array_dim": 6, + "is_pointer": false, + "doc": "" + }, + { + "name": "sitegroup", + "c_type": "mjtByte [6]", + "array_dim": 6, + "is_pointer": false, + "doc": "" + }, + { + "name": "jointgroup", + "c_type": "mjtByte [6]", + "array_dim": 6, + "is_pointer": false, + "doc": "" + }, + { + "name": "tendongroup", + "c_type": "mjtByte [6]", + "array_dim": 6, + "is_pointer": false, + "doc": "" + }, + { + "name": "actuatorgroup", + "c_type": "mjtByte [6]", + "array_dim": 6, + "is_pointer": false, + "doc": "" + }, + { + "name": "flexgroup", + "c_type": "mjtByte [6]", + "array_dim": 6, + "is_pointer": false, + "doc": "" + }, + { + "name": "skingroup", + "c_type": "mjtByte [6]", + "array_dim": 6, + "is_pointer": false, + "doc": "" + }, + { + "name": "flags", + "c_type": "mjtByte [31]", + "array_dim": 31, + "is_pointer": false, + "doc": "" + }, + { + "name": "bvh_depth", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "flex_layer", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 285 + }, + "mjvScene": { + "name": "mjvScene", + "fields": [ + { + "name": "maxgeom", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "ngeom", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "geoms", + "c_type": "mjvGeom *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geomorder", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "nflex", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "flexedgeadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexedgenum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexvertadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexvertnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexfaceadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexfacenum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexfaceused", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexedge", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexvert", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexface", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexnormal", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flextexcoord", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "flexvertopt", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "flexedgeopt", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "flexfaceopt", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "flexskinopt", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nskin", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "skinfacenum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skinvertadr", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skinvertnum", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skinvert", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skinnormal", + "c_type": "float *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "nlight", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "lights", + "c_type": "mjvLight [100]", + "array_dim": 100, + "is_pointer": false, + "doc": "" + }, + { + "name": "camera", + "c_type": "mjvGLCamera [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "enabletransform", + "c_type": "mjtByte", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "translate", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "rotate", + "c_type": "float [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "scale", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "stereo", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "flags", + "c_type": "mjtByte [11]", + "array_dim": 11, + "is_pointer": false, + "doc": "" + }, + { + "name": "framewidth", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "framergb", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "status", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 304 + }, + "mjvFigure": { + "name": "mjvFigure", + "fields": [ + { + "name": "flg_legend", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "flg_ticklabel", + "c_type": "int [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "flg_extend", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "flg_barplot", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "flg_selection", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "flg_symmetric", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "linewidth", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "gridwidth", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "gridsize", + "c_type": "int [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "gridrgb", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "figurergba", + "c_type": "float [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "panergba", + "c_type": "float [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "legendrgba", + "c_type": "float [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "textrgb", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "linergb", + "c_type": "float [100][3]", + "array_dim": 100, + "is_pointer": false, + "doc": "" + }, + { + "name": "range", + "c_type": "float [2][2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "xformat", + "c_type": "char [20]", + "array_dim": 20, + "is_pointer": false, + "doc": "" + }, + { + "name": "yformat", + "c_type": "char [20]", + "array_dim": 20, + "is_pointer": false, + "doc": "" + }, + { + "name": "minwidth", + "c_type": "char [20]", + "array_dim": 20, + "is_pointer": false, + "doc": "" + }, + { + "name": "title", + "c_type": "char [1000]", + "array_dim": 1000, + "is_pointer": false, + "doc": "" + }, + { + "name": "xlabel", + "c_type": "char [100]", + "array_dim": 100, + "is_pointer": false, + "doc": "" + }, + { + "name": "linename", + "c_type": "char [100][100]", + "array_dim": 100, + "is_pointer": false, + "doc": "" + }, + { + "name": "legendoffset", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "subplot", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "highlight", + "c_type": "int [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "highlightid", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "selection", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "linepnt", + "c_type": "int [100]", + "array_dim": 100, + "is_pointer": false, + "doc": "" + }, + { + "name": "linedata", + "c_type": "float [100][2002]", + "array_dim": 100, + "is_pointer": false, + "doc": "" + }, + { + "name": "xaxispixel", + "c_type": "int [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "yaxispixel", + "c_type": "int [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "xaxisdata", + "c_type": "float [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "yaxisdata", + "c_type": "float [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 367 + }, + "mjResource": { + "name": "mjResource", + "fields": [ + { + "name": "name", + "c_type": "char *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "data", + "c_type": "void *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "vfs", + "c_type": "mjVFS *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "timestamp", + "c_type": "char [512]", + "array_dim": 512, + "is_pointer": false, + "doc": "" + }, + { + "name": "provider", + "c_type": "const struct mjpResourceProvider *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjplugin.h", + "line": 27 + }, + "mjpResourceProvider": { + "name": "mjpResourceProvider", + "fields": [ + { + "name": "prefix", + "c_type": "const char *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "open", + "c_type": "mjfOpenResource", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "read", + "c_type": "mjfReadResource", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "close", + "c_type": "mjfCloseResource", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "mount", + "c_type": "mjfMountResource", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "unmount", + "c_type": "mjfUnmountResource", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "modified", + "c_type": "mjfResourceModified", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "data", + "c_type": "void *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjplugin.h", + "line": 60 + }, + "mjpDecoder": { + "name": "mjpDecoder", + "fields": [ + { + "name": "content_type", + "c_type": "const char *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "extension", + "c_type": "const char *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "can_decode", + "c_type": "mjfCanDecode", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "decode", + "c_type": "mjfDecode", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjplugin.h", + "line": 81 + }, + "mjpEncoder": { + "name": "mjpEncoder", + "fields": [ + { + "name": "content_type", + "c_type": "const char *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "extension", + "c_type": "const char *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "encode", + "c_type": "mjfEncode", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "close_resource", + "c_type": "mjfCloseResource", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjplugin.h", + "line": 97 + }, + "mjpPlugin": { + "name": "mjpPlugin", + "fields": [ + { + "name": "name", + "c_type": "const char *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "nattribute", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "attributes", + "c_type": "const char *const *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "capabilityflags", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "needstage", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nstate", + "c_type": "int (*)(const mjModel *, int)", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "nsensordata", + "c_type": "int (*)(const mjModel *, int, int)", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "init", + "c_type": "int (*)(const mjModel *, mjData *, int)", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "destroy", + "c_type": "void (*)(mjData *, int)", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "copy", + "c_type": "void (*)(mjData *, const mjModel *, const mjData *, int)", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "reset", + "c_type": "void (*)(const mjModel *, mjtNum *, void *, int)", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "compute", + "c_type": "void (*)(const mjModel *, mjData *, int, int)", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "advance", + "c_type": "void (*)(const mjModel *, mjData *, int)", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "visualize", + "c_type": "void (*)(const mjModel *, mjData *, const mjvOption *, mjvScene *, int)", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "actuator_act_dot", + "c_type": "void (*)(const mjModel *, mjData *, int)", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sdf_distance", + "c_type": "mjtNum (*)(const mjtNum *, const mjData *, int)", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sdf_gradient", + "c_type": "void (*)(mjtNum *, const mjtNum *, const mjData *, int)", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sdf_staticdistance", + "c_type": "mjtNum (*)(const mjtNum *, const mjtNum *)", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sdf_attribute", + "c_type": "void (*)(mjtNum *, const char **, const char **)", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sdf_aabb", + "c_type": "void (*)(mjtNum *, const mjtNum *)", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjplugin.h", + "line": 114 + }, + "mjSDF": { + "name": "mjSDF", + "fields": [ + { + "name": "plugin", + "c_type": "const mjpPlugin **", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "id", + "c_type": "int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "type", + "c_type": "mjtSDFType", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "relpos", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "relmat", + "c_type": "mjtNum *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "geomtype", + "c_type": "mjtGeom *", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjplugin.h", + "line": 175 + }, + "mjrRect": { + "name": "mjrRect", + "fields": [ + { + "name": "left", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "bottom", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "width", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "height", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjrender.h", + "line": 69 + }, + "mjrContext": { + "name": "mjrContext", + "fields": [ + { + "name": "lineWidth", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "shadowClip", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "shadowScale", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "fogStart", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "fogEnd", + "c_type": "float", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "fogRGBA", + "c_type": "float [4]", + "array_dim": 4, + "is_pointer": false, + "doc": "" + }, + { + "name": "shadowSize", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "offWidth", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "offHeight", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "offSamples", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "fontScale", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "auxWidth", + "c_type": "int [10]", + "array_dim": 10, + "is_pointer": false, + "doc": "" + }, + { + "name": "auxHeight", + "c_type": "int [10]", + "array_dim": 10, + "is_pointer": false, + "doc": "" + }, + { + "name": "auxSamples", + "c_type": "int [10]", + "array_dim": 10, + "is_pointer": false, + "doc": "" + }, + { + "name": "offFBO", + "c_type": "unsigned int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "offFBO_r", + "c_type": "unsigned int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "offColor", + "c_type": "unsigned int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "offColor_r", + "c_type": "unsigned int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "offDepthStencil", + "c_type": "unsigned int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "offDepthStencil_r", + "c_type": "unsigned int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "shadowFBO", + "c_type": "unsigned int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "shadowTex", + "c_type": "unsigned int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "auxFBO", + "c_type": "unsigned int [10]", + "array_dim": 10, + "is_pointer": false, + "doc": "" + }, + { + "name": "auxFBO_r", + "c_type": "unsigned int [10]", + "array_dim": 10, + "is_pointer": false, + "doc": "" + }, + { + "name": "auxColor", + "c_type": "unsigned int [10]", + "array_dim": 10, + "is_pointer": false, + "doc": "" + }, + { + "name": "auxColor_r", + "c_type": "unsigned int [10]", + "array_dim": 10, + "is_pointer": false, + "doc": "" + }, + { + "name": "mat_texid", + "c_type": "int [10000]", + "array_dim": 10000, + "is_pointer": false, + "doc": "" + }, + { + "name": "mat_texuniform", + "c_type": "int [1000]", + "array_dim": 1000, + "is_pointer": false, + "doc": "" + }, + { + "name": "mat_texrepeat", + "c_type": "float [2000]", + "array_dim": 2000, + "is_pointer": false, + "doc": "" + }, + { + "name": "ntexture", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "textureType", + "c_type": "int [1000]", + "array_dim": 1000, + "is_pointer": false, + "doc": "" + }, + { + "name": "texture", + "c_type": "unsigned int [1000]", + "array_dim": 1000, + "is_pointer": false, + "doc": "" + }, + { + "name": "basePlane", + "c_type": "unsigned int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "baseMesh", + "c_type": "unsigned int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "baseHField", + "c_type": "unsigned int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "baseBuiltin", + "c_type": "unsigned int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "baseFontNormal", + "c_type": "unsigned int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "baseFontShadow", + "c_type": "unsigned int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "baseFontBig", + "c_type": "unsigned int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "rangePlane", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "rangeMesh", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "rangeHField", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "rangeBuiltin", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "rangeFont", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nskin", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "skinvertVBO", + "c_type": "unsigned int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skinnormalVBO", + "c_type": "unsigned int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skintexcoordVBO", + "c_type": "unsigned int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "skinfaceVBO", + "c_type": "unsigned int *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "charWidth", + "c_type": "int [127]", + "array_dim": 127, + "is_pointer": false, + "doc": "" + }, + { + "name": "charWidthBig", + "c_type": "int [127]", + "array_dim": 127, + "is_pointer": false, + "doc": "" + }, + { + "name": "charHeight", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "charHeightBig", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "glInitialized", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "windowAvailable", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "windowSamples", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "windowStereo", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "windowDoublebuffer", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "currentBuffer", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "readPixelFormat", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "readDepthMap", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjrender.h", + "line": 80 + }, + "mjuiState": { + "name": "mjuiState", + "fields": [ + { + "name": "nrect", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "rect", + "c_type": "mjrRect [25]", + "array_dim": 25, + "is_pointer": false, + "doc": "" + }, + { + "name": "userdata", + "c_type": "void *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "type", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "left", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "right", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "middle", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "doubleclick", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "button", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "buttontime", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "x", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "y", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "dx", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "dy", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "sx", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "sy", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "control", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "shift", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "alt", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "key", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "keytime", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "mouserect", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "dragrect", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "dragbutton", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "dropcount", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "droppaths", + "c_type": "const char **", + "array_dim": null, + "is_pointer": true, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 123 + }, + "mjuiThemeSpacing": { + "name": "mjuiThemeSpacing", + "fields": [ + { + "name": "total", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "scroll", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "label", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "section", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "cornersect", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "cornersep", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "itemside", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "itemmid", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "itemver", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "texthor", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "textver", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "linescroll", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "samples", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 169 + }, + "mjuiThemeColor": { + "name": "mjuiThemeColor", + "fields": [ + { + "name": "master", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "thumb", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "secttitle", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "secttitle2", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "secttitleuncheck", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "secttitleuncheck2", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "secttitlecheck", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "secttitlecheck2", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "sectfont", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "sectsymbol", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "sectpane", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "separator", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "separator2", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "shortcut", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "fontactive", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "fontinactive", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "decorinactive", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "decorinactive2", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "button", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "check", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "radio", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "select", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "select2", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "slider", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "slider2", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "edit", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "edit2", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + }, + { + "name": "cursor", + "c_type": "float [3]", + "array_dim": 3, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 189 + }, + "mjuiItemSingle": { + "name": "mjuiItemSingle", + "fields": [ + { + "name": "modifier", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "shortcut", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 224 + }, + "mjuiItemMulti": { + "name": "mjuiItemMulti", + "fields": [ + { + "name": "nelem", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "name", + "c_type": "char [35][40]", + "array_dim": 35, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 230 + }, + "mjuiItemSlider": { + "name": "mjuiItemSlider", + "fields": [ + { + "name": "range", + "c_type": "double [2]", + "array_dim": 2, + "is_pointer": false, + "doc": "" + }, + { + "name": "divisions", + "c_type": "double", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 236 + }, + "mjuiItemEdit": { + "name": "mjuiItemEdit", + "fields": [ + { + "name": "nelem", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "range", + "c_type": "double [7][2]", + "array_dim": 7, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 242 + }, + "mjuiItem": { + "name": "mjuiItem", + "fields": [ + { + "name": "type", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "name", + "c_type": "char [40]", + "array_dim": 40, + "is_pointer": false, + "doc": "" + }, + { + "name": "state", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "pdata", + "c_type": "void *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "sectionid", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "itemid", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "userid", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "rect", + "c_type": "mjrRect", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "skip", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 248 + }, + "mjuiSection": { + "name": "mjuiSection", + "fields": [ + { + "name": "name", + "c_type": "char [40]", + "array_dim": 40, + "is_pointer": false, + "doc": "" + }, + { + "name": "state", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "modifier", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "shortcut", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "checkbox", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "nitem", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "item", + "c_type": "mjuiItem [200]", + "array_dim": 200, + "is_pointer": false, + "doc": "" + }, + { + "name": "rtitle", + "c_type": "mjrRect", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "rcontent", + "c_type": "mjrRect", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "lastclick", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 275 + }, + "mjUI": { + "name": "mjUI", + "fields": [ + { + "name": "spacing", + "c_type": "mjuiThemeSpacing", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "color", + "c_type": "mjuiThemeColor", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "predicate", + "c_type": "mjfItemEnable", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "userdata", + "c_type": "void *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "rectid", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "auxid", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "radiocol", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "width", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "height", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "maxheight", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "scroll", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "mousesect", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "mouseitem", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "mousehelp", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "mouseclicks", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "mousesectcheck", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "editsect", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "edititem", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "editcursor", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "editscroll", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "edittext", + "c_type": "char [300]", + "array_dim": 300, + "is_pointer": false, + "doc": "" + }, + { + "name": "editchanged", + "c_type": "mjuiItem *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "nsect", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "sect", + "c_type": "mjuiSection [10]", + "array_dim": 10, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 295 + }, + "mjuiDef": { + "name": "mjuiDef", + "fields": [ + { + "name": "type", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "name", + "c_type": "char [40]", + "array_dim": 40, + "is_pointer": false, + "doc": "" + }, + { + "name": "state", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + }, + { + "name": "pdata", + "c_type": "void *", + "array_dim": null, + "is_pointer": true, + "doc": "" + }, + { + "name": "other", + "c_type": "char [300]", + "array_dim": 300, + "is_pointer": false, + "doc": "" + }, + { + "name": "otherint", + "c_type": "int", + "array_dim": null, + "is_pointer": false, + "doc": "" + } + ], + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 335 + } + }, + "defines": { + "mjMINVAL": { + "value": "1E-15", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjtnum.h", + "line": 26 + }, + "mjPI": { + "value": "3.14159265358979323846", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 25 + }, + "mjMAXVAL": { + "value": "1E+10", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 26 + }, + "mjMINMU": { + "value": "1E-5", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 27 + }, + "mjMINIMP": { + "value": "0.0001", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 28 + }, + "mjMAXIMP": { + "value": "0.9999", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 29 + }, + "mjMAXCONPAIR": { + "value": "50", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 30 + }, + "mjMAXTREEDEPTH": { + "value": "50", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 31 + }, + "mjMAXFLEXNODES": { + "value": "27", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 32 + }, + "mjMINAWAKE": { + "value": "10", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 33 + }, + "mjNEQDATA": { + "value": "11", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 38 + }, + "mjNDYN": { + "value": "10", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 39 + }, + "mjNGAIN": { + "value": "10", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 40 + }, + "mjNBIAS": { + "value": "10", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 41 + }, + "mjNFLUID": { + "value": "12", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 42 + }, + "mjNREF": { + "value": "2", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 43 + }, + "mjNIMP": { + "value": "5", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 44 + }, + "mjNPOLY": { + "value": "2", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 45 + }, + "mjNSENS": { + "value": "3", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 46 + }, + "mjNSOLVER": { + "value": "200", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 47 + }, + "mjNISLAND": { + "value": "20", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmodel.h", + "line": 48 + }, + "MJOPTION_FIELDS": { + "value": "X ( mjtNum , timestep , 1 ) X ( mjtNum , impratio , 1 ) X ( mjtNum , tolerance , 1 ) X ( mjtNum , ls_tolerance , 1 ) X ( mjtNum , noslip_tolerance , 1 ) X ( mjtNum , ccd_tolerance , 1 ) X ( mjtNum , sleep_tolerance , 1 ) XVEC ( mjtNum , gravity , 3 ) XVEC ( mjtNum , wind , 3 ) XVEC ( mjtNum , magnetic , 3 ) X ( mjtNum , density , 1 ) X ( mjtNum , viscosity , 1 ) X ( mjtNum , o_margin , 1 ) XVEC ( mjtNum , o_solref , mjNREF ) XVEC ( mjtNum , o_solimp , mjNIMP ) XVEC ( mjtNum , o_friction , 5 ) X ( int , integrator , 1 ) X ( int , cone , 1 ) X ( int , jacobian , 1 ) X ( int , solver , 1 ) X ( int , iterations , 1 ) X ( int , ls_iterations , 1 ) X ( int , noslip_iterations , 1 ) X ( int , ccd_iterations , 1 ) X ( int , disableflags , 1 ) X ( int , enableflags , 1 ) X ( int , disableactuator , 1 ) X ( int , sdf_initpoints , 1 ) X ( int , sdf_iterations , 1 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 23 + }, + "MJSTATISTIC_FIELDS": { + "value": "X ( meaninertia , 1 ) X ( meanmass , 1 ) X ( meansize , 1 ) X ( extent , 1 ) XVEC ( center , 3 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 58 + }, + "MJVISUAL_GLOBAL_FIELDS": { + "value": "X ( int , cameraid ) X ( int , orthographic ) X ( float , fovy ) X ( float , ipd ) X ( float , azimuth ) X ( float , elevation ) X ( float , linewidth ) X ( float , glow ) X ( float , realtime ) X ( int , offwidth ) X ( int , offheight ) X ( int , ellipsoidinertia ) X ( int , bvactive )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 69 + }, + "MJVISUAL_QUALITY_FIELDS": { + "value": "X ( shadowsize ) X ( offsamples ) X ( numslices ) X ( numstacks ) X ( numquads )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 84 + }, + "MJVISUAL_HEADLIGHT_FIELDS": { + "value": "XVEC ( float , ambient , 3 ) XVEC ( float , diffuse , 3 ) XVEC ( float , specular , 3 ) X ( int , active , 1 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 91 + }, + "MJVISUAL_MAP_FIELDS": { + "value": "X ( stiffness ) X ( stiffnessrot ) X ( force ) X ( torque ) X ( alpha ) X ( fogstart ) X ( fogend ) X ( znear ) X ( zfar ) X ( haze ) X ( shadowclip ) X ( shadowscale ) X ( actuatortendon )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 97 + }, + "MJVISUAL_SCALE_FIELDS": { + "value": "X ( forcewidth ) X ( contactwidth ) X ( contactheight ) X ( connect ) X ( com ) X ( camera ) X ( light ) X ( selectpoint ) X ( jointlength ) X ( jointwidth ) X ( actuatorlength ) X ( actuatorwidth ) X ( framelength ) X ( framewidth ) X ( constraint ) X ( slidercrank ) X ( frustum )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 112 + }, + "MJVISUAL_RGBA_FIELDS": { + "value": "X ( fog ) X ( haze ) X ( force ) X ( inertia ) X ( joint ) X ( actuator ) X ( actuatornegative ) X ( actuatorpositive ) X ( com ) X ( camera ) X ( light ) X ( selectpoint ) X ( connect ) X ( contactpoint ) X ( contactforce ) X ( contactfriction ) X ( contacttorque ) X ( contactgap ) X ( rangefinder ) X ( constraint ) X ( slidercrank ) X ( crankbroken ) X ( frustum ) X ( bv ) X ( bvactive )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 131 + }, + "MJMODEL_SIZES": { + "value": "X ( nq ) X ( nv ) X ( nu ) X ( na ) X ( nbody ) X ( nbvh ) X ( nbvhstatic ) X ( nbvhdynamic ) X ( noct ) X ( njnt ) X ( ntree ) X ( nM ) X ( nB ) X ( nC ) X ( nD ) X ( ngeom ) X ( nsite ) X ( ncam ) X ( nlight ) X ( nflex ) X ( nflexnode ) X ( nflexvert ) X ( nflexedge ) X ( nflexelem ) X ( nflexelemdata ) X ( nflexstiffness ) X ( nflexbending ) X ( nflexelemedge ) X ( nflexshelldata ) X ( nflexevpair ) X ( nflextexcoord ) X ( nJfe ) X ( nJfv ) X ( nmesh ) X ( nmeshvert ) X ( nmeshnormal ) X ( nmeshtexcoord ) X ( nmeshface ) X ( nmeshgraph ) X ( nmeshpoly ) X ( nmeshpolyvert ) X ( nmeshpolymap ) X ( nskin ) X ( nskinvert ) X ( nskintexvert ) X ( nskinface ) X ( nskinbone ) X ( nskinbonevert ) X ( nhfield ) X ( nhfielddata ) X ( ntex ) X ( ntexdata ) X ( nmat ) X ( npair ) X ( nexclude ) X ( neq ) X ( ntendon ) X ( nJten ) X ( nwrap ) X ( nsensor ) X ( nnumeric ) X ( nnumericdata ) X ( ntext ) X ( ntextdata ) X ( ntuple ) X ( ntupledata ) X ( nkey ) X ( nmocap ) X ( nplugin ) X ( npluginattr ) X ( nuser_body ) X ( nuser_jnt ) X ( nuser_geom ) X ( nuser_site ) X ( nuser_cam ) X ( nuser_tendon ) X ( nuser_actuator ) X ( nuser_sensor ) X ( nnames ) X ( npaths ) X ( nnames_map ) X ( nJmom ) X ( ngravcomp ) X ( nemax ) X ( njmax ) X ( nconmax ) X ( nuserdata ) X ( nsensordata ) X ( npluginstate ) X ( nhistory ) X ( narena ) X ( nbuffer )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 162 + }, + "MJMODEL_POINTERS_PREAMBLE": { + "value": "( m ) int nuser_body = m -> nuser_body ; int nuser_jnt = m -> nuser_jnt ; int nuser_geom = m -> nuser_geom ; int nuser_site = m -> nuser_site ; int nuser_cam = m -> nuser_cam ; int nuser_tendon = m -> nuser_tendon ; int nuser_actuator = m -> nuser_actuator ; int nuser_sensor = m -> nuser_sensor ; int nq = m -> nq ; int nv = m -> nv ; int na = m -> na ; int nu = m -> nu ; int nmocap = m -> nmocap ;", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 260 + }, + "MJ_M": { + "value": "( n ) n", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 277 + }, + "MJMODEL_POINTERS_BODY": { + "value": "X ( int , body_parentid , nbody , 1 ) X ( int , body_rootid , nbody , 1 ) X ( int , body_weldid , nbody , 1 ) X ( int , body_mocapid , nbody , 1 ) X ( int , body_jntnum , nbody , 1 ) X ( int , body_jntadr , nbody , 1 ) X ( int , body_dofnum , nbody , 1 ) X ( int , body_dofadr , nbody , 1 ) X ( int , body_treeid , nbody , 1 ) X ( int , body_geomnum , nbody , 1 ) X ( int , body_geomadr , nbody , 1 ) X ( mjtByte , body_simple , nbody , 1 ) X ( mjtByte , body_sameframe , nbody , 1 ) X ( mjtNum , body_pos , nbody , 3 ) X ( mjtNum , body_quat , nbody , 4 ) X ( mjtNum , body_ipos , nbody , 3 ) X ( mjtNum , body_iquat , nbody , 4 ) X ( mjtNum , body_mass , nbody , 1 ) X ( mjtNum , body_subtreemass , nbody , 1 ) X ( mjtNum , body_inertia , nbody , 3 ) X ( mjtNum , body_invweight0 , nbody , 2 ) X ( mjtNum , body_gravcomp , nbody , 1 ) X ( mjtNum , body_margin , nbody , 1 ) X ( mjtNum , body_user , nbody , MJ_M ( nuser_body ) ) X ( int , body_plugin , nbody , 1 ) X ( int , body_contype , nbody , 1 ) X ( int , body_conaffinity , nbody , 1 ) X ( int , body_bvhadr , nbody , 1 ) X ( int , body_bvhnum , nbody , 1 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 283 + }, + "MJMODEL_POINTERS_JOINT": { + "value": "X ( int , jnt_type , njnt , 1 ) X ( int , jnt_qposadr , njnt , 1 ) X ( int , jnt_dofadr , njnt , 1 ) X ( int , jnt_bodyid , njnt , 1 ) X ( int , jnt_actuatorid , njnt , 1 ) X ( int , jnt_group , njnt , 1 ) X ( mjtByte , jnt_limited , njnt , 1 ) X ( mjtByte , jnt_actfrclimited , njnt , 1 ) X ( mjtByte , jnt_actgravcomp , njnt , 1 ) X ( mjtNum , jnt_solref , njnt , mjNREF ) X ( mjtNum , jnt_solimp , njnt , mjNIMP ) X ( mjtNum , jnt_pos , njnt , 3 ) X ( mjtNum , jnt_axis , njnt , 3 ) X ( mjtNum , jnt_stiffness , njnt , 1 ) X ( mjtNum , jnt_stiffnesspoly , njnt , mjNPOLY ) X ( mjtNum , jnt_range , njnt , 2 ) X ( mjtNum , jnt_actfrcrange , njnt , 2 ) X ( mjtNum , jnt_margin , njnt , 1 ) X ( mjtNum , jnt_user , njnt , MJ_M ( nuser_jnt ) )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 314 + }, + "MJMODEL_POINTERS_DOF": { + "value": "X ( int , dof_bodyid , nv , 1 ) X ( int , dof_jntid , nv , 1 ) X ( int , dof_parentid , nv , 1 ) X ( int , dof_treeid , nv , 1 ) X ( int , dof_Madr , nv , 1 ) X ( int , dof_simplenum , nv , 1 ) X ( mjtNum , dof_solref , nv , mjNREF ) X ( mjtNum , dof_solimp , nv , mjNIMP ) X ( mjtNum , dof_frictionloss , nv , 1 ) X ( mjtNum , dof_armature , nv , 1 ) X ( mjtNum , dof_damping , nv , 1 ) X ( mjtNum , dof_dampingpoly , nv , mjNPOLY ) X ( mjtNum , dof_invweight0 , nv , 1 ) X ( mjtNum , dof_M0 , nv , 1 ) X ( mjtNum , dof_length , nv , 1 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 335 + }, + "MJMODEL_POINTERS_TREE": { + "value": "X ( int , tree_bodyadr , ntree , 1 ) X ( int , tree_bodynum , ntree , 1 ) X ( int , tree_dofadr , ntree , 1 ) X ( int , tree_dofnum , ntree , 1 ) X ( int , tree_sleep_policy , ntree , 1 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 352 + }, + "MJMODEL_POINTERS_GEOM": { + "value": "X ( int , geom_type , ngeom , 1 ) X ( int , geom_contype , ngeom , 1 ) X ( int , geom_conaffinity , ngeom , 1 ) X ( int , geom_condim , ngeom , 1 ) X ( int , geom_bodyid , ngeom , 1 ) X ( int , geom_dataid , ngeom , 1 ) X ( int , geom_matid , ngeom , 1 ) X ( int , geom_group , ngeom , 1 ) X ( int , geom_priority , ngeom , 1 ) X ( int , geom_plugin , ngeom , 1 ) X ( mjtByte , geom_sameframe , ngeom , 1 ) X ( mjtNum , geom_solmix , ngeom , 1 ) X ( mjtNum , geom_solref , ngeom , mjNREF ) X ( mjtNum , geom_solimp , ngeom , mjNIMP ) X ( mjtNum , geom_size , ngeom , 3 ) X ( mjtNum , geom_aabb , ngeom , 6 ) X ( mjtNum , geom_rbound , ngeom , 1 ) X ( mjtNum , geom_pos , ngeom , 3 ) X ( mjtNum , geom_quat , ngeom , 4 ) X ( mjtNum , geom_friction , ngeom , 3 ) X ( mjtNum , geom_margin , ngeom , 1 ) X ( mjtNum , geom_gap , ngeom , 1 ) XNV ( mjtNum , geom_fluid , ngeom , mjNFLUID ) X ( mjtNum , geom_user , ngeom , MJ_M ( nuser_geom ) ) X ( float , geom_rgba , ngeom , 4 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 359 + }, + "MJMODEL_POINTERS_SITE": { + "value": "X ( int , site_type , nsite , 1 ) X ( int , site_bodyid , nsite , 1 ) X ( int , site_matid , nsite , 1 ) X ( int , site_group , nsite , 1 ) X ( mjtByte , site_sameframe , nsite , 1 ) X ( mjtNum , site_size , nsite , 3 ) X ( mjtNum , site_pos , nsite , 3 ) X ( mjtNum , site_quat , nsite , 4 ) X ( mjtNum , site_user , nsite , MJ_M ( nuser_site ) ) X ( float , site_rgba , nsite , 4 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 386 + }, + "MJMODEL_POINTERS_CAMERA": { + "value": "X ( int , cam_mode , ncam , 1 ) X ( int , cam_bodyid , ncam , 1 ) X ( int , cam_targetbodyid , ncam , 1 ) X ( mjtNum , cam_pos , ncam , 3 ) X ( mjtNum , cam_quat , ncam , 4 ) X ( mjtNum , cam_poscom0 , ncam , 3 ) X ( mjtNum , cam_pos0 , ncam , 3 ) X ( mjtNum , cam_mat0 , ncam , 9 ) X ( int , cam_projection , ncam , 1 ) X ( mjtNum , cam_fovy , ncam , 1 ) X ( mjtNum , cam_ipd , ncam , 1 ) X ( int , cam_resolution , ncam , 2 ) X ( int , cam_output , ncam , 1 ) X ( float , cam_sensorsize , ncam , 2 ) X ( float , cam_intrinsic , ncam , 4 ) X ( mjtNum , cam_user , ncam , MJ_M ( nuser_cam ) )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 398 + }, + "MJMODEL_POINTERS_LIGHT": { + "value": "X ( int , light_mode , nlight , 1 ) X ( int , light_bodyid , nlight , 1 ) X ( int , light_targetbodyid , nlight , 1 ) X ( int , light_type , nlight , 1 ) X ( int , light_texid , nlight , 1 ) X ( mjtByte , light_castshadow , nlight , 1 ) X ( float , light_bulbradius , nlight , 1 ) X ( float , light_intensity , nlight , 1 ) X ( float , light_range , nlight , 1 ) X ( mjtByte , light_active , nlight , 1 ) X ( mjtNum , light_pos , nlight , 3 ) X ( mjtNum , light_dir , nlight , 3 ) X ( mjtNum , light_poscom0 , nlight , 3 ) X ( mjtNum , light_pos0 , nlight , 3 ) X ( mjtNum , light_dir0 , nlight , 3 ) X ( float , light_attenuation , nlight , 3 ) X ( float , light_cutoff , nlight , 1 ) X ( float , light_exponent , nlight , 1 ) X ( float , light_ambient , nlight , 3 ) X ( float , light_diffuse , nlight , 3 ) X ( float , light_specular , nlight , 3 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 416 + }, + "MJMODEL_POINTERS_FLEX": { + "value": "X ( int , flex_contype , nflex , 1 ) X ( int , flex_conaffinity , nflex , 1 ) X ( int , flex_condim , nflex , 1 ) X ( int , flex_priority , nflex , 1 ) X ( mjtNum , flex_solmix , nflex , 1 ) X ( mjtNum , flex_solref , nflex , mjNREF ) X ( mjtNum , flex_solimp , nflex , mjNIMP ) X ( mjtNum , flex_friction , nflex , 3 ) X ( mjtNum , flex_margin , nflex , 1 ) X ( mjtNum , flex_gap , nflex , 1 ) X ( mjtByte , flex_internal , nflex , 1 ) X ( int , flex_selfcollide , nflex , 1 ) X ( int , flex_activelayers , nflex , 1 ) X ( int , flex_passive , nflex , 1 ) X ( int , flex_dim , nflex , 1 ) X ( int , flex_matid , nflex , 1 ) X ( int , flex_group , nflex , 1 ) X ( int , flex_interp , nflex , 1 ) X ( int , flex_bandwidth , nflex , 1 ) X ( int , flex_cellnum , nflex , 3 ) X ( int , flex_nodeadr , nflex , 1 ) X ( int , flex_nodenum , nflex , 1 ) X ( int , flex_vertadr , nflex , 1 ) X ( int , flex_vertnum , nflex , 1 ) X ( int , flex_edgeadr , nflex , 1 ) X ( int , flex_edgenum , nflex , 1 ) X ( int , flex_elemadr , nflex , 1 ) X ( int , flex_elemnum , nflex , 1 ) X ( int , flex_elemdataadr , nflex , 1 ) X ( int , flex_stiffnessadr , nflex , 1 ) X ( int , flex_elemedgeadr , nflex , 1 ) X ( int , flex_bendingadr , nflex , 1 ) X ( int , flex_shellnum , nflex , 1 ) X ( int , flex_shelldataadr , nflex , 1 ) X ( int , flex_evpairadr , nflex , 1 ) X ( int , flex_evpairnum , nflex , 1 ) X ( int , flex_texcoordadr , nflex , 1 ) X ( int , flex_nodebodyid , nflexnode , 1 ) X ( int , flex_vertbodyid , nflexvert , 1 ) X ( int , flex_vertedgeadr , nflexvert , 1 ) X ( int , flex_vertedgenum , nflexvert , 1 ) X ( int , flex_vertedge , nflexedge , 2 ) X ( int , flex_edge , nflexedge , 2 ) X ( int , flex_edgeflap , nflexedge , 2 ) X ( int , flex_elem , nflexelemdata , 1 ) X ( int , flex_elemtexcoord , nflexelemdata , 1 ) X ( int , flex_elemedge , nflexelemedge , 1 ) X ( int , flex_elemlayer , nflexelem , 1 ) X ( int , flex_shell , nflexshelldata , 1 ) X ( int , flex_evpair , nflexevpair , 2 ) X ( mjtNum , flex_vert , nflexvert , 3 ) X ( mjtNum , flex_vert0 , nflexvert , 3 ) X ( mjtNum , flex_vertmetric , nflexvert , 4 ) X ( mjtNum , flex_node , nflexnode , 3 ) X ( mjtNum , flex_node0 , nflexnode , 3 ) X ( mjtNum , flexedge_length0 , nflexedge , 1 ) X ( mjtNum , flexedge_invweight0 , nflexedge , 1 ) X ( mjtNum , flex_radius , nflex , 1 ) X ( mjtNum , flex_size , nflex , 3 ) X ( mjtNum , flex_stiffness , nflexstiffness , 1 ) X ( mjtNum , flex_bending , nflexbending , 1 ) X ( mjtNum , flex_damping , nflex , 1 ) X ( mjtNum , flex_edgestiffness , nflex , 1 ) X ( mjtNum , flex_edgedamping , nflex , 1 ) X ( int , flex_edgeequality , nflex , 1 ) X ( mjtByte , flex_rigid , nflex , 1 ) X ( mjtByte , flexedge_rigid , nflexedge , 1 ) X ( mjtByte , flex_centered , nflex , 1 ) X ( mjtByte , flex_flatskin , nflex , 1 ) X ( int , flex_bvhadr , nflex , 1 ) X ( int , flex_bvhnum , nflex , 1 ) X ( int , flexedge_J_rownnz , nflexedge , 1 ) X ( int , flexedge_J_rowadr , nflexedge , 1 ) X ( int , flexedge_J_colind , nJfe , 1 ) X ( int , flexvert_J_rownnz , nflexvert , 2 ) X ( int , flexvert_J_rowadr , nflexvert , 2 ) X ( int , flexvert_J_colind , nJfv , 2 ) X ( float , flex_rgba , nflex , 4 ) X ( float , flex_texcoord , nflextexcoord , 2 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 439 + }, + "MJMODEL_POINTERS_MESH": { + "value": "X ( int , mesh_vertadr , nmesh , 1 ) X ( int , mesh_vertnum , nmesh , 1 ) X ( int , mesh_faceadr , nmesh , 1 ) X ( int , mesh_facenum , nmesh , 1 ) X ( int , mesh_bvhadr , nmesh , 1 ) X ( int , mesh_bvhnum , nmesh , 1 ) X ( int , mesh_octadr , nmesh , 1 ) X ( int , mesh_octnum , nmesh , 1 ) X ( int , mesh_normaladr , nmesh , 1 ) X ( int , mesh_normalnum , nmesh , 1 ) X ( int , mesh_texcoordadr , nmesh , 1 ) X ( int , mesh_texcoordnum , nmesh , 1 ) X ( int , mesh_graphadr , nmesh , 1 ) XNV ( float , mesh_vert , nmeshvert , 3 ) XNV ( float , mesh_normal , nmeshnormal , 3 ) XNV ( float , mesh_texcoord , nmeshtexcoord , 2 ) XNV ( int , mesh_face , nmeshface , 3 ) XNV ( int , mesh_facenormal , nmeshface , 3 ) XNV ( int , mesh_facetexcoord , nmeshface , 3 ) XNV ( int , mesh_graph , nmeshgraph , 1 ) X ( mjtNum , mesh_scale , nmesh , 3 ) X ( mjtNum , mesh_pos , nmesh , 3 ) X ( mjtNum , mesh_quat , nmesh , 4 ) X ( int , mesh_pathadr , nmesh , 1 ) XNV ( int , mesh_polynum , nmesh , 1 ) XNV ( int , mesh_polyadr , nmesh , 1 ) XNV ( mjtNum , mesh_polynormal , nmeshpoly , 3 ) XNV ( int , mesh_polyvertadr , nmeshpoly , 1 ) XNV ( int , mesh_polyvertnum , nmeshpoly , 1 ) XNV ( int , mesh_polyvert , nmeshpolyvert , 1 ) XNV ( int , mesh_polymapadr , nmeshvert , 1 ) XNV ( int , mesh_polymapnum , nmeshvert , 1 ) XNV ( int , mesh_polymap , nmeshpolymap , 1 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 520 + }, + "MJMODEL_POINTERS_SKIN": { + "value": "X ( int , skin_matid , nskin , 1 ) X ( int , skin_group , nskin , 1 ) X ( float , skin_rgba , nskin , 4 ) X ( float , skin_inflate , nskin , 1 ) X ( int , skin_vertadr , nskin , 1 ) X ( int , skin_vertnum , nskin , 1 ) X ( int , skin_texcoordadr , nskin , 1 ) X ( int , skin_faceadr , nskin , 1 ) X ( int , skin_facenum , nskin , 1 ) X ( int , skin_boneadr , nskin , 1 ) X ( int , skin_bonenum , nskin , 1 ) X ( float , skin_vert , nskinvert , 3 ) X ( float , skin_texcoord , nskintexvert , 2 ) X ( int , skin_face , nskinface , 3 ) X ( int , skin_bonevertadr , nskinbone , 1 ) X ( int , skin_bonevertnum , nskinbone , 1 ) X ( float , skin_bonebindpos , nskinbone , 3 ) X ( float , skin_bonebindquat , nskinbone , 4 ) X ( int , skin_bonebodyid , nskinbone , 1 ) X ( int , skin_bonevertid , nskinbonevert , 1 ) X ( float , skin_bonevertweight , nskinbonevert , 1 ) X ( int , skin_pathadr , nskin , 1 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 555 + }, + "MJMODEL_POINTERS_HFIELD": { + "value": "X ( mjtNum , hfield_size , nhfield , 4 ) X ( int , hfield_nrow , nhfield , 1 ) X ( int , hfield_ncol , nhfield , 1 ) X ( int , hfield_adr , nhfield , 1 ) XNV ( float , hfield_data , nhfielddata , 1 ) X ( int , hfield_pathadr , nhfield , 1 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 579 + }, + "MJMODEL_POINTERS_TEXTURE": { + "value": "X ( int , tex_type , ntex , 1 ) X ( int , tex_colorspace , ntex , 1 ) X ( int , tex_height , ntex , 1 ) X ( int , tex_width , ntex , 1 ) X ( int , tex_nchannel , ntex , 1 ) X ( mjtSize , tex_adr , ntex , 1 ) XNV ( mjtByte , tex_data , ntexdata , 1 ) X ( int , tex_pathadr , ntex , 1 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 587 + }, + "MJMODEL_POINTERS_MATERIAL": { + "value": "X ( int , mat_texid , nmat , mjNTEXROLE ) X ( mjtByte , mat_texuniform , nmat , 1 ) X ( float , mat_texrepeat , nmat , 2 ) X ( float , mat_emission , nmat , 1 ) X ( float , mat_specular , nmat , 1 ) X ( float , mat_shininess , nmat , 1 ) X ( float , mat_reflectance , nmat , 1 ) X ( float , mat_metallic , nmat , 1 ) X ( float , mat_roughness , nmat , 1 ) X ( float , mat_rgba , nmat , 4 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 597 + }, + "MJMODEL_POINTERS_PAIR": { + "value": "X ( int , pair_dim , npair , 1 ) X ( int , pair_geom1 , npair , 1 ) X ( int , pair_geom2 , npair , 1 ) X ( int , pair_signature , npair , 1 ) X ( mjtNum , pair_solref , npair , mjNREF ) X ( mjtNum , pair_solreffriction , npair , mjNREF ) X ( mjtNum , pair_solimp , npair , mjNIMP ) X ( mjtNum , pair_margin , npair , 1 ) X ( mjtNum , pair_gap , npair , 1 ) X ( mjtNum , pair_friction , npair , 5 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 609 + }, + "MJMODEL_POINTERS_EXCLUDE": { + "value": "X ( int , exclude_signature , nexclude , 1 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 621 + }, + "MJMODEL_POINTERS_EQUALITY": { + "value": "X ( int , eq_type , neq , 1 ) X ( int , eq_obj1id , neq , 1 ) X ( int , eq_obj2id , neq , 1 ) X ( int , eq_objtype , neq , 1 ) X ( mjtByte , eq_active0 , neq , 1 ) X ( mjtNum , eq_solref , neq , mjNREF ) X ( mjtNum , eq_solimp , neq , mjNIMP ) X ( mjtNum , eq_data , neq , mjNEQDATA )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 624 + }, + "MJMODEL_POINTERS_TENDON": { + "value": "X ( int , tendon_adr , ntendon , 1 ) X ( int , tendon_num , ntendon , 1 ) X ( int , tendon_matid , ntendon , 1 ) X ( int , tendon_actuatorid , ntendon , 1 ) X ( int , tendon_group , ntendon , 1 ) X ( int , tendon_treenum , ntendon , 1 ) X ( int , tendon_treeid , ntendon , 2 ) X ( int , ten_J_rownnz , ntendon , 1 ) X ( int , ten_J_rowadr , ntendon , 1 ) X ( int , ten_J_colind , nJten , 1 ) X ( mjtByte , tendon_limited , ntendon , 1 ) X ( mjtByte , tendon_actfrclimited , ntendon , 1 ) X ( mjtNum , tendon_width , ntendon , 1 ) X ( mjtNum , tendon_solref_lim , ntendon , mjNREF ) X ( mjtNum , tendon_solimp_lim , ntendon , mjNIMP ) X ( mjtNum , tendon_solref_fri , ntendon , mjNREF ) X ( mjtNum , tendon_solimp_fri , ntendon , mjNIMP ) X ( mjtNum , tendon_range , ntendon , 2 ) X ( mjtNum , tendon_actfrcrange , ntendon , 2 ) X ( mjtNum , tendon_margin , ntendon , 1 ) X ( mjtNum , tendon_stiffness , ntendon , 1 ) X ( mjtNum , tendon_stiffnesspoly , ntendon , mjNPOLY ) X ( mjtNum , tendon_damping , ntendon , 1 ) X ( mjtNum , tendon_dampingpoly , ntendon , mjNPOLY ) X ( mjtNum , tendon_armature , ntendon , 1 ) X ( mjtNum , tendon_frictionloss , ntendon , 1 ) X ( mjtNum , tendon_lengthspring , ntendon , 2 ) X ( mjtNum , tendon_length0 , ntendon , 1 ) X ( mjtNum , tendon_invweight0 , ntendon , 1 ) X ( mjtNum , tendon_user , ntendon , MJ_M ( nuser_tendon ) ) X ( float , tendon_rgba , ntendon , 4 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 634 + }, + "MJMODEL_POINTERS_ACTUATOR": { + "value": "X ( int , actuator_trntype , nu , 1 ) X ( int , actuator_dyntype , nu , 1 ) X ( int , actuator_gaintype , nu , 1 ) X ( int , actuator_biastype , nu , 1 ) X ( int , actuator_trnid , nu , 2 ) X ( mjtNum , actuator_damping , nu , 1 ) X ( mjtNum , actuator_dampingpoly , nu , mjNPOLY ) X ( mjtNum , actuator_armature , nu , 1 ) X ( int , actuator_actadr , nu , 1 ) X ( int , actuator_actnum , nu , 1 ) X ( int , actuator_group , nu , 1 ) X ( int , actuator_history , nu , 2 ) X ( int , actuator_historyadr , nu , 1 ) X ( mjtNum , actuator_delay , nu , 1 ) X ( mjtByte , actuator_ctrllimited , nu , 1 ) X ( mjtByte , actuator_forcelimited , nu , 1 ) X ( mjtByte , actuator_actlimited , nu , 1 ) X ( mjtNum , actuator_dynprm , nu , mjNDYN ) X ( mjtNum , actuator_gainprm , nu , mjNGAIN ) X ( mjtNum , actuator_biasprm , nu , mjNBIAS ) X ( mjtByte , actuator_actearly , nu , 1 ) X ( mjtNum , actuator_ctrlrange , nu , 2 ) X ( mjtNum , actuator_forcerange , nu , 2 ) X ( mjtNum , actuator_actrange , nu , 2 ) X ( mjtNum , actuator_gear , nu , 6 ) X ( mjtNum , actuator_cranklength , nu , 1 ) X ( mjtNum , actuator_acc0 , nu , 1 ) X ( mjtNum , actuator_length0 , nu , 1 ) X ( mjtNum , actuator_lengthrange , nu , 2 ) X ( mjtNum , actuator_user , nu , MJ_M ( nuser_actuator ) ) X ( int , actuator_plugin , nu , 1 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 667 + }, + "MJMODEL_POINTERS_SENSOR": { + "value": "X ( int , sensor_type , nsensor , 1 ) X ( int , sensor_datatype , nsensor , 1 ) X ( int , sensor_needstage , nsensor , 1 ) X ( int , sensor_objtype , nsensor , 1 ) X ( int , sensor_objid , nsensor , 1 ) X ( int , sensor_reftype , nsensor , 1 ) X ( int , sensor_refid , nsensor , 1 ) X ( int , sensor_intprm , nsensor , mjNSENS ) X ( int , sensor_dim , nsensor , 1 ) X ( int , sensor_adr , nsensor , 1 ) X ( mjtNum , sensor_cutoff , nsensor , 1 ) X ( mjtNum , sensor_noise , nsensor , 1 ) X ( int , sensor_history , nsensor , 2 ) X ( int , sensor_historyadr , nsensor , 1 ) X ( mjtNum , sensor_delay , nsensor , 1 ) X ( mjtNum , sensor_interval , nsensor , 2 ) X ( mjtNum , sensor_user , nsensor , MJ_M ( nuser_sensor ) ) X ( int , sensor_plugin , nsensor , 1 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 700 + }, + "MJMODEL_POINTERS": { + "value": "X ( mjtNum , qpos0 , nq , 1 ) X ( mjtNum , qpos_spring , nq , 1 ) MJMODEL_POINTERS_BODY X ( int , bvh_depth , nbvh , 1 ) X ( int , bvh_child , nbvh , 2 ) X ( int , bvh_nodeid , nbvh , 1 ) X ( mjtNum , bvh_aabb , nbvhstatic , 6 ) X ( int , oct_depth , noct , 1 ) X ( int , oct_child , noct , 8 ) X ( mjtNum , oct_aabb , noct , 6 ) X ( mjtNum , oct_coeff , noct , 8 ) MJMODEL_POINTERS_JOINT MJMODEL_POINTERS_DOF MJMODEL_POINTERS_TREE MJMODEL_POINTERS_GEOM MJMODEL_POINTERS_SITE MJMODEL_POINTERS_CAMERA MJMODEL_POINTERS_LIGHT MJMODEL_POINTERS_FLEX MJMODEL_POINTERS_MESH MJMODEL_POINTERS_SKIN MJMODEL_POINTERS_HFIELD MJMODEL_POINTERS_TEXTURE MJMODEL_POINTERS_MATERIAL MJMODEL_POINTERS_PAIR MJMODEL_POINTERS_EXCLUDE MJMODEL_POINTERS_EQUALITY MJMODEL_POINTERS_TENDON X ( int , wrap_type , nwrap , 1 ) X ( int , wrap_objid , nwrap , 1 ) X ( mjtNum , wrap_prm , nwrap , 1 ) MJMODEL_POINTERS_ACTUATOR MJMODEL_POINTERS_SENSOR X ( int , plugin , nplugin , 1 ) X ( int , plugin_stateadr , nplugin , 1 ) X ( int , plugin_statenum , nplugin , 1 ) X ( char , plugin_attr , npluginattr , 1 ) X ( int , plugin_attradr , nplugin , 1 ) X ( int , numeric_adr , nnumeric , 1 ) X ( int , numeric_size , nnumeric , 1 ) X ( mjtNum , numeric_data , nnumericdata , 1 ) X ( int , text_adr , ntext , 1 ) X ( int , text_size , ntext , 1 ) X ( char , text_data , ntextdata , 1 ) X ( int , tuple_adr , ntuple , 1 ) X ( int , tuple_size , ntuple , 1 ) X ( int , tuple_objtype , ntupledata , 1 ) X ( int , tuple_objid , ntupledata , 1 ) X ( mjtNum , tuple_objprm , ntupledata , 1 ) X ( mjtNum , key_time , nkey , 1 ) X ( mjtNum , key_qpos , nkey , MJ_M ( nq ) ) X ( mjtNum , key_qvel , nkey , MJ_M ( nv ) ) X ( mjtNum , key_act , nkey , MJ_M ( na ) ) X ( mjtNum , key_mpos , nkey , MJ_M ( nmocap ) * 3 ) X ( mjtNum , key_mquat , nkey , MJ_M ( nmocap ) * 4 ) X ( mjtNum , key_ctrl , nkey , MJ_M ( nu ) ) X ( int , name_bodyadr , nbody , 1 ) X ( int , name_jntadr , njnt , 1 ) X ( int , name_geomadr , ngeom , 1 ) X ( int , name_siteadr , nsite , 1 ) X ( int , name_camadr , ncam , 1 ) X ( int , name_lightadr , nlight , 1 ) X ( int , name_flexadr , nflex , 1 ) X ( int , name_meshadr , nmesh , 1 ) X ( int , name_skinadr , nskin , 1 ) X ( int , name_hfieldadr , nhfield , 1 ) X ( int , name_texadr , ntex , 1 ) X ( int , name_matadr , nmat , 1 ) X ( int , name_pairadr , npair , 1 ) X ( int , name_excludeadr , nexclude , 1 ) X ( int , name_eqadr , neq , 1 ) X ( int , name_tendonadr , ntendon , 1 ) X ( int , name_actuatoradr , nu , 1 ) X ( int , name_sensoradr , nsensor , 1 ) X ( int , name_numericadr , nnumeric , 1 ) X ( int , name_textadr , ntext , 1 ) X ( int , name_tupleadr , ntuple , 1 ) X ( int , name_keyadr , nkey , 1 ) X ( int , name_pluginadr , nplugin , 1 ) X ( char , names , nnames , 1 ) X ( int , names_map , nnames_map , 1 ) X ( char , paths , npaths , 1 ) X ( int , B_rownnz , nbody , 1 ) X ( int , B_rowadr , nbody , 1 ) X ( int , B_colind , nB , 1 ) X ( int , M_rownnz , nv , 1 ) X ( int , M_rowadr , nv , 1 ) X ( int , M_colind , nC , 1 ) X ( int , mapM2M , nC , 1 ) X ( int , D_rownnz , nv , 1 ) X ( int , D_rowadr , nv , 1 ) X ( int , D_diag , nv , 1 ) X ( int , D_colind , nD , 1 ) X ( int , mapM2D , nD , 1 ) X ( int , mapD2M , nC , 1 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 720 + }, + "MJDATA_POINTERS": { + "value": "X ( mjtNum , qpos , nq , 1 ) X ( mjtNum , qvel , nv , 1 ) X ( mjtNum , act , na , 1 ) X ( mjtNum , history , nhistory , 1 ) X ( mjtNum , qacc_warmstart , nv , 1 ) X ( mjtNum , plugin_state , npluginstate , 1 ) X ( mjtNum , ctrl , nu , 1 ) X ( mjtNum , qfrc_applied , nv , 1 ) X ( mjtNum , xfrc_applied , nbody , 6 ) X ( mjtByte , eq_active , neq , 1 ) X ( mjtNum , mocap_pos , nmocap , 3 ) X ( mjtNum , mocap_quat , nmocap , 4 ) X ( mjtNum , qacc , nv , 1 ) X ( mjtNum , act_dot , na , 1 ) X ( mjtNum , userdata , nuserdata , 1 ) X ( mjtNum , sensordata , nsensordata , 1 ) X ( int , tree_asleep , ntree , 1 ) X ( int , plugin , nplugin , 1 ) X ( uintptr_t , plugin_data , nplugin , 1 ) X ( mjtNum , xpos , nbody , 3 ) X ( mjtNum , xquat , nbody , 4 ) X ( mjtNum , xmat , nbody , 9 ) X ( mjtNum , xipos , nbody , 3 ) X ( mjtNum , ximat , nbody , 9 ) X ( mjtNum , xanchor , njnt , 3 ) X ( mjtNum , xaxis , njnt , 3 ) X ( mjtNum , geom_xpos , ngeom , 3 ) X ( mjtNum , geom_xmat , ngeom , 9 ) X ( mjtNum , site_xpos , nsite , 3 ) X ( mjtNum , site_xmat , nsite , 9 ) X ( mjtNum , cam_xpos , ncam , 3 ) X ( mjtNum , cam_xmat , ncam , 9 ) X ( mjtNum , light_xpos , nlight , 3 ) X ( mjtNum , light_xdir , nlight , 3 ) X ( mjtNum , subtree_com , nbody , 3 ) X ( mjtNum , cdof , nv , 6 ) X ( mjtNum , cinert , nbody , 10 ) X ( mjtNum , flexvert_xpos , nflexvert , 3 ) X ( mjtNum , flexelem_aabb , nflexelem , 6 ) X ( mjtNum , flexedge_J , nJfe , 1 ) X ( mjtNum , flexedge_length , nflexedge , 1 ) X ( mjtNum , flexvert_J , nJfv , 2 ) X ( mjtNum , flexvert_length , nflexvert , 2 ) X ( mjtNum , bvh_aabb_dyn , nbvhdynamic , 6 ) X ( int , ten_wrapadr , ntendon , 1 ) X ( int , ten_wrapnum , ntendon , 1 ) X ( mjtNum , ten_J , nJten , 1 ) X ( mjtNum , ten_length , ntendon , 1 ) X ( int , wrap_obj , nwrap , 2 ) X ( mjtNum , wrap_xpos , nwrap , 6 ) X ( mjtNum , actuator_length , nu , 1 ) X ( int , moment_rownnz , nu , 1 ) X ( int , moment_rowadr , nu , 1 ) X ( int , moment_colind , nJmom , 1 ) X ( mjtNum , actuator_moment , nJmom , 1 ) XNV ( mjtNum , crb , nbody , 10 ) XNV ( mjtNum , qM , nM , 1 ) XNV ( mjtNum , M , nC , 1 ) XNV ( mjtNum , qLD , nC , 1 ) X ( mjtNum , qLDiagInv , nv , 1 ) X ( mjtByte , bvh_active , nbvh , 1 ) X ( int , tree_awake , ntree , 1 ) X ( int , body_awake , nbody , 1 ) X ( int , body_awake_ind , nbody , 1 ) X ( int , parent_awake_ind , nbody , 1 ) X ( int , dof_awake_ind , nv , 1 ) X ( mjtNum , flexedge_velocity , nflexedge , 1 ) X ( mjtNum , ten_velocity , ntendon , 1 ) X ( mjtNum , actuator_velocity , nu , 1 ) X ( mjtNum , cvel , nbody , 6 ) X ( mjtNum , cdof_dot , nv , 6 ) X ( mjtNum , qfrc_bias , nv , 1 ) X ( mjtNum , qfrc_spring , nv , 1 ) X ( mjtNum , qfrc_damper , nv , 1 ) X ( mjtNum , qfrc_gravcomp , nv , 1 ) X ( mjtNum , qfrc_fluid , nv , 1 ) X ( mjtNum , qfrc_passive , nv , 1 ) X ( mjtNum , subtree_linvel , nbody , 3 ) X ( mjtNum , subtree_angmom , nbody , 3 ) XNV ( mjtNum , qH , nC , 1 ) X ( mjtNum , qHDiagInv , nv , 1 ) XNV ( mjtNum , qDeriv , nD , 1 ) XNV ( mjtNum , qLU , nD , 1 ) X ( mjtNum , actuator_force , nu , 1 ) X ( mjtNum , qfrc_actuator , nv , 1 ) X ( mjtNum , qfrc_smooth , nv , 1 ) X ( mjtNum , qacc_smooth , nv , 1 ) X ( mjtNum , qfrc_constraint , nv , 1 ) X ( mjtNum , qfrc_inverse , nv , 1 ) X ( mjtNum , cacc , nbody , 6 ) X ( mjtNum , cfrc_int , nbody , 6 ) X ( mjtNum , cfrc_ext , nbody , 6 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 822 + }, + "MJ_D": { + "value": "( n ) n", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 919 + }, + "MJDATA_ARENA_POINTERS_CONTACT": { + "value": "X ( mjContact , contact , MJ_D ( ncon ) , 1 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 922 + }, + "MJDATA_ARENA_POINTERS_SOLVER": { + "value": "X ( int , efc_type , MJ_D ( nefc ) , 1 ) X ( int , efc_id , MJ_D ( nefc ) , 1 ) XNV ( int , efc_J_rownnz , MJ_D ( nefc ) , 1 ) XNV ( int , efc_J_rowadr , MJ_D ( nefc ) , 1 ) XNV ( int , efc_J_rowsuper , MJ_D ( nefc ) , 1 ) XNV ( int , efc_J_colind , MJ_D ( nJ ) , 1 ) XNV ( mjtNum , efc_J , MJ_D ( nJ ) , 1 ) X ( mjtNum , efc_pos , MJ_D ( nefc ) , 1 ) X ( mjtNum , efc_margin , MJ_D ( nefc ) , 1 ) X ( mjtNum , efc_frictionloss , MJ_D ( nefc ) , 1 ) X ( mjtNum , efc_diagApprox , MJ_D ( nefc ) , 1 ) X ( mjtNum , efc_KBIP , MJ_D ( nefc ) , 4 ) X ( mjtNum , efc_D , MJ_D ( nefc ) , 1 ) X ( mjtNum , efc_R , MJ_D ( nefc ) , 1 ) X ( int , tendon_efcadr , MJ_M ( ntendon ) , 1 ) X ( mjtNum , efc_vel , MJ_D ( nefc ) , 1 ) X ( mjtNum , efc_aref , MJ_D ( nefc ) , 1 ) X ( mjtNum , efc_b , MJ_D ( nefc ) , 1 ) X ( int , efc_state , MJ_D ( nefc ) , 1 ) X ( mjtNum , efc_force , MJ_D ( nefc ) , 1 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 926 + }, + "MJDATA_ARENA_POINTERS_DUAL": { + "value": "XNV ( int , efc_AR_rownnz , MJ_D ( nefc ) , 1 ) XNV ( int , efc_AR_rowadr , MJ_D ( nefc ) , 1 ) XNV ( int , efc_AR_colind , MJ_D ( nA ) , 1 ) XNV ( mjtNum , efc_AR , MJ_D ( nA ) , 1 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 949 + }, + "MJDATA_ARENA_POINTERS_ISLAND": { + "value": "X ( int , tree_island , MJ_M ( ntree ) , 1 ) X ( int , island_ntree , MJ_D ( nisland ) , 1 ) X ( int , island_itreeadr , MJ_D ( nisland ) , 1 ) X ( int , map_itree2tree , MJ_M ( ntree ) , 1 ) X ( int , dof_island , MJ_M ( nv ) , 1 ) X ( int , island_nv , MJ_D ( nisland ) , 1 ) X ( int , island_idofadr , MJ_D ( nisland ) , 1 ) X ( int , island_dofadr , MJ_D ( nisland ) , 1 ) X ( int , map_dof2idof , MJ_M ( nv ) , 1 ) X ( int , map_idof2dof , MJ_M ( nv ) , 1 ) X ( mjtNum , ifrc_smooth , MJ_D ( nidof ) , 1 ) X ( mjtNum , iacc_smooth , MJ_D ( nidof ) , 1 ) XNV ( int , iM_rownnz , MJ_D ( nidof ) , 1 ) XNV ( int , iM_rowadr , MJ_D ( nidof ) , 1 ) XNV ( int , iM_colind , MJ_M ( nC ) , 1 ) XNV ( mjtNum , iM , MJ_M ( nC ) , 1 ) XNV ( mjtNum , iLD , MJ_M ( nC ) , 1 ) X ( mjtNum , iLDiagInv , MJ_D ( nidof ) , 1 ) X ( mjtNum , iacc , MJ_D ( nidof ) , 1 ) X ( int , efc_island , MJ_D ( nefc ) , 1 ) X ( int , island_ne , MJ_D ( nisland ) , 1 ) X ( int , island_nf , MJ_D ( nisland ) , 1 ) X ( int , island_nefc , MJ_D ( nisland ) , 1 ) X ( int , island_iefcadr , MJ_D ( nisland ) , 1 ) X ( int , map_efc2iefc , MJ_D ( nefc ) , 1 ) X ( int , map_iefc2efc , MJ_D ( nefc ) , 1 ) X ( int , iefc_type , MJ_D ( nefc ) , 1 ) X ( int , iefc_id , MJ_D ( nefc ) , 1 ) XNV ( int , iefc_J_rownnz , MJ_D ( nefc ) , 1 ) XNV ( int , iefc_J_rowadr , MJ_D ( nefc ) , 1 ) XNV ( int , iefc_J_rowsuper , MJ_D ( nefc ) , 1 ) XNV ( int , iefc_J_colind , MJ_D ( nJ ) , 1 ) XNV ( mjtNum , iefc_J , MJ_D ( nJ ) , 1 ) X ( mjtNum , iefc_frictionloss , MJ_D ( nefc ) , 1 ) X ( mjtNum , iefc_D , MJ_D ( nefc ) , 1 ) X ( mjtNum , iefc_R , MJ_D ( nefc ) , 1 ) X ( mjtNum , iefc_aref , MJ_D ( nefc ) , 1 ) X ( int , iefc_state , MJ_D ( nefc ) , 1 ) X ( mjtNum , iefc_force , MJ_D ( nefc ) , 1 ) X ( mjtNum , ifrc_constraint , MJ_D ( nidof ) , 1 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 956 + }, + "MJDATA_ARENA_POINTERS": { + "value": "MJDATA_ARENA_POINTERS_CONTACT MJDATA_ARENA_POINTERS_SOLVER MJDATA_ARENA_POINTERS_DUAL MJDATA_ARENA_POINTERS_ISLAND", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 999 + }, + "MJDATA_SCALAR": { + "value": "X ( size_t , narena ) X ( size_t , nbuffer ) X ( int , nplugin ) X ( size_t , pstack ) X ( size_t , pbase ) X ( size_t , parena ) X ( size_t , maxuse_stack ) X ( size_t , maxuse_arena ) X ( int , maxuse_con ) X ( int , maxuse_efc ) X ( int , ncon ) X ( int , ne ) X ( int , nf ) X ( int , nl ) X ( int , nefc ) X ( int , nJ ) X ( int , nA ) X ( int , nisland ) X ( int , nidof ) X ( int , ntree_awake ) X ( int , nbody_awake ) X ( int , nparent_awake ) X ( int , nv_awake ) X ( mjtByte , flg_energypos ) X ( mjtByte , flg_energyvel ) X ( mjtByte , flg_subtreevel ) X ( mjtByte , flg_rnepost ) X ( mjtNum , time ) X ( uintptr_t , threadpool )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 1007 + }, + "MJDATA_VECTOR": { + "value": "X ( size_t , maxuse_threadstack , mjMAXTHREAD , 1 ) X ( mjSolverStat , solver , mjNISLAND , mjNSOLVER ) X ( int , solver_niter , mjNISLAND , 1 ) X ( int , solver_nnz , mjNISLAND , 1 ) X ( mjtNum , solver_fwdinv , 2 , 1 ) X ( mjWarningStat , warning , mjNWARNING , 1 ) X ( mjTimerStat , timer , mjNTIMER , 1 ) X ( mjtNum , energy , 2 , 1 )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 1040 + }, + "XNV": { + "value": "X", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjxmacro.h", + "line": 1053 + }, + "mjVERSION_HEADER": { + "value": "3008001", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 19 + }, + "mjMAXTHREAD": { + "value": "128", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjthread.h", + "line": 18 + }, + "MUJOCO_HELPER_DLL_IMPORT": { + "value": "__declspec ( dllimport )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjexport.h", + "line": 19 + }, + "MUJOCO_HELPER_DLL_EXPORT": { + "value": "__declspec ( dllexport )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjexport.h", + "line": 20 + }, + "mjMAX": { + "value": "( a , b ) ( ( ( a ) > ( b ) ) ? ( a ) : ( b ) )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmacro.h", + "line": 19 + }, + "mjMIN": { + "value": "( a , b ) ( ( ( a ) < ( b ) ) ? ( a ) : ( b ) )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmacro.h", + "line": 20 + }, + "mjDISABLED": { + "value": "( x ) ( m -> opt . disableflags & ( x ) )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmacro.h", + "line": 23 + }, + "mjENABLED": { + "value": "( x ) ( m -> opt . enableflags & ( x ) )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmacro.h", + "line": 24 + }, + "mjACTUATORDISABLED": { + "value": "( i ) ( m -> opt . disableactuator & ( 1 << m -> actuator_group [ i ] ) )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmacro.h", + "line": 27 + }, + "mjPRINTFLIKE": { + "value": "( n , m )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjmacro.h", + "line": 34 + }, + "mjNGROUP": { + "value": "6", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 23 + }, + "mjMAXLIGHT": { + "value": "100", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 24 + }, + "mjMAXOVERLAY": { + "value": "500", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 25 + }, + "mjMAXLINE": { + "value": "100", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 26 + }, + "mjMAXLINEPNT": { + "value": "1001", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 27 + }, + "mjMAXPLANEGRID": { + "value": "200", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjvisualize.h", + "line": 28 + }, + "mjPLUGIN_LIB_INIT": { + "value": "( n ) static void _mj_init_ ## n ( void ) __attribute__ ( ( constructor ) ) ; static void _mj_init_ ## n ( void )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjplugin.h", + "line": 189 + }, + "mjNAUX": { + "value": "10", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjrender.h", + "line": 24 + }, + "mjMAXTEXTURE": { + "value": "1000", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjrender.h", + "line": 25 + }, + "mjMAXMATERIAL": { + "value": "1000", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjrender.h", + "line": 26 + }, + "ASAN_POISON_MEMORY_REGION": { + "value": "( addr , size )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjsan.h", + "line": 33 + }, + "ASAN_UNPOISON_MEMORY_REGION": { + "value": "( addr , size )", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjsan.h", + "line": 34 + }, + "mjMAXUISECT": { + "value": "10", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 20 + }, + "mjMAXUIITEM": { + "value": "200", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 21 + }, + "mjMAXUITEXT": { + "value": "300", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 22 + }, + "mjMAXUINAME": { + "value": "40", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 23 + }, + "mjMAXUIMULTI": { + "value": "35", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 24 + }, + "mjMAXUIEDIT": { + "value": "7", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 25 + }, + "mjMAXUIRECT": { + "value": "25", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 26 + }, + "mjSEPCLOSED": { + "value": "1000", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 28 + }, + "mjPRESERVE": { + "value": "2000", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 29 + }, + "mjKEY_ESCAPE": { + "value": "256", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 33 + }, + "mjKEY_ENTER": { + "value": "257", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 34 + }, + "mjKEY_TAB": { + "value": "258", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 35 + }, + "mjKEY_BACKSPACE": { + "value": "259", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 36 + }, + "mjKEY_INSERT": { + "value": "260", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 37 + }, + "mjKEY_DELETE": { + "value": "261", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 38 + }, + "mjKEY_RIGHT": { + "value": "262", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 39 + }, + "mjKEY_LEFT": { + "value": "263", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 40 + }, + "mjKEY_DOWN": { + "value": "264", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 41 + }, + "mjKEY_UP": { + "value": "265", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 42 + }, + "mjKEY_PAGE_UP": { + "value": "266", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 43 + }, + "mjKEY_PAGE_DOWN": { + "value": "267", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 44 + }, + "mjKEY_HOME": { + "value": "268", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 45 + }, + "mjKEY_END": { + "value": "269", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 46 + }, + "mjKEY_F1": { + "value": "290", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 47 + }, + "mjKEY_F2": { + "value": "291", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 48 + }, + "mjKEY_F3": { + "value": "292", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 49 + }, + "mjKEY_F4": { + "value": "293", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 50 + }, + "mjKEY_F5": { + "value": "294", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 51 + }, + "mjKEY_F6": { + "value": "295", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 52 + }, + "mjKEY_F7": { + "value": "296", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 53 + }, + "mjKEY_F8": { + "value": "297", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 54 + }, + "mjKEY_F9": { + "value": "298", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 55 + }, + "mjKEY_F10": { + "value": "299", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 56 + }, + "mjKEY_F11": { + "value": "300", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 57 + }, + "mjKEY_F12": { + "value": "301", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 58 + }, + "mjKEY_NUMPAD_0": { + "value": "320", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 59 + }, + "mjKEY_NUMPAD_9": { + "value": "329", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mjui.h", + "line": 60 + }, + "mju_sqrt": { + "value": "sqrt", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1015 + }, + "mju_exp": { + "value": "exp", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1016 + }, + "mju_sin": { + "value": "sin", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1017 + }, + "mju_cos": { + "value": "cos", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1018 + }, + "mju_tan": { + "value": "tan", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1019 + }, + "mju_asin": { + "value": "asin", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1020 + }, + "mju_acos": { + "value": "acos", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1021 + }, + "mju_atan2": { + "value": "atan2", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1022 + }, + "mju_tanh": { + "value": "tanh", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1023 + }, + "mju_pow": { + "value": "pow", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1024 + }, + "mju_abs": { + "value": "fabs", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1025 + }, + "mju_log": { + "value": "log", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1026 + }, + "mju_log10": { + "value": "log10", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1027 + }, + "mju_floor": { + "value": "floor", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1028 + }, + "mju_ceil": { + "value": "ceil", + "doc": "", + "file": "c:\\users\\jonat\\documents\\unreal projects\\url_proj\\plugins\\unrealroboticslab\\third_party\\install\\mujoco\\include\\mujoco\\mujoco.h", + "line": 1029 + } + } +} \ No newline at end of file diff --git a/Scripts/mjcf_schema_snapshot.json b/Scripts/codegen/snapshots/mjcf_schema_snapshot.json similarity index 56% rename from Scripts/mjcf_schema_snapshot.json rename to Scripts/codegen/snapshots/mjcf_schema_snapshot.json index 05a5798..ef17273 100644 --- a/Scripts/mjcf_schema_snapshot.json +++ b/Scripts/codegen/snapshots/mjcf_schema_snapshot.json @@ -1,7 +1,7 @@ { "_meta": { "mujoco_version": "3.8.1", - "snapshot_date": "2026-05-15", + "snapshot_date": "2026-05-28", "source": "https://github.com/google-deepmind/mujoco/blob/main/src/xml/xml_native_reader.cc", "description": "MJCF schema snapshot, auto-extracted by Scripts/codegen/build_mjcf_schema_snapshot.py from the MuJoCo submodule's xml_native_reader.cc." }, @@ -351,6 +351,400 @@ "user" ] }, + "sensor_per_type": { + "touch": { + "mj_type": "mjSENS_TOUCH", + "objtype": "mjOBJ_SITE", + "reftype": null, + "obj_attr": "site", + "ref_attr": null, + "computed": false + }, + "accelerometer": { + "mj_type": "mjSENS_ACCELEROMETER", + "objtype": "mjOBJ_SITE", + "reftype": null, + "obj_attr": "site", + "ref_attr": null, + "computed": false + }, + "velocimeter": { + "mj_type": "mjSENS_VELOCIMETER", + "objtype": "mjOBJ_SITE", + "reftype": null, + "obj_attr": "site", + "ref_attr": null, + "computed": false + }, + "gyro": { + "mj_type": "mjSENS_GYRO", + "objtype": "mjOBJ_SITE", + "reftype": null, + "obj_attr": "site", + "ref_attr": null, + "computed": false + }, + "force": { + "mj_type": "mjSENS_FORCE", + "objtype": "mjOBJ_SITE", + "reftype": null, + "obj_attr": "site", + "ref_attr": null, + "computed": false + }, + "torque": { + "mj_type": "mjSENS_TORQUE", + "objtype": "mjOBJ_SITE", + "reftype": null, + "obj_attr": "site", + "ref_attr": null, + "computed": false + }, + "magnetometer": { + "mj_type": "mjSENS_MAGNETOMETER", + "objtype": "mjOBJ_SITE", + "reftype": null, + "obj_attr": "site", + "ref_attr": null, + "computed": false + }, + "camprojection": { + "mj_type": "mjSENS_CAMPROJECTION", + "objtype": "mjOBJ_SITE", + "reftype": "mjOBJ_CAMERA", + "obj_attr": "site", + "ref_attr": "camera", + "computed": false + }, + "rangefinder": { + "mj_type": "mjSENS_RANGEFINDER", + "objtype": "computed", + "reftype": "computed", + "obj_attr": "site", + "ref_attr": null, + "computed": true + }, + "jointpos": { + "mj_type": "mjSENS_JOINTPOS", + "objtype": "mjOBJ_JOINT", + "reftype": null, + "obj_attr": "joint", + "ref_attr": null, + "computed": false + }, + "jointvel": { + "mj_type": "mjSENS_JOINTVEL", + "objtype": "mjOBJ_JOINT", + "reftype": null, + "obj_attr": "joint", + "ref_attr": null, + "computed": false + }, + "tendonpos": { + "mj_type": "mjSENS_TENDONPOS", + "objtype": "mjOBJ_TENDON", + "reftype": null, + "obj_attr": "tendon", + "ref_attr": null, + "computed": false + }, + "tendonvel": { + "mj_type": "mjSENS_TENDONVEL", + "objtype": "mjOBJ_TENDON", + "reftype": null, + "obj_attr": "tendon", + "ref_attr": null, + "computed": false + }, + "actuatorpos": { + "mj_type": "mjSENS_ACTUATORPOS", + "objtype": "mjOBJ_ACTUATOR", + "reftype": null, + "obj_attr": "actuator", + "ref_attr": null, + "computed": false + }, + "actuatorvel": { + "mj_type": "mjSENS_ACTUATORVEL", + "objtype": "mjOBJ_ACTUATOR", + "reftype": null, + "obj_attr": "actuator", + "ref_attr": null, + "computed": false + }, + "actuatorfrc": { + "mj_type": "mjSENS_ACTUATORFRC", + "objtype": "mjOBJ_ACTUATOR", + "reftype": null, + "obj_attr": "actuator", + "ref_attr": null, + "computed": false + }, + "jointactuatorfrc": { + "mj_type": "mjSENS_JOINTACTFRC", + "objtype": "mjOBJ_JOINT", + "reftype": null, + "obj_attr": "joint", + "ref_attr": null, + "computed": false + }, + "tendonactuatorfrc": { + "mj_type": "mjSENS_TENDONACTFRC", + "objtype": "mjOBJ_TENDON", + "reftype": null, + "obj_attr": "tendon", + "ref_attr": null, + "computed": false + }, + "ballquat": { + "mj_type": "mjSENS_BALLQUAT", + "objtype": "mjOBJ_JOINT", + "reftype": null, + "obj_attr": "joint", + "ref_attr": null, + "computed": false + }, + "ballangvel": { + "mj_type": "mjSENS_BALLANGVEL", + "objtype": "mjOBJ_JOINT", + "reftype": null, + "obj_attr": "joint", + "ref_attr": null, + "computed": false + }, + "jointlimitpos": { + "mj_type": "mjSENS_JOINTLIMITPOS", + "objtype": "mjOBJ_JOINT", + "reftype": null, + "obj_attr": "joint", + "ref_attr": null, + "computed": false + }, + "jointlimitvel": { + "mj_type": "mjSENS_JOINTLIMITVEL", + "objtype": "mjOBJ_JOINT", + "reftype": null, + "obj_attr": "joint", + "ref_attr": null, + "computed": false + }, + "jointlimitfrc": { + "mj_type": "mjSENS_JOINTLIMITFRC", + "objtype": "mjOBJ_JOINT", + "reftype": null, + "obj_attr": "joint", + "ref_attr": null, + "computed": false + }, + "tendonlimitpos": { + "mj_type": "mjSENS_TENDONLIMITPOS", + "objtype": "mjOBJ_TENDON", + "reftype": null, + "obj_attr": "tendon", + "ref_attr": null, + "computed": false + }, + "tendonlimitvel": { + "mj_type": "mjSENS_TENDONLIMITVEL", + "objtype": "mjOBJ_TENDON", + "reftype": null, + "obj_attr": "tendon", + "ref_attr": null, + "computed": false + }, + "tendonlimitfrc": { + "mj_type": "mjSENS_TENDONLIMITFRC", + "objtype": "mjOBJ_TENDON", + "reftype": null, + "obj_attr": "tendon", + "ref_attr": null, + "computed": false + }, + "framepos": { + "mj_type": "mjSENS_FRAMEPOS", + "objtype": "from_xml", + "reftype": null, + "obj_attr": "objname", + "ref_attr": "refname", + "computed": false + }, + "framequat": { + "mj_type": "mjSENS_FRAMEQUAT", + "objtype": "from_xml", + "reftype": null, + "obj_attr": "objname", + "ref_attr": "refname", + "computed": false + }, + "framexaxis": { + "mj_type": "mjSENS_FRAMEXAXIS", + "objtype": "from_xml", + "reftype": null, + "obj_attr": "objname", + "ref_attr": "refname", + "computed": false + }, + "frameyaxis": { + "mj_type": "mjSENS_FRAMEYAXIS", + "objtype": "from_xml", + "reftype": null, + "obj_attr": "objname", + "ref_attr": "refname", + "computed": false + }, + "framezaxis": { + "mj_type": "mjSENS_FRAMEZAXIS", + "objtype": "from_xml", + "reftype": null, + "obj_attr": "objname", + "ref_attr": "refname", + "computed": false + }, + "framelinvel": { + "mj_type": "mjSENS_FRAMELINVEL", + "objtype": "from_xml", + "reftype": null, + "obj_attr": "objname", + "ref_attr": "refname", + "computed": false + }, + "frameangvel": { + "mj_type": "mjSENS_FRAMEANGVEL", + "objtype": "from_xml", + "reftype": null, + "obj_attr": "objname", + "ref_attr": "refname", + "computed": false + }, + "framelinacc": { + "mj_type": "mjSENS_FRAMELINACC", + "objtype": "from_xml", + "reftype": null, + "obj_attr": "objname", + "ref_attr": null, + "computed": false + }, + "frameangacc": { + "mj_type": "mjSENS_FRAMEANGACC", + "objtype": "from_xml", + "reftype": null, + "obj_attr": "objname", + "ref_attr": null, + "computed": false + }, + "subtreecom": { + "mj_type": "mjSENS_SUBTREECOM", + "objtype": "mjOBJ_BODY", + "reftype": null, + "obj_attr": "body", + "ref_attr": null, + "computed": false + }, + "subtreelinvel": { + "mj_type": "mjSENS_SUBTREELINVEL", + "objtype": "mjOBJ_BODY", + "reftype": null, + "obj_attr": "body", + "ref_attr": null, + "computed": false + }, + "subtreeangmom": { + "mj_type": "mjSENS_SUBTREEANGMOM", + "objtype": "mjOBJ_BODY", + "reftype": null, + "obj_attr": "body", + "ref_attr": null, + "computed": false + }, + "insidesite": { + "mj_type": "mjSENS_INSIDESITE", + "objtype": "from_xml", + "reftype": "mjOBJ_SITE", + "obj_attr": "objname", + "ref_attr": "site", + "computed": false + }, + "distance": { + "mj_type": "mjSENS_GEOMDIST", + "objtype": "computed", + "reftype": "computed", + "obj_attr": "body1", + "ref_attr": "body2", + "computed": true + }, + "normal": { + "mj_type": "mjSENS_GEOMNORMAL", + "objtype": "computed", + "reftype": "computed", + "obj_attr": "body1", + "ref_attr": "body2", + "computed": true + }, + "fromto": { + "mj_type": "mjSENS_GEOMFROMTO", + "objtype": "computed", + "reftype": "computed", + "obj_attr": "body1", + "ref_attr": "body2", + "computed": true + }, + "contact": { + "mj_type": "mjSENS_CONTACT", + "objtype": "computed", + "reftype": "computed", + "obj_attr": "site", + "ref_attr": "body2", + "computed": true + }, + "e_potential": { + "mj_type": "mjSENS_E_POTENTIAL", + "objtype": "mjOBJ_UNKNOWN", + "reftype": null, + "obj_attr": null, + "ref_attr": null, + "computed": false + }, + "e_kinetic": { + "mj_type": "mjSENS_E_KINETIC", + "objtype": "mjOBJ_UNKNOWN", + "reftype": null, + "obj_attr": null, + "ref_attr": null, + "computed": false + }, + "clock": { + "mj_type": "mjSENS_CLOCK", + "objtype": "mjOBJ_UNKNOWN", + "reftype": null, + "obj_attr": null, + "ref_attr": null, + "computed": false + }, + "tactile": { + "mj_type": "mjSENS_TACTILE", + "objtype": "mjOBJ_MESH", + "reftype": "mjOBJ_GEOM", + "obj_attr": "mesh", + "ref_attr": "geom", + "computed": false + }, + "user": { + "mj_type": "mjSENS_USER", + "objtype": "computed", + "reftype": "computed", + "obj_attr": "objname", + "ref_attr": null, + "computed": true + }, + "plugin": { + "mj_type": "mjSENS_PLUGIN", + "objtype": "computed", + "reftype": "computed", + "obj_attr": "objname", + "ref_attr": "refname", + "computed": true + } + }, "tendon": { "spatial": { "attrs": [ diff --git a/Scripts/mjspec_snapshot.json b/Scripts/codegen/snapshots/mjspec_snapshot.json similarity index 60% rename from Scripts/mjspec_snapshot.json rename to Scripts/codegen/snapshots/mjspec_snapshot.json index 64531d0..0d08aab 100644 --- a/Scripts/mjspec_snapshot.json +++ b/Scripts/codegen/snapshots/mjspec_snapshot.json @@ -689,5 +689,332 @@ } ] } + }, + "enums": { + "mjtDisableBit": { + "mjDSBL_CONSTRAINT": 1, + "mjDSBL_EQUALITY": 2, + "mjDSBL_FRICTIONLOSS": 4, + "mjDSBL_LIMIT": 8, + "mjDSBL_CONTACT": 16, + "mjDSBL_SPRING": 32, + "mjDSBL_DAMPER": 64, + "mjDSBL_GRAVITY": 128, + "mjDSBL_CLAMPCTRL": 256, + "mjDSBL_WARMSTART": 512, + "mjDSBL_FILTERPARENT": 1024, + "mjDSBL_ACTUATION": 2048, + "mjDSBL_REFSAFE": 4096, + "mjDSBL_SENSOR": 8192, + "mjDSBL_MIDPHASE": 16384, + "mjDSBL_EULERDAMP": 32768, + "mjDSBL_AUTORESET": 65536, + "mjDSBL_NATIVECCD": 131072, + "mjDSBL_ISLAND": 262144, + "mjDSBL_MULTICCD": 524288, + "mjNDISABLE": 20 + }, + "mjtEnableBit": { + "mjENBL_OVERRIDE": 1, + "mjENBL_ENERGY": 2, + "mjENBL_FWDINV": 4, + "mjENBL_INVDISCRETE": 8, + "mjENBL_SLEEP": 16, + "mjNENABLE": 5 + }, + "mjtJoint": { + "mjJNT_FREE": 0, + "mjJNT_BALL": 1, + "mjJNT_SLIDE": 2, + "mjJNT_HINGE": 3 + }, + "mjtGeom": { + "mjGEOM_PLANE": 0, + "mjGEOM_HFIELD": 1, + "mjGEOM_SPHERE": 2, + "mjGEOM_CAPSULE": 3, + "mjGEOM_ELLIPSOID": 4, + "mjGEOM_CYLINDER": 5, + "mjGEOM_BOX": 6, + "mjGEOM_MESH": 7, + "mjGEOM_SDF": 8, + "mjNGEOMTYPES": 9, + "mjGEOM_ARROW": 100, + "mjGEOM_ARROW1": 101, + "mjGEOM_ARROW2": 102, + "mjGEOM_LINE": 103, + "mjGEOM_LINEBOX": 104, + "mjGEOM_FLEX": 105, + "mjGEOM_SKIN": 106, + "mjGEOM_LABEL": 107, + "mjGEOM_TRIANGLE": 108, + "mjGEOM_NONE": 1001 + }, + "mjtProjection": { + "mjPROJ_PERSPECTIVE": 0, + "mjPROJ_ORTHOGRAPHIC": 1 + }, + "mjtCamLight": { + "mjCAMLIGHT_FIXED": 0, + "mjCAMLIGHT_TRACK": 1, + "mjCAMLIGHT_TRACKCOM": 2, + "mjCAMLIGHT_TARGETBODY": 3, + "mjCAMLIGHT_TARGETBODYCOM": 4 + }, + "mjtLightType": { + "mjLIGHT_SPOT": 0, + "mjLIGHT_DIRECTIONAL": 1, + "mjLIGHT_POINT": 2, + "mjLIGHT_IMAGE": 3 + }, + "mjtTexture": { + "mjTEXTURE_2D": 0, + "mjTEXTURE_CUBE": 1, + "mjTEXTURE_SKYBOX": 2 + }, + "mjtTextureRole": { + "mjTEXROLE_USER": 0, + "mjTEXROLE_RGB": 1, + "mjTEXROLE_OCCLUSION": 2, + "mjTEXROLE_ROUGHNESS": 3, + "mjTEXROLE_METALLIC": 4, + "mjTEXROLE_NORMAL": 5, + "mjTEXROLE_OPACITY": 6, + "mjTEXROLE_EMISSIVE": 7, + "mjTEXROLE_RGBA": 8, + "mjTEXROLE_ORM": 9, + "mjNTEXROLE": 10 + }, + "mjtColorSpace": { + "mjCOLORSPACE_AUTO": 0, + "mjCOLORSPACE_LINEAR": 1, + "mjCOLORSPACE_SRGB": 2 + }, + "mjtIntegrator": { + "mjINT_EULER": 0, + "mjINT_RK4": 1, + "mjINT_IMPLICIT": 2, + "mjINT_IMPLICITFAST": 3 + }, + "mjtCone": { + "mjCONE_PYRAMIDAL": 0, + "mjCONE_ELLIPTIC": 1 + }, + "mjtJacobian": { + "mjJAC_DENSE": 0, + "mjJAC_SPARSE": 1, + "mjJAC_AUTO": 2 + }, + "mjtSolver": { + "mjSOL_PGS": 0, + "mjSOL_CG": 1, + "mjSOL_NEWTON": 2 + }, + "mjtEq": { + "mjEQ_CONNECT": 0, + "mjEQ_WELD": 1, + "mjEQ_JOINT": 2, + "mjEQ_TENDON": 3, + "mjEQ_FLEX": 4, + "mjEQ_FLEXVERT": 5, + "mjEQ_FLEXSTRAIN": 6, + "mjEQ_DISTANCE": 7 + }, + "mjtWrap": { + "mjWRAP_NONE": 0, + "mjWRAP_JOINT": 1, + "mjWRAP_PULLEY": 2, + "mjWRAP_SITE": 3, + "mjWRAP_SPHERE": 4, + "mjWRAP_CYLINDER": 5 + }, + "mjtTrn": { + "mjTRN_JOINT": 0, + "mjTRN_JOINTINPARENT": 1, + "mjTRN_SLIDERCRANK": 2, + "mjTRN_TENDON": 3, + "mjTRN_SITE": 4, + "mjTRN_BODY": 5, + "mjTRN_UNDEFINED": 1000 + }, + "mjtDyn": { + "mjDYN_NONE": 0, + "mjDYN_INTEGRATOR": 1, + "mjDYN_FILTER": 2, + "mjDYN_FILTEREXACT": 3, + "mjDYN_MUSCLE": 4, + "mjDYN_DCMOTOR": 5, + "mjDYN_USER": 6 + }, + "mjtGain": { + "mjGAIN_FIXED": 0, + "mjGAIN_AFFINE": 1, + "mjGAIN_MUSCLE": 2, + "mjGAIN_DCMOTOR": 3, + "mjGAIN_USER": 4 + }, + "mjtBias": { + "mjBIAS_NONE": 0, + "mjBIAS_AFFINE": 1, + "mjBIAS_MUSCLE": 2, + "mjBIAS_DCMOTOR": 3, + "mjBIAS_USER": 4 + }, + "mjtObj": { + "mjOBJ_UNKNOWN": 0, + "mjOBJ_BODY": 1, + "mjOBJ_XBODY": 2, + "mjOBJ_JOINT": 3, + "mjOBJ_DOF": 4, + "mjOBJ_GEOM": 5, + "mjOBJ_SITE": 6, + "mjOBJ_CAMERA": 7, + "mjOBJ_LIGHT": 8, + "mjOBJ_FLEX": 9, + "mjOBJ_MESH": 10, + "mjOBJ_SKIN": 11, + "mjOBJ_HFIELD": 12, + "mjOBJ_TEXTURE": 13, + "mjOBJ_MATERIAL": 14, + "mjOBJ_PAIR": 15, + "mjOBJ_EXCLUDE": 16, + "mjOBJ_EQUALITY": 17, + "mjOBJ_TENDON": 18, + "mjOBJ_ACTUATOR": 19, + "mjOBJ_SENSOR": 20, + "mjOBJ_NUMERIC": 21, + "mjOBJ_TEXT": 22, + "mjOBJ_TUPLE": 23, + "mjOBJ_KEY": 24, + "mjOBJ_PLUGIN": 25, + "mjNOBJECT": 26, + "mjOBJ_FRAME": 100, + "mjOBJ_DEFAULT": 101, + "mjOBJ_MODEL": 102 + }, + "mjtSensor": { + "mjSENS_TOUCH": 0, + "mjSENS_ACCELEROMETER": 1, + "mjSENS_VELOCIMETER": 2, + "mjSENS_GYRO": 3, + "mjSENS_FORCE": 4, + "mjSENS_TORQUE": 5, + "mjSENS_MAGNETOMETER": 6, + "mjSENS_RANGEFINDER": 7, + "mjSENS_CAMPROJECTION": 8, + "mjSENS_JOINTPOS": 9, + "mjSENS_JOINTVEL": 10, + "mjSENS_TENDONPOS": 11, + "mjSENS_TENDONVEL": 12, + "mjSENS_ACTUATORPOS": 13, + "mjSENS_ACTUATORVEL": 14, + "mjSENS_ACTUATORFRC": 15, + "mjSENS_JOINTACTFRC": 16, + "mjSENS_TENDONACTFRC": 17, + "mjSENS_BALLQUAT": 18, + "mjSENS_BALLANGVEL": 19, + "mjSENS_JOINTLIMITPOS": 20, + "mjSENS_JOINTLIMITVEL": 21, + "mjSENS_JOINTLIMITFRC": 22, + "mjSENS_TENDONLIMITPOS": 23, + "mjSENS_TENDONLIMITVEL": 24, + "mjSENS_TENDONLIMITFRC": 25, + "mjSENS_FRAMEPOS": 26, + "mjSENS_FRAMEQUAT": 27, + "mjSENS_FRAMEXAXIS": 28, + "mjSENS_FRAMEYAXIS": 29, + "mjSENS_FRAMEZAXIS": 30, + "mjSENS_FRAMELINVEL": 31, + "mjSENS_FRAMEANGVEL": 32, + "mjSENS_FRAMELINACC": 33, + "mjSENS_FRAMEANGACC": 34, + "mjSENS_SUBTREECOM": 35, + "mjSENS_SUBTREELINVEL": 36, + "mjSENS_SUBTREEANGMOM": 37, + "mjSENS_INSIDESITE": 38, + "mjSENS_GEOMDIST": 39, + "mjSENS_GEOMNORMAL": 40, + "mjSENS_GEOMFROMTO": 41, + "mjSENS_CONTACT": 42, + "mjSENS_E_POTENTIAL": 43, + "mjSENS_E_KINETIC": 44, + "mjSENS_CLOCK": 45, + "mjSENS_TACTILE": 46, + "mjSENS_PLUGIN": 47, + "mjSENS_USER": 48 + }, + "mjtStage": { + "mjSTAGE_NONE": 0, + "mjSTAGE_POS": 1, + "mjSTAGE_VEL": 2, + "mjSTAGE_ACC": 3 + }, + "mjtDataType": { + "mjDATATYPE_REAL": 0, + "mjDATATYPE_POSITIVE": 1, + "mjDATATYPE_AXIS": 2, + "mjDATATYPE_QUATERNION": 3 + }, + "mjtConDataField": { + "mjCONDATA_FOUND": 0, + "mjCONDATA_FORCE": 1, + "mjCONDATA_TORQUE": 2, + "mjCONDATA_DIST": 3, + "mjCONDATA_POS": 4, + "mjCONDATA_NORMAL": 5, + "mjCONDATA_TANGENT": 6, + "mjNCONDATA": 7 + }, + "mjtRayDataField": { + "mjRAYDATA_DIST": 0, + "mjRAYDATA_DIR": 1, + "mjRAYDATA_ORIGIN": 2, + "mjRAYDATA_POINT": 3, + "mjRAYDATA_NORMAL": 4, + "mjRAYDATA_DEPTH": 5, + "mjNRAYDATA": 6 + }, + "mjtCamOutBit": { + "mjCAMOUT_RGB": 1, + "mjCAMOUT_DEPTH": 2, + "mjCAMOUT_DIST": 4, + "mjCAMOUT_NORMAL": 8, + "mjCAMOUT_SEG": 16, + "mjNCAMOUT": 5 + }, + "mjtSameFrame": { + "mjSAMEFRAME_NONE": 0, + "mjSAMEFRAME_BODY": 1, + "mjSAMEFRAME_INERTIA": 2, + "mjSAMEFRAME_BODYROT": 3, + "mjSAMEFRAME_INERTIAROT": 4 + }, + "mjtSleepPolicy": { + "mjSLEEP_AUTO": 0, + "mjSLEEP_AUTO_NEVER": 1, + "mjSLEEP_AUTO_ALLOWED": 2, + "mjSLEEP_NEVER": 3, + "mjSLEEP_ALLOWED": 4, + "mjSLEEP_INIT": 5 + }, + "mjtLRMode": { + "mjLRMODE_NONE": 0, + "mjLRMODE_MUSCLE": 1, + "mjLRMODE_MUSCLEUSER": 2, + "mjLRMODE_ALL": 3 + }, + "mjtFlexSelf": { + "mjFLEXSELF_NONE": 0, + "mjFLEXSELF_NARROW": 1, + "mjFLEXSELF_BVH": 2, + "mjFLEXSELF_SAP": 3, + "mjFLEXSELF_AUTO": 4 + }, + "mjtSDFType": { + "mjSDFTYPE_SINGLE": 0, + "mjSDFTYPE_INTERSECTION": 1, + "mjSDFTYPE_MIDSURFACE": 2, + "mjSDFTYPE_COLLISION": 3 + } } } \ No newline at end of file diff --git a/Scripts/mjxmacro_snapshot.json b/Scripts/codegen/snapshots/mjxmacro_snapshot.json similarity index 69% rename from Scripts/mjxmacro_snapshot.json rename to Scripts/codegen/snapshots/mjxmacro_snapshot.json index bdfe4c1..9ce4ddb 100644 --- a/Scripts/mjxmacro_snapshot.json +++ b/Scripts/codegen/snapshots/mjxmacro_snapshot.json @@ -1,7 +1,19 @@ { "_meta": { "source": "third_party\\install\\MuJoCo\\include\\mujoco\\mjxmacro.h", - "schema_kind": "mjxmacro" + "schema_kind": "mjxmacro", + "struct_field_sources": { + "MJOPTION_FIELDS": "third_party\\install\\MuJoCo\\include\\mujoco\\mjxmacro.h", + "MJSTATISTIC_FIELDS": "third_party\\install\\MuJoCo\\include\\mujoco\\mjxmacro.h", + "MJVISUAL_GLOBAL_FIELDS": "third_party\\install\\MuJoCo\\include\\mujoco\\mjxmacro.h", + "MJVISUAL_QUALITY_FIELDS": "third_party\\install\\MuJoCo\\include\\mujoco\\mjxmacro.h", + "MJVISUAL_HEADLIGHT_FIELDS": "third_party\\install\\MuJoCo\\include\\mujoco\\mjxmacro.h", + "MJVISUAL_MAP_FIELDS": "third_party\\install\\MuJoCo\\include\\mujoco\\mjxmacro.h", + "MJVISUAL_SCALE_FIELDS": "third_party\\install\\MuJoCo\\include\\mujoco\\mjxmacro.h", + "MJVISUAL_RGBA_FIELDS": "third_party\\install\\MuJoCo\\include\\mujoco\\mjxmacro.h", + "MJSCOMPILER_FIELDS": "Scripts\\codegen\\_vendored\\mjspecmacro.h", + "MJSPEC_FIELDS": "Scripts\\codegen\\_vendored\\mjspecmacro.h" + } }, "mjmodel_pointers": { "MJMODEL_POINTERS_BODY": [ @@ -552,6 +564,24 @@ "name": "geom_gap", "outer_dim": "ngeom", "stride": "1" + }, + { + "type": "mjtNum", + "name": "geom_fluid", + "outer_dim": "ngeom", + "stride": "mjNFLUID" + }, + { + "type": "mjtNum", + "name": "geom_user", + "outer_dim": "ngeom", + "stride": "MJ_M(nuser_geom)" + }, + { + "type": "float", + "name": "geom_rgba", + "outer_dim": "ngeom", + "stride": "4" } ], "MJMODEL_POINTERS_SITE": [ @@ -1396,6 +1426,126 @@ "name": "mesh_graphadr", "outer_dim": "nmesh", "stride": "1" + }, + { + "type": "float", + "name": "mesh_vert", + "outer_dim": "nmeshvert", + "stride": "3" + }, + { + "type": "float", + "name": "mesh_normal", + "outer_dim": "nmeshnormal", + "stride": "3" + }, + { + "type": "float", + "name": "mesh_texcoord", + "outer_dim": "nmeshtexcoord", + "stride": "2" + }, + { + "type": "int", + "name": "mesh_face", + "outer_dim": "nmeshface", + "stride": "3" + }, + { + "type": "int", + "name": "mesh_facenormal", + "outer_dim": "nmeshface", + "stride": "3" + }, + { + "type": "int", + "name": "mesh_facetexcoord", + "outer_dim": "nmeshface", + "stride": "3" + }, + { + "type": "int", + "name": "mesh_graph", + "outer_dim": "nmeshgraph", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "mesh_scale", + "outer_dim": "nmesh", + "stride": "3" + }, + { + "type": "mjtNum", + "name": "mesh_pos", + "outer_dim": "nmesh", + "stride": "3" + }, + { + "type": "mjtNum", + "name": "mesh_quat", + "outer_dim": "nmesh", + "stride": "4" + }, + { + "type": "int", + "name": "mesh_pathadr", + "outer_dim": "nmesh", + "stride": "1" + }, + { + "type": "int", + "name": "mesh_polynum", + "outer_dim": "nmesh", + "stride": "1" + }, + { + "type": "int", + "name": "mesh_polyadr", + "outer_dim": "nmesh", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "mesh_polynormal", + "outer_dim": "nmeshpoly", + "stride": "3" + }, + { + "type": "int", + "name": "mesh_polyvertadr", + "outer_dim": "nmeshpoly", + "stride": "1" + }, + { + "type": "int", + "name": "mesh_polyvertnum", + "outer_dim": "nmeshpoly", + "stride": "1" + }, + { + "type": "int", + "name": "mesh_polyvert", + "outer_dim": "nmeshpolyvert", + "stride": "1" + }, + { + "type": "int", + "name": "mesh_polymapadr", + "outer_dim": "nmeshvert", + "stride": "1" + }, + { + "type": "int", + "name": "mesh_polymapnum", + "outer_dim": "nmeshvert", + "stride": "1" + }, + { + "type": "int", + "name": "mesh_polymap", + "outer_dim": "nmeshpolymap", + "stride": "1" } ], "MJMODEL_POINTERS_SKIN": [ @@ -1556,6 +1706,18 @@ "name": "hfield_adr", "outer_dim": "nhfield", "stride": "1" + }, + { + "type": "float", + "name": "hfield_data", + "outer_dim": "nhfielddata", + "stride": "1" + }, + { + "type": "int", + "name": "hfield_pathadr", + "outer_dim": "nhfield", + "stride": "1" } ], "MJMODEL_POINTERS_TEXTURE": [ @@ -1594,6 +1756,18 @@ "name": "tex_adr", "outer_dim": "ntex", "stride": "1" + }, + { + "type": "mjtByte", + "name": "tex_data", + "outer_dim": "ntexdata", + "stride": "1" + }, + { + "type": "int", + "name": "tex_pathadr", + "outer_dim": "ntex", + "stride": "1" } ], "MJMODEL_POINTERS_MATERIAL": [ @@ -2596,417 +2770,1566 @@ "name": "actuator_moment", "outer_dim": "nJmom", "stride": "1" - } - ], - "MJDATA_ARENA_POINTERS_SOLVER": [ + }, { - "type": "int", - "name": "efc_type", - "outer_dim": "MJ_D(nefc)", - "stride": "1" + "type": "mjtNum", + "name": "crb", + "outer_dim": "nbody", + "stride": "10" }, { - "type": "int", - "name": "efc_id", - "outer_dim": "MJ_D(nefc)", + "type": "mjtNum", + "name": "qM", + "outer_dim": "nM", "stride": "1" - } - ], - "MJDATA_ARENA_POINTERS_DUAL": [], - "MJDATA_ARENA_POINTERS_ISLAND": [ + }, { - "type": "int", - "name": "tree_island", - "outer_dim": "MJ_M(ntree)", + "type": "mjtNum", + "name": "M", + "outer_dim": "nC", "stride": "1" }, { - "type": "int", - "name": "island_ntree", - "outer_dim": "MJ_D(nisland)", + "type": "mjtNum", + "name": "qLD", + "outer_dim": "nC", "stride": "1" }, { - "type": "int", - "name": "island_itreeadr", - "outer_dim": "MJ_D(nisland)", + "type": "mjtNum", + "name": "qLDiagInv", + "outer_dim": "nv", "stride": "1" }, { - "type": "int", - "name": "map_itree2tree", - "outer_dim": "MJ_M(ntree)", + "type": "mjtByte", + "name": "bvh_active", + "outer_dim": "nbvh", "stride": "1" }, { "type": "int", - "name": "dof_island", - "outer_dim": "MJ_M(nv)", + "name": "tree_awake", + "outer_dim": "ntree", "stride": "1" }, { "type": "int", - "name": "island_nv", - "outer_dim": "MJ_D(nisland)", + "name": "body_awake", + "outer_dim": "nbody", "stride": "1" }, { "type": "int", - "name": "island_idofadr", - "outer_dim": "MJ_D(nisland)", + "name": "body_awake_ind", + "outer_dim": "nbody", "stride": "1" }, { "type": "int", - "name": "island_dofadr", - "outer_dim": "MJ_D(nisland)", + "name": "parent_awake_ind", + "outer_dim": "nbody", "stride": "1" }, { "type": "int", - "name": "map_dof2idof", - "outer_dim": "MJ_M(nv)", + "name": "dof_awake_ind", + "outer_dim": "nv", "stride": "1" }, { - "type": "int", - "name": "map_idof2dof", - "outer_dim": "MJ_M(nv)", + "type": "mjtNum", + "name": "flexedge_velocity", + "outer_dim": "nflexedge", "stride": "1" }, { "type": "mjtNum", - "name": "ifrc_smooth", - "outer_dim": "MJ_D(nidof)", + "name": "ten_velocity", + "outer_dim": "ntendon", "stride": "1" }, { "type": "mjtNum", - "name": "iacc_smooth", - "outer_dim": "MJ_D(nidof)", + "name": "actuator_velocity", + "outer_dim": "nu", "stride": "1" - } - ], - "MJDATA_ARENA_POINTERS": [] - }, - "struct_fields": { - "MJOPTION_FIELDS": [ + }, { "type": "mjtNum", - "name": "timestep", - "count": "1", - "is_vec": false + "name": "cvel", + "outer_dim": "nbody", + "stride": "6" }, { "type": "mjtNum", - "name": "impratio", - "count": "1", - "is_vec": false + "name": "cdof_dot", + "outer_dim": "nv", + "stride": "6" }, { "type": "mjtNum", - "name": "tolerance", - "count": "1", - "is_vec": false + "name": "qfrc_bias", + "outer_dim": "nv", + "stride": "1" }, { "type": "mjtNum", - "name": "ls_tolerance", - "count": "1", - "is_vec": false + "name": "qfrc_spring", + "outer_dim": "nv", + "stride": "1" }, { "type": "mjtNum", - "name": "noslip_tolerance", - "count": "1", - "is_vec": false + "name": "qfrc_damper", + "outer_dim": "nv", + "stride": "1" }, { "type": "mjtNum", - "name": "ccd_tolerance", - "count": "1", - "is_vec": false + "name": "qfrc_gravcomp", + "outer_dim": "nv", + "stride": "1" }, { "type": "mjtNum", - "name": "sleep_tolerance", - "count": "1", - "is_vec": false + "name": "qfrc_fluid", + "outer_dim": "nv", + "stride": "1" }, { "type": "mjtNum", - "name": "gravity", - "count": "3", - "is_vec": true + "name": "qfrc_passive", + "outer_dim": "nv", + "stride": "1" }, { "type": "mjtNum", - "name": "wind", - "count": "3", - "is_vec": true + "name": "subtree_linvel", + "outer_dim": "nbody", + "stride": "3" }, { "type": "mjtNum", - "name": "magnetic", - "count": "3", - "is_vec": true + "name": "subtree_angmom", + "outer_dim": "nbody", + "stride": "3" }, { "type": "mjtNum", - "name": "density", - "count": "1", - "is_vec": false + "name": "qH", + "outer_dim": "nC", + "stride": "1" }, { "type": "mjtNum", - "name": "viscosity", - "count": "1", - "is_vec": false + "name": "qHDiagInv", + "outer_dim": "nv", + "stride": "1" }, { "type": "mjtNum", - "name": "o_margin", - "count": "1", - "is_vec": false + "name": "qDeriv", + "outer_dim": "nD", + "stride": "1" }, { "type": "mjtNum", - "name": "o_solref", - "count": "mjNREF", - "is_vec": true + "name": "qLU", + "outer_dim": "nD", + "stride": "1" }, { "type": "mjtNum", - "name": "o_solimp", - "count": "mjNIMP", - "is_vec": true + "name": "actuator_force", + "outer_dim": "nu", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "qfrc_actuator", + "outer_dim": "nv", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "qfrc_smooth", + "outer_dim": "nv", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "qacc_smooth", + "outer_dim": "nv", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "qfrc_constraint", + "outer_dim": "nv", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "qfrc_inverse", + "outer_dim": "nv", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "cacc", + "outer_dim": "nbody", + "stride": "6" + }, + { + "type": "mjtNum", + "name": "cfrc_int", + "outer_dim": "nbody", + "stride": "6" + }, + { + "type": "mjtNum", + "name": "cfrc_ext", + "outer_dim": "nbody", + "stride": "6" + } + ], + "MJDATA_ARENA_POINTERS_SOLVER": [ + { + "type": "int", + "name": "efc_type", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "int", + "name": "efc_id", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "int", + "name": "efc_J_rownnz", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "int", + "name": "efc_J_rowadr", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "int", + "name": "efc_J_rowsuper", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "int", + "name": "efc_J_colind", + "outer_dim": "MJ_D(nJ)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "efc_J", + "outer_dim": "MJ_D(nJ)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "efc_pos", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "efc_margin", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "efc_frictionloss", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "efc_diagApprox", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "efc_KBIP", + "outer_dim": "MJ_D(nefc)", + "stride": "4" + }, + { + "type": "mjtNum", + "name": "efc_D", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "efc_R", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "int", + "name": "tendon_efcadr", + "outer_dim": "MJ_M(ntendon)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "efc_vel", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "efc_aref", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "efc_b", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "int", + "name": "efc_state", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "efc_force", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + } + ], + "MJDATA_ARENA_POINTERS_DUAL": [ + { + "type": "int", + "name": "efc_AR_rownnz", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "int", + "name": "efc_AR_rowadr", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "int", + "name": "efc_AR_colind", + "outer_dim": "MJ_D(nA)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "efc_AR", + "outer_dim": "MJ_D(nA)", + "stride": "1" + } + ], + "MJDATA_ARENA_POINTERS_ISLAND": [ + { + "type": "int", + "name": "tree_island", + "outer_dim": "MJ_M(ntree)", + "stride": "1" + }, + { + "type": "int", + "name": "island_ntree", + "outer_dim": "MJ_D(nisland)", + "stride": "1" + }, + { + "type": "int", + "name": "island_itreeadr", + "outer_dim": "MJ_D(nisland)", + "stride": "1" + }, + { + "type": "int", + "name": "map_itree2tree", + "outer_dim": "MJ_M(ntree)", + "stride": "1" + }, + { + "type": "int", + "name": "dof_island", + "outer_dim": "MJ_M(nv)", + "stride": "1" + }, + { + "type": "int", + "name": "island_nv", + "outer_dim": "MJ_D(nisland)", + "stride": "1" + }, + { + "type": "int", + "name": "island_idofadr", + "outer_dim": "MJ_D(nisland)", + "stride": "1" + }, + { + "type": "int", + "name": "island_dofadr", + "outer_dim": "MJ_D(nisland)", + "stride": "1" + }, + { + "type": "int", + "name": "map_dof2idof", + "outer_dim": "MJ_M(nv)", + "stride": "1" + }, + { + "type": "int", + "name": "map_idof2dof", + "outer_dim": "MJ_M(nv)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "ifrc_smooth", + "outer_dim": "MJ_D(nidof)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "iacc_smooth", + "outer_dim": "MJ_D(nidof)", + "stride": "1" + }, + { + "type": "int", + "name": "iM_rownnz", + "outer_dim": "MJ_D(nidof)", + "stride": "1" + }, + { + "type": "int", + "name": "iM_rowadr", + "outer_dim": "MJ_D(nidof)", + "stride": "1" + }, + { + "type": "int", + "name": "iM_colind", + "outer_dim": "MJ_M(nC)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "iM", + "outer_dim": "MJ_M(nC)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "iLD", + "outer_dim": "MJ_M(nC)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "iLDiagInv", + "outer_dim": "MJ_D(nidof)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "iacc", + "outer_dim": "MJ_D(nidof)", + "stride": "1" + }, + { + "type": "int", + "name": "efc_island", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "int", + "name": "island_ne", + "outer_dim": "MJ_D(nisland)", + "stride": "1" + }, + { + "type": "int", + "name": "island_nf", + "outer_dim": "MJ_D(nisland)", + "stride": "1" + }, + { + "type": "int", + "name": "island_nefc", + "outer_dim": "MJ_D(nisland)", + "stride": "1" + }, + { + "type": "int", + "name": "island_iefcadr", + "outer_dim": "MJ_D(nisland)", + "stride": "1" + }, + { + "type": "int", + "name": "map_efc2iefc", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "int", + "name": "map_iefc2efc", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "int", + "name": "iefc_type", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "int", + "name": "iefc_id", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "int", + "name": "iefc_J_rownnz", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "int", + "name": "iefc_J_rowadr", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "int", + "name": "iefc_J_rowsuper", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "int", + "name": "iefc_J_colind", + "outer_dim": "MJ_D(nJ)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "iefc_J", + "outer_dim": "MJ_D(nJ)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "iefc_frictionloss", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "iefc_D", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "iefc_R", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "iefc_aref", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "int", + "name": "iefc_state", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "iefc_force", + "outer_dim": "MJ_D(nefc)", + "stride": "1" + }, + { + "type": "mjtNum", + "name": "ifrc_constraint", + "outer_dim": "MJ_D(nidof)", + "stride": "1" + } + ], + "MJDATA_ARENA_POINTERS": [] + }, + "struct_fields": { + "MJOPTION_FIELDS": [ + { + "type": "mjtNum", + "name": "timestep", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "impratio", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "tolerance", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "ls_tolerance", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "noslip_tolerance", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "ccd_tolerance", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "sleep_tolerance", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "gravity", + "count": "3", + "is_vec": true + }, + { + "type": "mjtNum", + "name": "wind", + "count": "3", + "is_vec": true + }, + { + "type": "mjtNum", + "name": "magnetic", + "count": "3", + "is_vec": true + }, + { + "type": "mjtNum", + "name": "density", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "viscosity", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "o_margin", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "o_solref", + "count": "mjNREF", + "is_vec": true + }, + { + "type": "mjtNum", + "name": "o_solimp", + "count": "mjNIMP", + "is_vec": true + }, + { + "type": "mjtNum", + "name": "o_friction", + "count": "5", + "is_vec": true + }, + { + "type": "int", + "name": "integrator", + "count": "1", + "is_vec": false + }, + { + "type": "int", + "name": "cone", + "count": "1", + "is_vec": false + }, + { + "type": "int", + "name": "jacobian", + "count": "1", + "is_vec": false + }, + { + "type": "int", + "name": "solver", + "count": "1", + "is_vec": false + }, + { + "type": "int", + "name": "iterations", + "count": "1", + "is_vec": false + }, + { + "type": "int", + "name": "ls_iterations", + "count": "1", + "is_vec": false + }, + { + "type": "int", + "name": "noslip_iterations", + "count": "1", + "is_vec": false + }, + { + "type": "int", + "name": "ccd_iterations", + "count": "1", + "is_vec": false + }, + { + "type": "int", + "name": "disableflags", + "count": "1", + "is_vec": false + }, + { + "type": "int", + "name": "enableflags", + "count": "1", + "is_vec": false + }, + { + "type": "int", + "name": "disableactuator", + "count": "1", + "is_vec": false + }, + { + "type": "int", + "name": "sdf_initpoints", + "count": "1", + "is_vec": false + }, + { + "type": "int", + "name": "sdf_iterations", + "count": "1", + "is_vec": false + } + ], + "MJSTATISTIC_FIELDS": [ + { + "type": "mjtNum", + "name": "meaninertia", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "meanmass", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "meansize", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "extent", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "center", + "count": "3", + "is_vec": true + } + ], + "MJVISUAL_GLOBAL_FIELDS": [ + { + "type": "int", + "name": "cameraid", + "count": "1", + "is_vec": false + }, + { + "type": "int", + "name": "orthographic", + "count": "1", + "is_vec": false + }, + { + "type": "float", + "name": "fovy", + "count": "1", + "is_vec": false + }, + { + "type": "float", + "name": "ipd", + "count": "1", + "is_vec": false + }, + { + "type": "float", + "name": "azimuth", + "count": "1", + "is_vec": false + }, + { + "type": "float", + "name": "elevation", + "count": "1", + "is_vec": false + }, + { + "type": "float", + "name": "linewidth", + "count": "1", + "is_vec": false + }, + { + "type": "float", + "name": "glow", + "count": "1", + "is_vec": false + }, + { + "type": "float", + "name": "realtime", + "count": "1", + "is_vec": false + }, + { + "type": "int", + "name": "offwidth", + "count": "1", + "is_vec": false + }, + { + "type": "int", + "name": "offheight", + "count": "1", + "is_vec": false + }, + { + "type": "int", + "name": "ellipsoidinertia", + "count": "1", + "is_vec": false + }, + { + "type": "int", + "name": "bvactive", + "count": "1", + "is_vec": false + } + ], + "MJVISUAL_QUALITY_FIELDS": [ + { + "type": "mjtNum", + "name": "shadowsize", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "offsamples", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "numslices", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "numstacks", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "numquads", + "count": "1", + "is_vec": false + } + ], + "MJVISUAL_HEADLIGHT_FIELDS": [ + { + "type": "float", + "name": "ambient", + "count": "3", + "is_vec": true + }, + { + "type": "float", + "name": "diffuse", + "count": "3", + "is_vec": true + }, + { + "type": "float", + "name": "specular", + "count": "3", + "is_vec": true + }, + { + "type": "int", + "name": "active", + "count": "1", + "is_vec": false + } + ], + "MJVISUAL_MAP_FIELDS": [ + { + "type": "mjtNum", + "name": "stiffness", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "stiffnessrot", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "force", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "torque", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "alpha", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "fogstart", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "fogend", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "znear", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "zfar", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "haze", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "shadowclip", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "shadowscale", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "actuatortendon", + "count": "1", + "is_vec": false + } + ], + "MJVISUAL_SCALE_FIELDS": [ + { + "type": "mjtNum", + "name": "forcewidth", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "contactwidth", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "contactheight", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "connect", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "com", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "camera", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "light", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "selectpoint", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "jointlength", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "jointwidth", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "actuatorlength", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "actuatorwidth", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "framelength", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "framewidth", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "constraint", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "slidercrank", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "frustum", + "count": "1", + "is_vec": false + } + ], + "MJVISUAL_RGBA_FIELDS": [ + { + "type": "mjtNum", + "name": "fog", + "count": "1", + "is_vec": false }, { "type": "mjtNum", - "name": "o_friction", - "count": "5", - "is_vec": true + "name": "haze", + "count": "1", + "is_vec": false }, { - "type": "int", - "name": "integrator", + "type": "mjtNum", + "name": "force", "count": "1", "is_vec": false }, { - "type": "int", - "name": "cone", + "type": "mjtNum", + "name": "inertia", "count": "1", "is_vec": false }, { - "type": "int", - "name": "jacobian", + "type": "mjtNum", + "name": "joint", "count": "1", "is_vec": false }, { - "type": "int", - "name": "solver", + "type": "mjtNum", + "name": "actuator", "count": "1", "is_vec": false }, { - "type": "int", - "name": "iterations", + "type": "mjtNum", + "name": "actuatornegative", "count": "1", "is_vec": false }, { - "type": "int", - "name": "ls_iterations", + "type": "mjtNum", + "name": "actuatorpositive", "count": "1", "is_vec": false }, { - "type": "int", - "name": "noslip_iterations", + "type": "mjtNum", + "name": "com", "count": "1", "is_vec": false }, { - "type": "int", - "name": "ccd_iterations", + "type": "mjtNum", + "name": "camera", "count": "1", "is_vec": false }, { - "type": "int", - "name": "disableflags", + "type": "mjtNum", + "name": "light", "count": "1", "is_vec": false }, { - "type": "int", - "name": "enableflags", + "type": "mjtNum", + "name": "selectpoint", "count": "1", "is_vec": false }, { - "type": "int", - "name": "disableactuator", + "type": "mjtNum", + "name": "connect", "count": "1", "is_vec": false }, { - "type": "int", - "name": "sdf_initpoints", + "type": "mjtNum", + "name": "contactpoint", "count": "1", "is_vec": false }, { - "type": "int", - "name": "sdf_iterations", + "type": "mjtNum", + "name": "contactforce", "count": "1", "is_vec": false - } - ], - "MJSTATISTIC_FIELDS": [ + }, { "type": "mjtNum", - "name": "meaninertia", + "name": "contactfriction", "count": "1", "is_vec": false }, { "type": "mjtNum", - "name": "meanmass", + "name": "contacttorque", "count": "1", "is_vec": false }, { "type": "mjtNum", - "name": "meansize", + "name": "contactgap", "count": "1", "is_vec": false }, { "type": "mjtNum", - "name": "extent", + "name": "rangefinder", "count": "1", "is_vec": false }, { "type": "mjtNum", - "name": "center", + "name": "constraint", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "slidercrank", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "crankbroken", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "frustum", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "bv", + "count": "1", + "is_vec": false + }, + { + "type": "mjtNum", + "name": "bvactive", + "count": "1", + "is_vec": false + } + ], + "MJSCOMPILER_FIELDS": [ + { + "type": "mjtByte", + "name": "autolimits", + "count": "1", + "is_vec": false + }, + { + "type": "double", + "name": "boundmass", + "count": "1", + "is_vec": false + }, + { + "type": "double", + "name": "boundinertia", + "count": "1", + "is_vec": false + }, + { + "type": "double", + "name": "settotalmass", + "count": "1", + "is_vec": false + }, + { + "type": "mjtByte", + "name": "balanceinertia", + "count": "1", + "is_vec": false + }, + { + "type": "mjtByte", + "name": "fitaabb", + "count": "1", + "is_vec": false + }, + { + "type": "mjtByte", + "name": "degree", + "count": "1", + "is_vec": false + }, + { + "type": "char", + "name": "eulerseq", "count": "3", "is_vec": true + }, + { + "type": "mjtByte", + "name": "discardvisual", + "count": "1", + "is_vec": false + }, + { + "type": "mjtByte", + "name": "usethread", + "count": "1", + "is_vec": false + }, + { + "type": "mjtByte", + "name": "fusestatic", + "count": "1", + "is_vec": false + }, + { + "type": "int", + "name": "inertiafromgeom", + "count": "1", + "is_vec": false + }, + { + "type": "int", + "name": "inertiagrouprange", + "count": "2", + "is_vec": true + }, + { + "type": "mjtByte", + "name": "saveinertial", + "count": "1", + "is_vec": false + }, + { + "type": "int", + "name": "alignfree", + "count": "1", + "is_vec": false + }, + { + "type": "mjLROpt", + "name": "LRopt", + "count": "1", + "is_vec": false + }, + { + "type": "mjString*", + "name": "meshdir", + "count": "1", + "is_vec": false + }, + { + "type": "mjString*", + "name": "texturedir", + "count": "1", + "is_vec": false } ], - "MJVISUAL_GLOBAL_FIELDS": [ + "MJSPEC_FIELDS": [ + { + "type": "mjsElement*", + "name": "element", + "count": "1", + "is_vec": false + }, + { + "type": "mjString*", + "name": "modelname", + "count": "1", + "is_vec": false + }, + { + "type": "mjsCompiler", + "name": "compiler", + "count": "1", + "is_vec": false + }, + { + "type": "mjtByte", + "name": "strippath", + "count": "1", + "is_vec": false + }, + { + "type": "mjOption", + "name": "option", + "count": "1", + "is_vec": false + }, + { + "type": "mjVisual", + "name": "visual", + "count": "1", + "is_vec": false + }, + { + "type": "mjStatistic", + "name": "stat", + "count": "1", + "is_vec": false + }, + { + "type": "mjtSize", + "name": "memory", + "count": "1", + "is_vec": false + }, { "type": "int", - "name": "cameraid", + "name": "nemax", "count": "1", "is_vec": false }, { "type": "int", - "name": "orthographic", + "name": "nuserdata", "count": "1", "is_vec": false }, { - "type": "float", - "name": "fovy", + "type": "int", + "name": "nuser_body", "count": "1", "is_vec": false }, { - "type": "float", - "name": "ipd", + "type": "int", + "name": "nuser_jnt", "count": "1", "is_vec": false }, { - "type": "float", - "name": "azimuth", + "type": "int", + "name": "nuser_geom", "count": "1", "is_vec": false }, { - "type": "float", - "name": "elevation", + "type": "int", + "name": "nuser_site", "count": "1", "is_vec": false }, { - "type": "float", - "name": "linewidth", + "type": "int", + "name": "nuser_cam", "count": "1", "is_vec": false }, { - "type": "float", - "name": "glow", + "type": "int", + "name": "nuser_tendon", "count": "1", "is_vec": false }, { - "type": "float", - "name": "realtime", + "type": "int", + "name": "nuser_actuator", "count": "1", "is_vec": false }, { "type": "int", - "name": "offwidth", + "name": "nuser_sensor", "count": "1", "is_vec": false }, { "type": "int", - "name": "offheight", + "name": "nkey", "count": "1", "is_vec": false }, { "type": "int", - "name": "ellipsoidinertia", + "name": "njmax", "count": "1", "is_vec": false }, { "type": "int", - "name": "bvactive", + "name": "nconmax", "count": "1", "is_vec": false - } - ], - "MJVISUAL_QUALITY_FIELDS": [], - "MJVISUAL_HEADLIGHT_FIELDS": [ + }, { - "type": "float", - "name": "ambient", - "count": "3", - "is_vec": true + "type": "mjtSize", + "name": "nstack", + "count": "1", + "is_vec": false }, { - "type": "float", - "name": "diffuse", - "count": "3", - "is_vec": true + "type": "mjString*", + "name": "comment", + "count": "1", + "is_vec": false }, { - "type": "float", - "name": "specular", - "count": "3", - "is_vec": true + "type": "mjString*", + "name": "modelfiledir", + "count": "1", + "is_vec": false }, { - "type": "int", - "name": "active", + "type": "mjtByte", + "name": "hasImplicitPluginElem", "count": "1", "is_vec": false } - ], - "MJVISUAL_MAP_FIELDS": [], - "MJVISUAL_SCALE_FIELDS": [], - "MJVISUAL_RGBA_FIELDS": [] + ] } } \ No newline at end of file diff --git a/Scripts/codegen/sync_vendored.py b/Scripts/codegen/sync_vendored.py new file mode 100644 index 0000000..f863bec --- /dev/null +++ b/Scripts/codegen/sync_vendored.py @@ -0,0 +1,165 @@ +# Copyright (c) 2026 Jonathan Embley-Riches. All rights reserved. +""" +Refresh vendored third-party files listed in +``Scripts/codegen/_vendored/_VENDORED_FROM.md``. + +Manifest format: GitHub-flavoured markdown table with columns +``file | upstream_url | upstream_sha | retrieved_date | license | local_dest``. +``upstream_url`` may contain ``{sha}`` which gets substituted with +``upstream_sha`` at fetch time. + +Re-running on the same SHAs produces zero diff in the manifest (the +script rewrites the table with stable column ordering + sorted-by-dest +rows, and re-stamps ``retrieved_date`` only when the fetch changed the +file content). + +Usage: + python Scripts/codegen/sync_vendored.py + [--manifest Scripts/codegen/_vendored/_VENDORED_FROM.md] + [--dry-run] (don't write anything; print what would happen) +""" + +from __future__ import annotations + +import argparse +import datetime as _dt +import hashlib +import os +import re +import sys +import urllib.request +from typing import Dict, List + +_HERE = os.path.dirname(os.path.abspath(__file__)) +_PLUGIN_ROOT = os.path.normpath(os.path.join(_HERE, "..", "..")) +_DEFAULT_MANIFEST = os.path.join(_HERE, "_vendored", "_VENDORED_FROM.md") + + +# Markdown-table row: pipe-separated, with leading + trailing pipes +# trimmed. Comments / preamble paragraphs are ignored. +_ROW_RE = re.compile(r"^\s*\|(?P.+)\|\s*$") + + +def _parse_manifest(text: str) -> List[Dict[str, str]]: + """Return the table rows as dicts keyed by column header. Skips the + header row and the markdown separator row (``|---|---|...``).""" + rows: List[Dict[str, str]] = [] + header: List[str] = [] + for line in text.splitlines(): + m = _ROW_RE.match(line) + if not m: + continue + cols = [c.strip() for c in m.group("row").split("|")] + if not header: + header = cols + continue + if all(c.startswith("-") or c == "" for c in cols): + continue # separator + if len(cols) != len(header): + continue # malformed; ignore quietly + rows.append(dict(zip(header, cols))) + return rows + + +_COL_ORDER = ("file", "upstream_url", "upstream_sha", "retrieved_date", + "license", "local_dest") + + +def _format_manifest(rows: List[Dict[str, str]], preamble: str) -> str: + """Render the table with stable column ordering + sorted-by-dest rows.""" + rows = sorted(rows, key=lambda r: r.get("local_dest", "")) + header = " | ".join(_COL_ORDER) + sep = " | ".join("-" * max(3, len(c)) for c in _COL_ORDER) + lines = [f"| {header} |", f"| {sep} |"] + for r in rows: + cells = [r.get(c, "") for c in _COL_ORDER] + lines.append("| " + " | ".join(cells) + " |") + return preamble.rstrip() + "\n\n" + "\n".join(lines) + "\n" + + +def _extract_preamble(text: str) -> str: + """Strip everything from the first table row onward.""" + lines = text.splitlines() + out: List[str] = [] + for line in lines: + if _ROW_RE.match(line): + break + out.append(line) + return "\n".join(out) + + +def _fetch(url: str, sha: str) -> bytes: + real_url = url.replace("{sha}", sha) + print(f" GET {real_url}", file=sys.stderr) + req = urllib.request.Request(real_url, headers={"User-Agent": "urlab-sync_vendored"}) + with urllib.request.urlopen(req, timeout=30) as resp: # nosec: trusted manifest URLs + return resp.read() + + +def _maybe_write(path: str, content: bytes, dry_run: bool) -> bool: + """Returns True if the file content changed.""" + existing = None + if os.path.exists(path): + with open(path, "rb") as f: + existing = f.read() + if existing == content: + return False + if dry_run: + print(f" WOULD WRITE {path} ({len(content)} bytes)") + return True + os.makedirs(os.path.dirname(path), exist_ok=True) + with open(path, "wb") as f: + f.write(content) + print(f" WROTE {path} ({len(content)} bytes; sha256=" + f"{hashlib.sha256(content).hexdigest()[:12]})") + return True + + +def main(argv: List[str] | None = None) -> int: + ap = argparse.ArgumentParser(description=__doc__) + ap.add_argument("--manifest", default=_DEFAULT_MANIFEST) + ap.add_argument("--dry-run", action="store_true", + help="don't write any files; print what would happen") + args = ap.parse_args(argv) + + if not os.path.exists(args.manifest): + print(f"manifest not found: {args.manifest}", file=sys.stderr) + return 1 + + with open(args.manifest, "r", encoding="utf-8") as f: + text = f.read() + preamble = _extract_preamble(text) + rows = _parse_manifest(text) + + today = _dt.date.today().isoformat() + updated_rows: List[Dict[str, str]] = [] + for row in rows: + url = row.get("upstream_url", "") + sha = row.get("upstream_sha", "") + dest_rel = row.get("local_dest", "") + if not (url and sha and dest_rel): + print(f"skipping malformed row: {row}", file=sys.stderr) + updated_rows.append(row) + continue + try: + content = _fetch(url, sha) + except Exception as exc: # noqa: BLE001 + print(f" FAILED to fetch {url} @ {sha}: {exc}", file=sys.stderr) + updated_rows.append(row) + continue + dest_abs = os.path.join(_PLUGIN_ROOT, dest_rel.replace("/", os.sep)) + changed = _maybe_write(dest_abs, content, args.dry_run) + if changed and not args.dry_run: + row["retrieved_date"] = today + updated_rows.append(row) + + new_text = _format_manifest(updated_rows, preamble) + if new_text != text and not args.dry_run: + with open(args.manifest, "w", encoding="utf-8") as f: + f.write(new_text) + print(f"updated manifest: {args.manifest}") + return 0 + + +if __name__ == "__main__": + raise SystemExit(main()) diff --git a/Scripts/codegen/tests/conftest.py b/Scripts/codegen/tests/conftest.py index 1d55e7b..b4a08a0 100644 --- a/Scripts/codegen/tests/conftest.py +++ b/Scripts/codegen/tests/conftest.py @@ -24,7 +24,7 @@ @pytest.fixture(scope="session") def real_schema() -> Dict[str, Any]: """The actual MJCF schema snapshot shipped with the plugin.""" - path = os.path.join(_PLUGIN_ROOT, "Scripts", "mjcf_schema_snapshot.json") + path = os.path.join(_PLUGIN_ROOT, "Scripts", "codegen", "snapshots", "mjcf_schema_snapshot.json") with open(path, "r", encoding="utf-8") as f: return json.load(f) @@ -38,7 +38,7 @@ def real_rules() -> Dict[str, Any]: @pytest.fixture(scope="session") def real_mjxmacro() -> Dict[str, Any]: - path = os.path.join(_PLUGIN_ROOT, "Scripts", "mjxmacro_snapshot.json") + path = os.path.join(_PLUGIN_ROOT, "Scripts", "codegen", "snapshots", "mjxmacro_snapshot.json") with open(path, "r", encoding="utf-8") as f: return json.load(f) diff --git a/Scripts/codegen/tests/test_dry_run.py b/Scripts/codegen/tests/test_dry_run.py index 3f1eb7b..8bd1963 100644 --- a/Scripts/codegen/tests/test_dry_run.py +++ b/Scripts/codegen/tests/test_dry_run.py @@ -17,7 +17,7 @@ @pytest.fixture(scope="session") def real_mjspec(): - with open(os.path.join(_PLUGIN_ROOT, "Scripts", "mjspec_snapshot.json"), "r") as f: + with open(os.path.join(_PLUGIN_ROOT, "Scripts", "codegen", "snapshots", "mjspec_snapshot.json"), "r") as f: return json.load(f) diff --git a/Scripts/codegen/tests/test_enum_scrape.py b/Scripts/codegen/tests/test_enum_scrape.py new file mode 100644 index 0000000..7b77f65 --- /dev/null +++ b/Scripts/codegen/tests/test_enum_scrape.py @@ -0,0 +1,156 @@ +# Copyright (c) 2026 Jonathan Embley-Riches. All rights reserved. +""" +Tests for the typedef-enum extractor in build_mjspec_snapshot.py. + +Phase 2d-1: regex scrape of mjmodel.h ``typedef enum mjtX_ { ... } mjtX;`` +blocks. Output lands under ``"enums"`` in mjspec_snapshot.json and feeds +Phase 2c's ``value_map_from_enum`` resolver. + +Vendored mjspecmacro.h, clang AST traversal, and per-field doc comments +are deferred to Phase 2d-2 / 2d-3 (only if Phase 2e actually needs them). +""" + +from __future__ import annotations + +import os +import sys + +_HERE = os.path.dirname(os.path.abspath(__file__)) +_CODEGEN_DIR = os.path.dirname(_HERE) +if _CODEGEN_DIR not in sys.path: + sys.path.insert(0, _CODEGEN_DIR) + +from build_mjspec_snapshot import parse_enums # noqa: E402 + + +_FAKE_HEADER = r""" +// Some unrelated declarations. +struct SomeStruct { int x; }; + +typedef enum mjtJoint_ { // type of degree of freedom + mjJNT_FREE = 0, // 7 dofs + mjJNT_BALL, // 4 dofs + mjJNT_SLIDE, // 1 dof + mjJNT_HINGE // 1 dof +} mjtJoint; + +typedef enum mjtGeom_ { + mjGEOM_PLANE = 0, + mjGEOM_HFIELD, + mjGEOM_SPHERE, + + mjNGEOMTYPES, // counter sentinel; auto = 3 + + mjGEOM_ARROW = 100, + mjGEOM_ARROW1, // 101 + mjGEOM_NONE = 1001 +} mjtGeom; + +typedef enum mjtBitFlag_ { + mjBIT_A = 1 << 0, + mjBIT_B = 1 << 1, +} mjtBitFlag; +""" + + +def test_basic_enum_with_auto_increment(): + enums = parse_enums(_FAKE_HEADER) + assert enums["mjtJoint"] == { + "mjJNT_FREE": 0, + "mjJNT_BALL": 1, + "mjJNT_SLIDE": 2, + "mjJNT_HINGE": 3, + } + + +def test_explicit_overrides_reset_counter(): + enums = parse_enums(_FAKE_HEADER) + # mjGEOM_PLANE explicitly = 0; HFIELD/SPHERE follow; mjNGEOMTYPES auto = 3; + # mjGEOM_ARROW explicitly = 100; mjGEOM_ARROW1 = 101; mjGEOM_NONE = 1001. + assert enums["mjtGeom"]["mjGEOM_PLANE"] == 0 + assert enums["mjtGeom"]["mjGEOM_HFIELD"] == 1 + assert enums["mjtGeom"]["mjGEOM_SPHERE"] == 2 + assert enums["mjtGeom"]["mjNGEOMTYPES"] == 3 + assert enums["mjtGeom"]["mjGEOM_ARROW"] == 100 + assert enums["mjtGeom"]["mjGEOM_ARROW1"] == 101 + assert enums["mjtGeom"]["mjGEOM_NONE"] == 1001 + + +def test_bitshift_expressions_resolve(): + """``1 << 0`` / ``1 << 1`` are non-int-literal but eval cleanly in the + sandbox. The extractor handles this so URLab's bitflag enums (e.g. + mjtDisableBit, mjtEnableBit) come through with the right values.""" + enums = parse_enums(_FAKE_HEADER) + assert enums["mjtBitFlag"] == {"mjBIT_A": 1, "mjBIT_B": 2} + + +def test_non_mjt_enums_skipped(): + """Only typedef enums whose tag matches ``mjt\\w+`` are captured. The + snapshot is scoped to enums URLab might map through xml_enum_attrs; + private/internal enums (e.g. tinyxml2's) stay out of the snapshot.""" + src = r""" + typedef enum NotMine_ { FOO = 0 } NotMine; + typedef enum mjtThing_ { mjT_X = 0 } mjtThing; + """ + enums = parse_enums(src) + assert "NotMine" not in enums + assert "mjtThing" in enums + + +def test_real_snapshot_has_expected_enums(): + """End-to-end: the shipped mjspec_snapshot.json should carry the enums + Phase 2c's value_map_from_enum needs. These are the enums likely to be + referenced by xml_enum_attrs rules in Phase 2e / 5.""" + import json + plugin_root = os.path.normpath(os.path.join(_HERE, "..", "..", "..")) + snap = json.load(open(os.path.join(plugin_root, "Scripts", "codegen", "snapshots", "mjspec_snapshot.json"))) + enums = snap.get("enums", {}) + for expected in ( + "mjtJoint", # joint.type + "mjtGeom", # geom.type + "mjtSensor", # sensor types + "mjtObj", # objtype / reftype + "mjtTrn", # actuator transmission + "mjtIntegrator", # mjOption.integrator (Phase 2e synthetic_categories) + "mjtCone", # mjOption.cone + "mjtSolver", # mjOption.solver + ): + assert expected in enums, f"missing enum {expected} from snapshot" + assert len(enums[expected]) > 0, f"enum {expected} has no members" + + +def test_value_map_from_enum_resolves_with_real_snapshot(): + """Wire the 2c resolver to the real snapshot and confirm it builds a + sensible value_map. Catches drift between mjmodel.h enum names and + rule-side ue_member_from_mj / xml_from_mj tables.""" + import json + from generate_ue_components import _resolve_value_map # noqa: E501 + + plugin_root = os.path.normpath(os.path.join(_HERE, "..", "..", "..")) + snap = json.load(open(os.path.join(plugin_root, "Scripts", "codegen", "snapshots", "mjspec_snapshot.json"))) + + enum_def = { + "ue_property": "Type", + "ue_enum_type": "EMjJointType", + "value_map_from_enum": "mjtJoint", + "ue_member_from_mj": { + "mjJNT_FREE": "Free", + "mjJNT_BALL": "Ball", + "mjJNT_SLIDE": "Slide", + "mjJNT_HINGE": "Hinge", + }, + "xml_from_mj": { + "mjJNT_FREE": "free", + "mjJNT_BALL": "ball", + "mjJNT_SLIDE": "slide", + "mjJNT_HINGE": "hinge", + }, + } + resolved = _resolve_value_map("type", enum_def, snap) + # Mapping order follows snapshot's enum iteration order. + assert resolved == { + "free": ["Free", "mjJNT_FREE"], + "ball": ["Ball", "mjJNT_BALL"], + "slide": ["Slide", "mjJNT_SLIDE"], + "hinge": ["Hinge", "mjJNT_HINGE"], + } diff --git a/Scripts/codegen/tests/test_introspect_snapshot.py b/Scripts/codegen/tests/test_introspect_snapshot.py new file mode 100644 index 0000000..2f3d83c --- /dev/null +++ b/Scripts/codegen/tests/test_introspect_snapshot.py @@ -0,0 +1,72 @@ +# Copyright (c) 2026 Jonathan Embley-Riches. All rights reserved. +""" +Smoke tests for the clang-AST introspect snapshot. + +Skipped automatically when libclang isn't available (e.g. CI runners +without the package). The real validation happens on the committed +``Scripts/introspect_snapshot.json`` itself — these tests just spot-check +that schema-evolution surprises don't slip through. +""" + +from __future__ import annotations + +import json +import os + +import pytest + +_HERE = os.path.dirname(os.path.abspath(__file__)) +_PLUGIN_ROOT = os.path.normpath(os.path.join(_HERE, "..", "..", "..")) +_SNAPSHOT = os.path.join(_PLUGIN_ROOT, "Scripts", "codegen", "snapshots", "introspect_snapshot.json") + + +def _load() -> dict: + if not os.path.exists(_SNAPSHOT): + pytest.skip("introspect_snapshot.json not built yet; run " + "build_introspect_snapshot.py") + with open(_SNAPSHOT, "r", encoding="utf-8") as f: + return json.load(f) + + +def test_snapshot_has_known_mjs_functions(): + snap = _load() + fns = snap["functions"] + # mjs_addBody is one of the canonical mjsX constructors. If the + # scraper missed it, the schema-evolution audit is broken. + assert "mjs_addBody" in fns, list(fns)[:5] + body_fn = fns["mjs_addBody"] + # Body takes (mjsBody* body) as first arg per upstream API. + assert body_fn["return_type"].endswith("mjsBody *") or body_fn["return_type"] == "mjsBody *" + assert any("body" in (p["c_type"].lower()) for p in body_fn["params"]) + + +def test_snapshot_has_known_enums(): + snap = _load() + enums = snap["enums"] + for expected in ("mjtJoint", "mjtGeom", "mjtSensor", "mjtObj"): + assert expected in enums, expected + members = enums[expected]["members"] + assert len(members) > 0 + + +def test_snapshot_has_known_structs(): + snap = _load() + structs = snap["structs"] + # mjsBody is the canonical spec struct; mjStatistic is one of the + # synthetic_categories pilots' c_struct_type targets. + assert any(name in structs for name in ("mjsBody_", "mjsBody")) + + +def test_snapshot_has_known_defines(): + snap = _load() + defs = snap["defines"] + for expected in ("mjNREF", "mjNIMP", "mjMAXVAL", "mjPI"): + assert expected in defs, expected + + +def test_header_hash_present_and_stable(): + snap = _load() + assert "_meta" in snap + assert snap["_meta"]["snapshot_version"] >= 1 + h = snap["_meta"]["header_hash"] + assert len(h) == 64 # SHA-256 hex diff --git a/Scripts/codegen/tests/test_mjxmacro_snapshot.py b/Scripts/codegen/tests/test_mjxmacro_snapshot.py new file mode 100644 index 0000000..301a3f9 --- /dev/null +++ b/Scripts/codegen/tests/test_mjxmacro_snapshot.py @@ -0,0 +1,128 @@ +# Copyright (c) 2026 Jonathan Embley-Riches. All rights reserved. +"""Tests for the mjxmacro snapshot parser. + +The XNV-accepting regex was added after a silent-drop bug — every entry +listed AFTER an XNV line in the same block (e.g. ``geom_user``, ``geom_rgba`` +after ``XNV(mjtNum, geom_fluid, ...)`` in MJMODEL_POINTERS_GEOM) was +discarded because the body-collector treated XNV as a non-entry sentinel +and stopped the loop. These tests pin the regex behaviour so adding a +new tag is a deliberate change with a test failure to acknowledge. +""" + +from __future__ import annotations + +import textwrap + +from build_mjxmacro_snapshot import ( + _BODY_ENTRY_RE, + _X_ENTRY_RE, + _X_TAG_RE, + _parse_block_body, + _parse_pointer_entry, +) + + +# --------------------------------------------------------------------------- +# Regex behaviour +# --------------------------------------------------------------------------- + +def test_x_tag_re_accepts_known_tags(): + """X, XVEC, XNV are the three macro tags MuJoCo uses today.""" + import re + rx = re.compile(rf"^{_X_TAG_RE}$") + assert rx.match("X") + assert rx.match("XVEC") + assert rx.match("XNV") + # Future tags should fail until added (the failure is the canary). + assert not rx.match("XSEG") + assert not rx.match("XMODEL") + + +def test_body_entry_re_matches_all_three_tags(): + assert _BODY_ENTRY_RE.match(" X ( int, foo, nfoo, 1 )") + assert _BODY_ENTRY_RE.match(" XVEC( mjtNum, bar, nbar, 3 )") + assert _BODY_ENTRY_RE.match(" XNV ( mjtNum, baz, nbaz, mjNFLUID )") + # Tags that look similar but aren't in the set. + assert not _BODY_ENTRY_RE.match(" X3 ( ... )") + + +def test_x_entry_re_captures_payload_for_all_tags(): + m = _X_ENTRY_RE.match(" XNV ( mjtNum, geom_fluid, ngeom, mjNFLUID ) \\") + assert m + assert "geom_fluid" in m.group(1) + m2 = _X_ENTRY_RE.match(" X ( int, geom_type, ngeom, 1 ) \\") + assert m2 + assert "geom_type" in m2.group(1) + + +# --------------------------------------------------------------------------- +# End-to-end block parsing — the bug that motivated this file +# --------------------------------------------------------------------------- + +def _block_lines(block_body: str) -> list: + """Strip the leading newline + dedent so test bodies read naturally.""" + return textwrap.dedent(block_body).strip("\n").split("\n") + + +def test_block_body_does_not_stop_at_xnv(): + """The original regex matched (X|XVEC) only; XNV broke the body collector + so every subsequent entry in the block was silently dropped. This pins + the behaviour so MJMODEL_POINTERS_GEOM can never lose geom_user / + geom_rgba again.""" + lines = _block_lines(""" + X ( int, geom_type, ngeom, 1 ) + XNV ( mjtNum, geom_fluid, ngeom, mjNFLUID ) + X ( mjtNum, geom_user, ngeom, MJ_M(nuser_geom) ) + X ( float, geom_rgba, ngeom, 4 ) + """) + entries = _parse_block_body(lines, 0) + assert len(entries) == 4, "XNV must not abort the body collector" + parsed = [_parse_pointer_entry(e) for e in entries] + names = [p["name"] for p in parsed if p] + assert names == ["geom_type", "geom_fluid", "geom_user", "geom_rgba"] + + +def test_parse_pointer_entry_for_xnv(): + """XNV entries parse as 4-tuples identical to X entries.""" + entry = _parse_pointer_entry("XNV ( mjtNum, geom_fluid, ngeom, mjNFLUID )") + assert entry == { + "type": "mjtNum", + "name": "geom_fluid", + "outer_dim": "ngeom", + "stride": "mjNFLUID", + } + + +# --------------------------------------------------------------------------- +# Two-source fold-in: mjxmacro.h + mjspecmacro.h => one snapshot +# --------------------------------------------------------------------------- + +def test_shipped_snapshot_has_struct_field_sources(real_mjxmacro): + """The snapshot writer should record which header each struct-field + block came from so consumers can tell mjmodel-side from mjspec-side.""" + meta = real_mjxmacro.get("_meta", {}) + sources = meta.get("struct_field_sources") + assert isinstance(sources, dict) and sources, ( + "expected _meta.struct_field_sources to be populated" + ) + + +def test_shipped_snapshot_attributes_mjspec_blocks_to_mjspecmacro(real_mjxmacro): + """MJSCOMPILER_FIELDS + MJSPEC_FIELDS must come from mjspecmacro.h, + not mjxmacro.h — they only exist in the spec header.""" + sources = real_mjxmacro["_meta"]["struct_field_sources"] + for block in ("MJSCOMPILER_FIELDS", "MJSPEC_FIELDS"): + assert block in sources, f"snapshot missing {block} source attribution" + assert "mjspecmacro.h" in sources[block], ( + f"{block} should be sourced from mjspecmacro.h, got {sources[block]!r}" + ) + + +def test_shipped_snapshot_attributes_mjoption_blocks_to_mjxmacro(real_mjxmacro): + """MJOPTION_FIELDS / MJSTATISTIC_FIELDS live in mjxmacro.h.""" + sources = real_mjxmacro["_meta"]["struct_field_sources"] + for block in ("MJOPTION_FIELDS", "MJSTATISTIC_FIELDS"): + assert block in sources, f"snapshot missing {block} source attribution" + assert "mjxmacro.h" in sources[block], ( + f"{block} should be sourced from mjxmacro.h, got {sources[block]!r}" + ) diff --git a/Scripts/codegen/tests/test_new_rule_shapes.py b/Scripts/codegen/tests/test_new_rule_shapes.py new file mode 100644 index 0000000..3f94b0c --- /dev/null +++ b/Scripts/codegen/tests/test_new_rule_shapes.py @@ -0,0 +1,375 @@ +# Copyright (c) 2026 Jonathan Embley-Riches. All rights reserved. +"""Unit tests for the v8/v9 rule shapes introduced during the codegen +overhaul: objtype_dispatch, geom_final_type, fully_emitted (banner +overwrite + safety audit), property_default (with cross-check), and +_guarded_export(multiline=True). + +Each test runs in isolation against ``_DIAGS`` so it can assert on +diagnostics without leaking state. +""" + +from __future__ import annotations + +import pytest + +import generate_ue_components as gen +from generate_ue_components import ( + _emit_objtype_dispatch_block, + _emit_geom_final_type_block, + _guarded_export, + _audit_banner_safety, +) + + +@pytest.fixture(autouse=True) +def _clear_diags(): + """Each test starts with a clean diagnostics buffer + strict counter.""" + gen._DIAGS.clear() + gen._STRICT_DIAGS_FIRED[0] = 0 + yield + gen._DIAGS.clear() + gen._STRICT_DIAGS_FIRED[0] = 0 + + +# ---------- objtype_dispatch ------------------------------------------------- + +def test_objtype_dispatch_emits_switch_with_default(): + cat_rules = { + "type_enum_name": "EMjEqualityType", + "objtype_dispatch": { + "discriminator": "Type", + "target": "Element->objtype", + "default": "mjOBJ_UNKNOWN", + "cases": [ + {"keys": ["Connect", "Weld"], "expr": "mjOBJ_BODY"}, + {"keys": ["Joint"], "expr": "mjOBJ_JOINT"}, + ], + }, + } + out = _emit_objtype_dispatch_block(cat_rules) + assert "switch (Type)" in out + assert "case EMjEqualityType::Connect:" in out + assert "case EMjEqualityType::Weld:" in out + assert "Element->objtype = mjOBJ_BODY;" in out + assert "case EMjEqualityType::Joint:" in out + assert "Element->objtype = mjOBJ_JOINT;" in out + assert "default:" in out + assert "Element->objtype = mjOBJ_UNKNOWN;" in out + assert len(gen._DIAGS) == 0 + + +def test_objtype_dispatch_returns_none_when_no_rule(): + assert _emit_objtype_dispatch_block({}) is None + assert len(gen._DIAGS) == 0 + + +def test_objtype_dispatch_diagnoses_missing_type_enum_name(): + out = _emit_objtype_dispatch_block({ + "objtype_dispatch": { + "discriminator": "Type", + "target": "Element->objtype", + "cases": [{"keys": ["A"], "expr": "X"}], + }, + }) + assert out is None + assert any("type_enum_name" in d.message for d in gen._DIAGS) + + +def test_objtype_dispatch_diagnoses_empty_cases(): + out = _emit_objtype_dispatch_block({ + "type_enum_name": "EMjEqualityType", + "objtype_dispatch": { + "discriminator": "Type", + "target": "Element->objtype", + "cases": [], + }, + }) + assert out is None + assert any("no cases" in d.message for d in gen._DIAGS) + + +def test_objtype_dispatch_diagnoses_empty_keys(): + out = _emit_objtype_dispatch_block({ + "type_enum_name": "EMjEqualityType", + "objtype_dispatch": { + "discriminator": "Type", + "target": "Element->objtype", + "cases": [{"keys": [], "expr": "mjOBJ_BODY"}], + }, + }) + assert out is None + assert any("empty" in d.message and "keys" in d.message + for d in gen._DIAGS) + + +def test_objtype_dispatch_diagnoses_missing_expr(): + out = _emit_objtype_dispatch_block({ + "type_enum_name": "EMjEqualityType", + "objtype_dispatch": { + "discriminator": "Type", + "target": "Element->objtype", + "cases": [{"keys": ["Connect"]}], + }, + }) + assert out is None + assert any("missing 'expr'" in d.message for d in gen._DIAGS) + + +# ---------- geom_final_type -------------------------------------------------- + +def _geom_value_map_rules(): + """Minimal cat/element rules that exercise the FinalType switch.""" + cat_rules = { + "geom_final_type": { + "xml_enum_ref": "type", + "override_field": "bOverride_Type", + "default_lookup": "Default->Type", + "default_fallback": "mjGEOM_SPHERE", + "name_export_for": "mjGEOM_MESH", + "name_field": "MeshName", + "name_setter": "Element->meshname.assign", + "name_target": "*Element", + }, + } + element_rules = { + "xml_enum_attrs": { + "type": { + "ue_property": "Type", + "ue_enum": "EMjGeomType", + "ue_enum_type": "EMjGeomType", + "override_toggle": "bOverride_Type", + "default_lookup": "Default->Type", + "value_map": { + "sphere": ["Sphere", "mjGEOM_SPHERE"], + "box": ["Box", "mjGEOM_BOX"], + "mesh": ["Mesh", "mjGEOM_MESH"], + }, + }, + }, + } + return cat_rules, element_rules + + +def test_geom_final_type_emits_full_block(): + cat_rules, element_rules = _geom_value_map_rules() + out = _emit_geom_final_type_block(cat_rules, element_rules) + assert out is not None + assert "FinalType" in out + assert "case EMjGeomType::Sphere: FinalType = mjGEOM_SPHERE;" in out + assert "case EMjGeomType::Box: FinalType = mjGEOM_BOX;" in out + assert "case EMjGeomType::Mesh: FinalType = mjGEOM_MESH;" in out + assert "MeshName" in out + assert len(gen._DIAGS) == 0 + + +def test_geom_final_type_returns_none_when_no_rule(): + assert _emit_geom_final_type_block({}, {}) is None + assert len(gen._DIAGS) == 0 + + +def test_geom_final_type_diagnoses_missing_enum_def(): + cat_rules = { + "geom_final_type": { + "xml_enum_ref": "nonexistent", + "default_fallback": "mjGEOM_SPHERE", + "first_mj_const_token": "mjGEOM_PLANE", + "name_for": "mjGEOM_MESH", + "name_field": "MeshName", + "name_setter": "Element->meshname.assign", + "name_target": "*Element", + }, + } + out = _emit_geom_final_type_block(cat_rules, {"xml_enum_attrs": {}}) + assert out is None + assert any("nonexistent" in d.message for d in gen._DIAGS) + + +def test_geom_final_type_diagnoses_empty_value_map(): + cat_rules, element_rules = _geom_value_map_rules() + # Wipe out the value_map and provide no mjspec to fall back to. + element_rules["xml_enum_attrs"]["type"]["value_map"] = {} + out = _emit_geom_final_type_block(cat_rules, element_rules) + assert out is None + assert any("empty value_map" in d.message for d in gen._DIAGS) + + +# ---------- property_default + cross-check ----------------------------------- + +def test_property_default_emitted_on_base(): + """`property_default` ends up as the UPROPERTY initializer when + ``emit_property_decl: true`` is set on an xml_enum_attr.""" + rules = { + "global_exclusions": [], + "default_type": "float", + "property_renames": {}, + "type_mappings": {}, + "canonicalizations": {}, + "element_rules": { + "actuator": { + "xml_enum_attrs": { + "gaintype": { + "ue_property": "GainType", + "ue_enum": "EMjGainType", + "ue_enum_type": "EMjGainType", + "override_toggle": "bOverride_GainType", + "default_lookup": "Default->GainType", + "emit_property_decl": True, + "property_default": "Fixed", + "value_map": { + "fixed": ["Fixed", "mjGAIN_FIXED"], + "affine": ["Affine", "mjGAIN_AFFINE"], + }, + }, + }, + }, + }, + } + out = gen.emit_schema_for_attrs( + ["gaintype"], rules, "actuator", "Actuator", + apply_canonicalizations=True, + ) + assert "EMjGainType GainType = EMjGainType::Fixed;" in out.properties_h + + +def test_property_default_cross_check_diagnoses_bad_member(): + rules = { + "global_exclusions": [], + "default_type": "float", + "property_renames": {}, + "type_mappings": {}, + "canonicalizations": {}, + "element_rules": { + "actuator": { + "xml_enum_attrs": { + "gaintype": { + "ue_property": "GainType", + "ue_enum": "EMjGainType", + "ue_enum_type": "EMjGainType", + "override_toggle": "bOverride_GainType", + "default_lookup": "Default->GainType", + "emit_property_decl": True, + # NotAMember does not appear in value_map below. + "property_default": "NotAMember", + "value_map": { + "fixed": ["Fixed", "mjGAIN_FIXED"], + "affine": ["Affine", "mjGAIN_AFFINE"], + }, + }, + }, + }, + }, + } + gen.emit_schema_for_attrs( + ["gaintype"], rules, "actuator", "Actuator", + apply_canonicalizations=True, + ) + assert any("NotAMember" in d.message for d in gen._DIAGS) + + +# ---------- _guarded_export(multiline=True) ---------------------------------- + +def test_guarded_export_singleline_form(): + """Single-line form: ``if (toggle) `` on one line.""" + out = _guarded_export("bOverride_x", "Element->x = X;") + assert out == " if (bOverride_x) Element->x = X;\n" + + +def test_guarded_export_multiline_brace_layout(): + """Multiline form: brace on its own line; body is emitted verbatim + between braces (caller owns inner indentation).""" + body = " line_a;\n line_b;\n" + out = _guarded_export("bOverride_x", body, multiline=True) + expected = ( + " if (bOverride_x)\n" + " {\n" + " line_a;\n" + " line_b;\n" + " }\n" + ) + assert out == expected + + +def test_guarded_export_multiline_with_extra_cond(): + """``extra_cond`` (default order) appears after the toggle.""" + body = " do_thing();\n" + out = _guarded_export( + "bOverride_x", body, + extra_cond="ready", + multiline=True, + ) + assert out.startswith(" if (bOverride_x && ready)\n {\n") + assert " do_thing();\n" in out + assert out.endswith(" }\n") + + +def test_guarded_export_extra_cond_first_order(): + """``extra_cond_first=True`` flips the order and parenthesises + the extra cond.""" + out = _guarded_export( + "bOverride_x", "Element->x = X;", + extra_cond="ready", + extra_cond_first=True, + ) + assert out == " if ((ready) && bOverride_x) Element->x = X;\n" + + +# ---------- banner-safety audit --------------------------------------------- + +def test_audit_banner_safety_silent_on_template_only(tmp_path): + """A subclass file containing only its own header include and a + bare ``Type = ...`` constructor should not trigger a diagnostic.""" + p = tmp_path / "MjBoxGeom.cpp" + p.write_text( + '#include "MuJoCo/Components/Geometry/MjBoxGeom.h"\n' + "UMjBoxGeom::UMjBoxGeom()\n" + "{\n" + " Type = EMjGeomType::Box;\n" + "}\n", + encoding="utf-8", + ) + subtype = {"class_name": "UMjBoxGeom"} + _audit_banner_safety(str(p), subtype) + assert len(gen._DIAGS) == 0 + + +def test_audit_banner_safety_flags_extra_include(tmp_path): + """An extra non-template #include in a soon-to-be-overwritten file + should trigger a diagnostic so the rule author knows hand-rolled + content will be discarded.""" + p = tmp_path / "MjBoxGeom.cpp" + p.write_text( + '#include "MuJoCo/Components/Geometry/MjBoxGeom.h"\n' + '#include "SomeOther/Header.h"\n' + "UMjBoxGeom::UMjBoxGeom()\n" + "{\n" + " Type = EMjGeomType::Box;\n" + "}\n", + encoding="utf-8", + ) + subtype = {"class_name": "UMjBoxGeom"} + _audit_banner_safety(str(p), subtype) + assert any("SomeOther/Header.h" in d.message for d in gen._DIAGS) + + +def test_audit_banner_safety_flags_extra_ctor_body(tmp_path): + """Constructor body content beyond ``Type = EMj...::X`` and the + rule-provided ``extra_constructor`` should be flagged — that's where + the joint-subtype bOverride_Type bug came from.""" + p = tmp_path / "MjHingeJoint.cpp" + p.write_text( + '#include "MuJoCo/Components/Joints/MjHingeJoint.h"\n' + "UMjHingeJoint::UMjHingeJoint()\n" + "{\n" + " Type = EMjJointType::Hinge;\n" + " HandRolledHelperCall();\n" + "}\n", + encoding="utf-8", + ) + subtype = { + "class_name": "UMjHingeJoint", + "extra_constructor": "", + } + _audit_banner_safety(str(p), subtype) + assert any("non-template ctor content" in d.message + and "HandRolledHelperCall" in d.message + for d in gen._DIAGS) diff --git a/Scripts/codegen/tests/test_phase2c_capabilities.py b/Scripts/codegen/tests/test_phase2c_capabilities.py new file mode 100644 index 0000000..6a151da --- /dev/null +++ b/Scripts/codegen/tests/test_phase2c_capabilities.py @@ -0,0 +1,192 @@ +# Copyright (c) 2026 Jonathan Embley-Riches. All rights reserved. +""" +Phase 2c added four opt-in capabilities to generate_ue_components.py: + +1. ``value_map_from_enum``: snapshot-driven enum-to-value-map resolver. +2. ``xml_enum_attrs.emit_property_decl: true``: codegen emits the UE + enum UPROPERTY decl into the schema PROPERTIES block. +3. Scalar-int view fields: views can declare ``scalar_int_fields`` for + derived integer values (not pointer slices). +4. ``export_if`` per-attr conditional: a C++ predicate that ANDs with + the override toggle before the write fires. + +No current rule opts in — these are scaffolding for Phase 2d / 2e / 5 +consumers. These tests use synthetic rules to verify each capability +works in isolation. +""" + +from __future__ import annotations + +import os +import sys + +_HERE = os.path.dirname(os.path.abspath(__file__)) +_CODEGEN_DIR = os.path.dirname(_HERE) +if _CODEGEN_DIR not in sys.path: + sys.path.insert(0, _CODEGEN_DIR) + +import pytest # noqa: E402 + +from generate_ue_components import ( # noqa: E402 + _resolve_value_map, + _emit_xml_enum_import, + _emit_xml_enum_export, + _emit_export_line, + emit_schema_for_attrs, + emit_view_structs, +) + + +# ----- value_map_from_enum resolver ------------------------------------ + +def test_value_map_explicit_takes_precedence(): + """If a rule has both ``value_map`` and ``value_map_from_enum``, the + explicit map wins. Preserves the pre-2c convention exactly.""" + enum_def = { + "ue_property": "Type", + "ue_enum_type": "EMjJointType", + "value_map": {"hinge": ["Hinge", "mjJNT_HINGE"]}, + "value_map_from_enum": "mjtJoint", + } + snap = {"enums": {"mjtJoint": {"mjJNT_HINGE": 0}}} + resolved = _resolve_value_map("type", enum_def, snap) + assert resolved == {"hinge": ["Hinge", "mjJNT_HINGE"]} + + +def test_value_map_from_enum_resolves_from_snapshot(): + """With only ``value_map_from_enum`` set, the resolver builds the + table from the snapshot's enum entries + the rule's xml_from_mj + + ue_member_from_mj cross-walks.""" + enum_def = { + "ue_property": "Type", + "ue_enum_type": "EMjJointType", + "value_map_from_enum": "mjtJoint", + "ue_member_from_mj": {"mjJNT_HINGE": "Hinge", "mjJNT_SLIDE": "Slide"}, + "xml_from_mj": {"mjJNT_HINGE": "hinge", "mjJNT_SLIDE": "slide"}, + } + snap = {"enums": {"mjtJoint": {"mjJNT_HINGE": 0, "mjJNT_SLIDE": 1}}} + resolved = _resolve_value_map("type", enum_def, snap) + assert resolved == { + "hinge": ["Hinge", "mjJNT_HINGE"], + "slide": ["Slide", "mjJNT_SLIDE"], + } + + +def test_value_map_resolver_errors_when_neither_path_works(): + enum_def = {"ue_property": "X", "ue_enum_type": "E"} + with pytest.raises(RuntimeError, match="no value_map and value_map_from_enum did not resolve"): + _resolve_value_map("attr", enum_def, mjspec=None) + + +def test_xml_enum_import_emits_byte_identical_with_resolver(): + """Emit through the resolver produces the SAME C++ as the old + direct-value_map path. This is the byte-identity guarantee Phase 2c + promised the gate.""" + enum_def = { + "ue_property": "Type", + "ue_enum_type": "EMjJointType", + "value_map": {"hinge": ["Hinge", "mjJNT_HINGE"], "slide": ["Slide", "mjJNT_SLIDE"]}, + } + out = _emit_xml_enum_import("type", enum_def, mjspec=None) + assert "Type = EMjJointType::Hinge" in out + assert "Type = EMjJointType::Slide" in out + assert "bOverride_Type = true" in out + + +# ----- emit_property_decl opt-in --------------------------------------- + +def test_emit_property_decl_off_skips_uproperty(): + """Default behaviour: xml_enum_attrs entries do NOT emit the UE + UPROPERTY decl (the .h hand-declares it).""" + rules = { + "element_rules": { + "joint": { + "xml_enum_attrs": { + "type": { + "ue_property": "Type", + "ue_enum_type": "EMjJointType", + "value_map": {"hinge": ["Hinge", "mjJNT_HINGE"]}, + } + } + } + } + } + out = emit_schema_for_attrs([], rules, element_name="joint", category_label="Joint") + assert "EMjJointType" not in out.properties_h + + +def test_emit_property_decl_on_emits_uproperty_pair(): + """With opt-in, codegen emits both the override toggle and the + EMjX UPROPERTY using the standard _emit_uproperty shape.""" + rules = { + "element_rules": { + "joint": { + "xml_enum_attrs": { + "type": { + "ue_property": "Type", + "ue_enum_type": "EMjJointType", + "emit_property_decl": True, + "value_map": {"hinge": ["Hinge", "mjJNT_HINGE"]}, + } + } + } + } + } + out = emit_schema_for_attrs([], rules, element_name="joint", category_label="Joint") + assert "EMjJointType Type" in out.properties_h + assert "bOverride_Type" in out.properties_h + + +# ----- scalar-int views ------------------------------------------------ + +def test_view_scalar_int_fields_emit_decl_and_bind(): + rules = { + "views": { + "TestView": { + "scalar_int_fields": { + "slot": "id * 2 + 1", + } + } + } + } + out = emit_view_structs(rules, mjxmacro={"mjmodel_pointers": {}}) + fields_block, bind_block = out["TestView"] + assert "int slot;" in fields_block + assert "slot = id * 2 + 1;" in bind_block + + +def test_view_scalar_int_unused_by_default(): + """Views that don't set scalar_int_fields produce no extra lines.""" + rules = {"views": {"TestView": {}}} + out = emit_view_structs(rules, mjxmacro={"mjmodel_pointers": {}}) + fields_block, bind_block = out["TestView"] + assert fields_block == "" + assert bind_block == "" + + +# ----- export_if per-attr conditional ---------------------------------- + +def test_export_if_unset_keeps_simple_toggle(): + out = _emit_export_line("kp", "kp", "float", export_if=None) + assert out == " if (bOverride_kp) Element->kp = kp;\n" + + +def test_export_if_set_combines_with_toggle(): + out = _emit_export_line("kp", "kp", "float", + export_if="Type == EMjActuatorType::Position") + assert out == " if (bOverride_kp && Type == EMjActuatorType::Position) Element->kp = kp;\n" + + +def test_export_if_threads_through_emit_schema_for_attrs(): + rules = { + "default_type": "float", + "type_mappings": {"kp": "float"}, + "element_rules": { + "actuator": { + "export_if": {"kp": "Type == EMjActuatorType::Position"}, + } + }, + } + out = emit_schema_for_attrs(["kp"], rules, element_name="actuator", category_label="Actuator") + assert "Type == EMjActuatorType::Position" in out.exports_cpp + assert "if (bOverride_kp && Type == EMjActuatorType::Position)" in out.exports_cpp diff --git a/Scripts/codegen/tests/test_regen_no_diff.py b/Scripts/codegen/tests/test_regen_no_diff.py new file mode 100644 index 0000000..4a073ad --- /dev/null +++ b/Scripts/codegen/tests/test_regen_no_diff.py @@ -0,0 +1,39 @@ +# Copyright (c) 2026 Jonathan Embley-Riches. All rights reserved. +""" +Golden-file gate. + +Runs ``generate_ue_components.py --check`` against the real schema / +mjxmacro / rules / mjspec snapshots and asserts every emitted file is +byte-identical to what's already on disk. Catches the failure mode that +prompted D4: hand-edits to codegen-managed regions that the emitters +weren't updated to match. + +Run as part of the codegen pytest suite, and from CI. +""" + +from __future__ import annotations + +import os +import subprocess +import sys + +_HERE = os.path.dirname(os.path.abspath(__file__)) +_GENERATOR = os.path.normpath(os.path.join(_HERE, "..", "generate_ue_components.py")) + + +def test_codegen_check_clean() -> None: + """`generate_ue_components.py --check` must exit 0 (zero files changed).""" + proc = subprocess.run( + [sys.executable, _GENERATOR, "--check"], + capture_output=True, + text=True, + ) + stdout = proc.stdout or "" + stderr = proc.stderr or "" + assert proc.returncode == 0, ( + "codegen drift detected: re-running the generator would rewrite one or " + "more on-disk files. Re-run `python Scripts/codegen/generate_ue_components.py` " + "to regenerate, or update the emit functions if hand-edits to " + "CODEGEN_*_START/END regions slipped past the generator.\n" + f"--- stdout ---\n{stdout}\n--- stderr ---\n{stderr}" + ) diff --git a/Scripts/codegen/tests/test_sensor_per_type_extractor.py b/Scripts/codegen/tests/test_sensor_per_type_extractor.py new file mode 100644 index 0000000..2a8345d --- /dev/null +++ b/Scripts/codegen/tests/test_sensor_per_type_extractor.py @@ -0,0 +1,199 @@ +# Copyright (c) 2026 Jonathan Embley-Riches. All rights reserved. +""" +Unit tests for the per-sensor objtype/reftype extractor in +build_mjcf_schema_snapshot.py. + +The extractor scrapes xml_native_reader.cc's ``Sensor()`` if/else cascade +so codegen rules don't have to hand-list each sensor's mjsSensor object +defaults. Tests cover the four shape classes the extractor produces: +literal default, from_xml, computed (multi-attr derivation), and the +nested-branch suppression case (distance/normal/fromto share an outer +branch whose inner ``if`` would otherwise overwrite the entry). +""" + +from __future__ import annotations + +import os +import sys + +_HERE = os.path.dirname(os.path.abspath(__file__)) +_CODEGEN_DIR = os.path.dirname(_HERE) +if _CODEGEN_DIR not in sys.path: + sys.path.insert(0, _CODEGEN_DIR) + +from build_mjcf_schema_snapshot import _extract_sensor_per_type # noqa: E402 + + +_FAKE_SOURCE = r""" +void mjXReader::Sensor(XMLElement* section) { + while (elem) { + mjsSensor* sensor = mjs_addSensor(spec); + string type = elem->Value(); + string text, name, objname, refname; + + if (type == "touch") { + sensor->type = mjSENS_TOUCH; + sensor->objtype = mjOBJ_SITE; + ReadAttrTxt(elem, "site", objname, true); + } else if (type == "framepos") { + sensor->type = mjSENS_FRAMEPOS; + ReadAttrTxt(elem, "objtype", text, true); + sensor->objtype = (mjtObj)mju_str2Type(text.c_str()); + ReadAttrTxt(elem, "objname", objname, true); + if (ReadAttrTxt(elem, "reftype", text)) { + sensor->reftype = (mjtObj)mju_str2Type(text.c_str()); + ReadAttrTxt(elem, "refname", refname, true); + } + } else if (type == "distance" || type == "normal" || type == "fromto") { + bool has_body1 = ReadAttrTxt(elem, "body1", objname); + sensor->objtype = has_body1 ? mjOBJ_BODY : mjOBJ_GEOM; + ReadAttrTxt(elem, "body2", refname); + sensor->reftype = mjOBJ_BODY; + if (type == "distance") { + sensor->type = mjSENS_GEOMDIST; + } else if (type == "normal") { + sensor->type = mjSENS_GEOMNORMAL; + } else { + sensor->type = mjSENS_GEOMFROMTO; + } + } else if (type == "clock") { + sensor->type = mjSENS_CLOCK; + sensor->objtype = mjOBJ_UNKNOWN; + } + elem = NextSiblingElement(elem); + } +} +""" + + +def test_literal_objtype_with_site_name_read(): + result = _extract_sensor_per_type(_FAKE_SOURCE) + assert result["touch"] == { + "mj_type": "mjSENS_TOUCH", + "objtype": "mjOBJ_SITE", + "reftype": None, + "obj_attr": "site", + "ref_attr": None, + "computed": False, + } + + +def test_from_xml_objtype_picks_up_objname_attr(): + result = _extract_sensor_per_type(_FAKE_SOURCE) + framepos = result["framepos"] + assert framepos["objtype"] == "from_xml" + assert framepos["obj_attr"] == "objname" + assert framepos["ref_attr"] == "refname" + assert framepos["computed"] is False + + +def test_multi_name_branch_emits_one_entry_per_name(): + result = _extract_sensor_per_type(_FAKE_SOURCE) + for name in ("distance", "normal", "fromto"): + assert name in result, f"missing {name}" + assert result[name]["computed"] is True + assert result[name]["objtype"] == "computed" + # All three share the same body1/body2 attr-read. + assert result[name]["obj_attr"] == "body1" + assert result[name]["ref_attr"] == "body2" + + +def test_inner_if_inside_multi_name_branch_does_not_overwrite(): + """Regression: the body of the distance/normal/fromto branch contains + ``if (type == "distance")`` and ``else if (type == "normal")`` which set + only ->type. Those inner matches would override the outer entry's + obj_attr/ref_attr with None if the extractor walked them naively.""" + result = _extract_sensor_per_type(_FAKE_SOURCE) + assert result["distance"]["obj_attr"] == "body1" + assert result["normal"]["obj_attr"] == "body1" + + +def test_clock_has_unknown_objtype_no_name_read(): + result = _extract_sensor_per_type(_FAKE_SOURCE) + assert result["clock"] == { + "mj_type": "mjSENS_CLOCK", + "objtype": "mjOBJ_UNKNOWN", + "reftype": None, + "obj_attr": None, + "ref_attr": None, + "computed": False, + } + + +def test_missing_sensor_method_returns_empty(): + assert _extract_sensor_per_type("// no Sensor method here") == {} + + +# ---------- Phase 5/D7: sensor switch + TagToType codegen ---------------- + +def test_sensor_switch_body_emits_static_objtype_when_present(): + from generate_ue_components import _emit_sensor_switch_block # noqa + cat_rules = { + "type_enum_name": "EMjSensorType", + "subtypes": [ + {"key": "touch", "enum_value": "Touch"}, + {"key": "framepos", "enum_value": "FramePos"}, + ], + "default_subtype_key": "touch", + } + sensor_per_type = { + "touch": {"mj_type": "mjSENS_TOUCH", "objtype": "mjOBJ_SITE", "reftype": None}, + "framepos": {"mj_type": "mjSENS_FRAMEPOS", "objtype": "from_xml", "reftype": None}, + } + out = _emit_sensor_switch_block(cat_rules, sensor_per_type) + # Touch gets static objtype literal. + assert "case EMjSensorType::Touch: Element->type = mjSENS_TOUCH; Element->objtype = mjOBJ_SITE; break;" in out + # framepos has objtype=from_xml -> NO static objtype emitted (handled in post-switch block). + assert "case EMjSensorType::FramePos: Element->type = mjSENS_FRAMEPOS; break;" in out + # Default fallback matches the chosen subtype. + assert "default: Element->type = mjSENS_TOUCH; Element->objtype = mjOBJ_SITE; break;" in out + + +def test_sensor_switch_body_honours_case_override(): + from generate_ue_components import _emit_sensor_switch_block + cat_rules = { + "type_enum_name": "EMjSensorType", + "subtypes": [ + {"key": "rangefinder", "enum_value": "RangeFinder", + "case_body_override": "Element->type = mjSENS_RANGEFINDER; Element->objtype = X;"}, + ], + "default_subtype_key": "rangefinder", + } + out = _emit_sensor_switch_block(cat_rules, {"rangefinder": {"mj_type": "mjSENS_RANGEFINDER"}}) + # Override appears verbatim; the emitter's automatic mj_type / objtype + # lines are SKIPPED for this case. + assert "Element->objtype = X;" in out + assert out.count("RangeFinder") >= 1 + + +def test_sensor_tag_to_type_map_uses_xml_key_verbatim(): + from generate_ue_components import _emit_sensor_tag_to_type_block + cat_rules = { + "type_enum_name": "EMjSensorType", + "subtypes": [ + {"key": "touch", "enum_value": "Touch"}, + {"key": "e_potential", "enum_value": "EPotential"}, + {"key": "jointactuatorfrc", "enum_value": "JointActFrc"}, + ], + } + out = _emit_sensor_tag_to_type_block(cat_rules) + assert '{TEXT("touch"), EMjSensorType::Touch},' in out + # Underscore-containing XML keys preserved literally. + assert '{TEXT("e_potential"), EMjSensorType::EPotential},' in out + # XML key and UE enum_value can diverge; map uses XML key. + assert '{TEXT("jointactuatorfrc"), EMjSensorType::JointActFrc},' in out + + +def test_real_snapshot_covers_every_schema_sensor(): + """End-to-end: the snapshot shipped in Scripts/ should have one + per_type entry for every sensor_types entry — and vice versa. Catches + drift between the static MJCF[] schema and the parser cascade.""" + import json + plugin_root = os.path.normpath(os.path.join(_HERE, "..", "..", "..")) + snap = json.load(open(os.path.join(plugin_root, "Scripts", "codegen", "snapshots", "mjcf_schema_snapshot.json"))) + schema_names = set(snap["sensor_types"]) + per_type_names = set(snap.get("sensor_per_type", {}).keys()) + assert schema_names == per_type_names, ( + f"schema/per_type drift: only-in-schema={sorted(schema_names - per_type_names)}; " + f"only-in-per_type={sorted(per_type_names - schema_names)}" + ) diff --git a/Scripts/codegen/tests/test_setto_introspection.py b/Scripts/codegen/tests/test_setto_introspection.py index ace30cc..a22ff8e 100644 --- a/Scripts/codegen/tests/test_setto_introspection.py +++ b/Scripts/codegen/tests/test_setto_introspection.py @@ -21,7 +21,7 @@ def _load_mjspec(): - with open(os.path.join(_PLUGIN_ROOT, "Scripts", "mjspec_snapshot.json"), "r") as f: + with open(os.path.join(_PLUGIN_ROOT, "Scripts", "codegen", "snapshots", "mjspec_snapshot.json"), "r") as f: return json.load(f) diff --git a/Scripts/codegen/tests/test_subclass_emission.py b/Scripts/codegen/tests/test_subclass_emission.py index 01cd157..c65d112 100644 --- a/Scripts/codegen/tests/test_subclass_emission.py +++ b/Scripts/codegen/tests/test_subclass_emission.py @@ -19,7 +19,7 @@ @pytest.fixture(scope="session") def real_mjspec(): """The mjspec snapshot (structs + setto_functions) shipped with the plugin.""" - with open(os.path.join(_PLUGIN_ROOT, "Scripts", "mjspec_snapshot.json"), "r") as f: + with open(os.path.join(_PLUGIN_ROOT, "Scripts", "codegen", "snapshots", "mjspec_snapshot.json"), "r") as f: return json.load(f) diff --git a/Scripts/codegen/tests/test_sync_vendored.py b/Scripts/codegen/tests/test_sync_vendored.py new file mode 100644 index 0000000..95ea959 --- /dev/null +++ b/Scripts/codegen/tests/test_sync_vendored.py @@ -0,0 +1,71 @@ +# Copyright (c) 2026 Jonathan Embley-Riches. All rights reserved. +""" +Unit tests for the manifest parser + formatter in sync_vendored.py. + +Network fetches are NOT exercised here — they need the real GitHub +endpoints. The tests cover only the deterministic-rewrite property +(re-parsing + re-formatting the same content produces the same bytes) +and the column-ordering / sort-by-dest invariants. +""" + +from __future__ import annotations + +import os +import sys + +_HERE = os.path.dirname(os.path.abspath(__file__)) +_CODEGEN_DIR = os.path.dirname(_HERE) +if _CODEGEN_DIR not in sys.path: + sys.path.insert(0, _CODEGEN_DIR) + +from sync_vendored import ( # noqa: E402 + _parse_manifest, + _format_manifest, + _extract_preamble, +) + + +_SAMPLE = """\ +# Vendored sources + +Preamble paragraph here. + +| file | upstream_url | upstream_sha | retrieved_date | license | local_dest | +|------|--------------|--------------|-----------------|---------|------------| +| foo.h | https://example.com/{sha}/foo.h | abc123 | 2026-01-01 | MIT | Scripts/codegen/_vendored/foo.h | +| bar.h | https://example.com/{sha}/bar.h | def456 | 2026-01-02 | Apache-2.0 | Scripts/codegen/_vendored/bar.h | +""" + + +def test_parse_skips_separator_and_preamble(): + rows = _parse_manifest(_SAMPLE) + assert len(rows) == 2 + assert rows[0]["file"] == "foo.h" + assert rows[0]["upstream_sha"] == "abc123" + assert rows[1]["file"] == "bar.h" + + +def test_extract_preamble_stops_at_first_row(): + pre = _extract_preamble(_SAMPLE) + assert "# Vendored sources" in pre + assert "abc123" not in pre + + +def test_format_sorts_by_local_dest(): + rows = _parse_manifest(_SAMPLE) + out = _format_manifest(rows, "# header\n") + # bar.h comes first because Scripts/.../bar.h < Scripts/.../foo.h + bar_idx = out.index("| bar.h |") + foo_idx = out.index("| foo.h |") + assert bar_idx < foo_idx + + +def test_format_is_deterministic_round_trip(): + """Parse + format + parse + format must produce identical bytes — + that's the merge-conflict-resistance property the manifest design + promises.""" + pre = _extract_preamble(_SAMPLE) + rows = _parse_manifest(_SAMPLE) + once = _format_manifest(rows, pre) + twice = _format_manifest(_parse_manifest(once), _extract_preamble(once)) + assert once == twice diff --git a/Scripts/codegen/tests/test_synthetic_categories.py b/Scripts/codegen/tests/test_synthetic_categories.py new file mode 100644 index 0000000..6b8dde7 --- /dev/null +++ b/Scripts/codegen/tests/test_synthetic_categories.py @@ -0,0 +1,221 @@ +# Copyright (c) 2026 Jonathan Embley-Riches. All rights reserved. +""" +Tests for the Phase 2e synthetic_categories emitter. + +Pilot scope per D9: emits one banner-mode .h file per entry from an +mjxmacro X-macro field list. mjStatistic ships as the proof-of-concept; +FMuJoCoOptions and the 6 mjVisual_* structs are follow-ups since they +need URLab pseudo-fields / mixed conditional writes / unit-conversion +hooks the pilot doesn't expose yet. +""" + +from __future__ import annotations + +import os +import sys + +_HERE = os.path.dirname(os.path.abspath(__file__)) +_CODEGEN_DIR = os.path.dirname(_HERE) +if _CODEGEN_DIR not in sys.path: + sys.path.insert(0, _CODEGEN_DIR) + +from generate_ue_components import ( # noqa: E402 + _emit_synthetic_struct_files, + _ue_field_name, +) + + +def test_ue_field_name_pascal_cases_snake_input(): + assert _ue_field_name("timestep") == "Timestep" + assert _ue_field_name("ls_iterations") == "LsIterations" + assert _ue_field_name("sleep_tolerance") == "SleepTolerance" + # Single component stays capitalised. + assert _ue_field_name("extent") == "Extent" + + +def test_synthetic_struct_emits_uproperty_per_field(): + mjxmacro = { + "struct_fields": { + "TEST_FIELDS": [ + {"type": "mjtNum", "name": "timestep", "count": "1", "is_vec": False}, + {"type": "int", "name": "iterations", "count": "1", "is_vec": False}, + {"type": "float", "name": "gravity", "count": "3", "is_vec": True}, + ], + }, + } + def_ = { + "ue_struct_name": "FTestStruct", + "mjxmacro_block": "TEST_FIELDS", + "c_struct_type": "mjTest", + "public_header": "MuJoCo/Generated/MjTest.h", + "private_source": "MuJoCo/Generated/MjTest.cpp", + "category_label": "Test", + "exclude_fields": [], + "per_field_meta": {}, + "urlab_extra_fields": [], + } + writes = _emit_synthetic_struct_files( + "MjTest", def_, mjxmacro, public_root="/tmp/pub", private_root="/tmp/priv", + ) + assert len(writes) == 1 + h = writes[0].content + # USTRUCT outline. + assert "USTRUCT(BlueprintType)" in h + assert "struct URLAB_API FTestStruct" in h + # Each field gets its toggle + value pair. + assert "bOverride_Timestep" in h + assert "double Timestep" in h + assert "bOverride_Iterations" in h + assert "int32 Iterations" in h + # is_vec + count==3 -> FVector. + assert "FVector Gravity" in h + # Category labels use the rule's category_label. + assert 'Category = "MuJoCo|Test"' in h + # ApplyTo body assigns each field with a decltype cast. + assert "Dst.timestep = (decltype(Dst.timestep))Timestep;" in h + assert "Dst.gravity[0] = (decltype(Dst.gravity[0]))Gravity.X;" in h + + +def test_synthetic_struct_skips_excluded_fields(): + mjxmacro = { + "struct_fields": { + "TEST_FIELDS": [ + {"type": "int", "name": "keep_me", "count": "1", "is_vec": False}, + {"type": "int", "name": "drop_me", "count": "1", "is_vec": False}, + ], + }, + } + def_ = { + "ue_struct_name": "F", + "mjxmacro_block": "TEST_FIELDS", + "public_header": "P/F.h", + "private_source": "P/F.cpp", + "category_label": "C", + "exclude_fields": ["drop_me"], + "per_field_meta": {}, + } + writes = _emit_synthetic_struct_files("X", def_, mjxmacro, "/tmp/pub", "/tmp/priv") + h = writes[0].content + assert "KeepMe" in h + assert "DropMe" not in h + + +def test_synthetic_struct_field_rename_overrides_default(): + """``field_renames`` lets rules pin a non-default UE name (e.g. URLab's + historical CCD_Iterations vs default CcdIterations).""" + mjxmacro = { + "struct_fields": { + "T_FIELDS": [ + {"type": "int", "name": "ccd_iterations", "count": "1", "is_vec": False}, + ], + }, + } + def_ = { + "ue_struct_name": "FT", + "mjxmacro_block": "T_FIELDS", + "public_header": "P/T.h", + "private_source": "P/T.cpp", + "category_label": "T", + "field_renames": {"ccd_iterations": "CCD_Iterations"}, + } + writes = _emit_synthetic_struct_files("MjT", def_, mjxmacro, "/tmp/pub", "/tmp/priv") + h = writes[0].content + assert "CCD_Iterations" in h + assert "CcdIterations" not in h + + +def test_synthetic_struct_skips_when_mjxmacro_block_missing(): + """Defensive: a typo in mjxmacro_block produces a diagnostic, not a + crash, and emits no file.""" + from generate_ue_components import _DIAGS + _DIAGS.clear() + mjxmacro = {"struct_fields": {}} + def_ = { + "ue_struct_name": "F", "mjxmacro_block": "NONEXISTENT", + "public_header": "P/F.h", "private_source": "P/F.cpp", + "category_label": "C", + } + writes = _emit_synthetic_struct_files("M", def_, mjxmacro, "/tmp/pub", "/tmp/priv") + assert writes == [] + assert any("NONEXISTENT" in d.message for d in _DIAGS) + _DIAGS.clear() + + +def test_generated_enum_emits_uenum_per_entry(): + from generate_ue_components import _emit_generated_enum_file + mjspec = {"enums": { + "mjtIntegrator": {"mjINT_EULER": 0, "mjINT_RK4": 1, "mjINT_IMPLICIT": 2}, + }} + def_ = { + "public_header": "Generated/MjOptionEnums.h", + "enums": [{ + "ue_name": "EMjIntegrator", + "from_mj_enum": "mjtIntegrator", + "ue_member_from_mj": { + "mjINT_EULER": "Euler", + "mjINT_RK4": "RK4", + "mjINT_IMPLICIT": "Implicit", + }, + }], + } + writes = _emit_generated_enum_file("MjOptionEnums", def_, mjspec, "/tmp/pub") + assert len(writes) == 1 + h = writes[0].content + assert "UENUM(BlueprintType)" in h + assert "enum class EMjIntegrator : uint8" in h + assert "Euler = 0" in h + assert "RK4 = 1" in h + assert "Implicit = 2" in h + + +def test_generated_enum_skips_when_mj_enum_missing(): + from generate_ue_components import _emit_generated_enum_file, _DIAGS + _DIAGS.clear() + mjspec = {"enums": {}} + def_ = { + "public_header": "P/H.h", + "enums": [{"ue_name": "E", "from_mj_enum": "mjtMissing", "ue_member_from_mj": {}}], + } + writes = _emit_generated_enum_file("X", def_, mjspec, "/tmp/pub") + assert writes == [] + assert any("mjtMissing" in d.message for d in _DIAGS) + _DIAGS.clear() + + +def test_generated_enum_member_without_mapping_silently_skipped(): + """C enums often have sentinel constants (mjNGEOMTYPES) that don't + map to UE. Rule author omits them from ue_member_from_mj; emitter + skips them without diagnostics.""" + from generate_ue_components import _emit_generated_enum_file + mjspec = {"enums": {"mjtX": {"mjX_A": 0, "mjX_SENTINEL": 1, "mjX_B": 2}}} + def_ = { + "public_header": "P/H.h", + "enums": [{ + "ue_name": "EMjX", "from_mj_enum": "mjtX", + "ue_member_from_mj": {"mjX_A": "A", "mjX_B": "B"}, + }], + } + h = _emit_generated_enum_file("X", def_, mjspec, "/tmp/pub")[0].content + assert "A = 0" in h + # B retains its original value 2 (skipped sentinel doesn't renumber). + assert "B = 2" in h + assert "Sentinel" not in h + + +def test_real_snapshot_mjstatistic_pilot(): + """End-to-end: the shipped rule produces a syntactically plausible + .h file. UE compile separately verifies it actually builds.""" + import json + plugin_root = os.path.normpath(os.path.join(_HERE, "..", "..", "..")) + h_path = os.path.join(plugin_root, "Source", "URLab", "Public", + "MuJoCo", "Generated", "MjStatistic.h") + assert os.path.exists(h_path), "MjStatistic.h was not generated" + with open(h_path, "r", encoding="utf-8") as f: + h = f.read() + # Pilot fields from MJSTATISTIC_FIELDS. + for ue_name in ("Meaninertia", "Meanmass", "Meansize", "Extent", "Center"): + assert ue_name in h, f"missing field {ue_name}" + # ApplyTo is templated so it works against both mjStatistic and any + # alias type. Compile correctness is verified by UE's build step. + assert "template " in h + assert "void ApplyTo(TDst& Dst) const" in h diff --git a/Scripts/codegen/tests/test_view_struct.py b/Scripts/codegen/tests/test_view_struct.py index 8ba7449..cccde19 100644 --- a/Scripts/codegen/tests/test_view_struct.py +++ b/Scripts/codegen/tests/test_view_struct.py @@ -63,3 +63,59 @@ def test_view_has_one_field_per_mjxmacro_entry(real_rules, real_mjxmacro): name = entry["name"] view_name = field_renames.get(name, name) assert f" {view_name};" in fields, f"missing view field for {name} (-> {view_name})" + + +def test_stride_one_int_entries_emit_as_dereferenced_scalars(): + """Single-int entries (stride=="1", type=="int") emit as ``int X`` + with ``X = m->src[id]`` in the bind body — value semantics, not pointer. + Regression guard for the codegen feature added in codegen(item-2).""" + rules = {"views": {"FooView": { + "obj_type": "mjOBJ_BODY", + "include_blocks": ["FOO_BLOCK"], + }}} + mjxmacro = {"mjmodel_pointers": {"FOO_BLOCK": [ + {"type": "int", "name": "foo_kind", "outer_dim": "nfoo", "stride": "1"}, + {"type": "int", "name": "foo_size_arr", "outer_dim": "nfoo", "stride": "3"}, + {"type": "mjtNum", "name": "foo_pos", "outer_dim": "nfoo", "stride": "3"}, + ]}} + views = emit_view_structs(rules, mjxmacro) + fields, bind = views["FooView"] + # Scalar int — dereferenced, not pointer. + assert " int foo_kind;" in fields + assert " foo_kind = m->foo_kind[id];" in bind + # Int but stride>1 — stays a pointer. + assert " int* foo_size_arr;" in fields + assert " foo_size_arr = m->foo_size_arr + id * 3;" in bind + # mjtNum stride>1 — pointer. + assert " mjtNum* foo_pos;" in fields + assert " foo_pos = m->foo_pos + id * 3;" in bind + + +def test_data_fields_bind_override(): + """``data_fields[name].bind_override`` short-circuits the standard + ``base + index_var * stride`` emit and drops the override verbatim + inside the BIND marker. Used by SensorView::sensordata (bounds-checked + slice) and ActuatorView::act (nullable lookup).""" + rules = {"views": {"BarView": { + "obj_type": "mjOBJ_GEOM", + "include_blocks": [], + "data_fields": { + "_note_skip_me": "comment-only; codegen must skip _note_* keys", + "plain": {"index_var": "id", "stride": "1"}, + "bounds_check": {"bind_override": + "bounds_check = (id < m->nfoo) ? d->bounds_check + id : nullptr;"}, + }, + }}} + mjxmacro = {"mjmodel_pointers": {}} + views = emit_view_structs(rules, mjxmacro) + fields, bind = views["BarView"] + # Standard data_field bind emitted. + assert " mjtNum* plain;" in fields + assert " plain = d->plain + id * 1;" in bind + # bind_override field still declared at the standard cpp_type. + assert " mjtNum* bounds_check;" in fields + # bind_override body dropped verbatim — no base+id*stride. + assert " bounds_check = (id < m->nfoo) ? d->bounds_check + id : nullptr;" in bind + # _note_* keys are documentation, not data fields. + assert "_note_skip_me" not in fields + assert "_note_skip_me" not in bind diff --git a/Source/URLab/Private/MuJoCo/Components/Actuators/MjActuator.cpp b/Source/URLab/Private/MuJoCo/Components/Actuators/MjActuator.cpp index eb41488..2df2f00 100644 --- a/Source/URLab/Private/MuJoCo/Components/Actuators/MjActuator.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Actuators/MjActuator.cpp @@ -21,6 +21,7 @@ // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. #include "MuJoCo/Components/Actuators/MjActuator.h" +#include "MuJoCo/Utils/MjUtils.h" #include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" #include "MuJoCo/Core/AMjManager.h" @@ -53,7 +54,7 @@ void UMjActuator::ExportTo(mjsActuator* Element, mjsDefault* Default) if (!Element) return; // --- CODEGEN_EXPORT_START --- - if (!TargetName.IsEmpty()) mjs_setString(Element->target, TCHAR_TO_UTF8(*TargetName)); + MjSetString(Element->target, TargetName); switch (TransmissionType) { case EMjActuatorTrnType::Joint: Element->trntype = mjTRN_JOINT; break; @@ -66,11 +67,11 @@ void UMjActuator::ExportTo(mjsActuator* Element, mjsDefault* Default) } if (TransmissionType == EMjActuatorTrnType::SliderCrank && !SliderSite.IsEmpty()) { - mjs_setString(Element->slidersite, TCHAR_TO_UTF8(*SliderSite)); + MjSetStringRaw(Element->slidersite, SliderSite); } if (TransmissionType == EMjActuatorTrnType::Site && !RefSite.IsEmpty()) { - mjs_setString(Element->refsite, TCHAR_TO_UTF8(*RefSite)); + MjSetStringRaw(Element->refsite, RefSite); } if (bOverride_GainType) { @@ -135,6 +136,7 @@ void UMjActuator::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& if (!Node) return; // --- CODEGEN_IMPORT_START --- + MjXmlUtils::ReadAttrString(Node, TEXT("class"), MjClassName); { // xml_enum: gaintype -> EMjGainType FString S = Node->GetAttribute(TEXT("gaintype")); S = S.ToLower(); @@ -217,23 +219,12 @@ void UMjActuator::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& } } // --- CODEGEN_IMPORT_END --- - - MjXmlUtils::ReadAttrString(Node, TEXT("class"), MjClassName); } void UMjActuator::Bind(mjModel* Model, mjData* Data, const FString& Prefix) { Super::Bind(Model, Data, Prefix); - m_ActuatorView = BindToView(Prefix); - - if (m_ActuatorView.id != -1) - { - m_ID = m_ActuatorView.id; - } - else - { - UE_LOG(LogURLabBind, Warning, TEXT("[MjActuator] Actuator '%s' could not bind! Prefix: %s"), *GetName(), *Prefix); - } + BindAndCacheView(m_ActuatorView, Prefix); } // ---------------------------------------------------------------------------------- @@ -288,38 +279,38 @@ float UMjActuator::ResolveDesiredControl(uint8 Source) const float UMjActuator::GetForce() const { - if (m_ActuatorView.id != -1 && m_ActuatorView.force) + if (m_ActuatorView.id != -1 && m_ActuatorView.actuator_force) { - return (float)m_ActuatorView.force[0]; + return (float)m_ActuatorView.actuator_force[0]; } return 0.0f; } float UMjActuator::GetLength() const { - if (m_ActuatorView.id != -1 && m_ActuatorView.length) + if (m_ActuatorView.id != -1 && m_ActuatorView.actuator_length) { - return (float)m_ActuatorView.length[0]; + return (float)m_ActuatorView.actuator_length[0]; } return 0.0f; } float UMjActuator::GetVelocity() const { - if (m_ActuatorView.id != -1 && m_ActuatorView.velocity) + if (m_ActuatorView.id != -1 && m_ActuatorView.actuator_velocity) { - return (float)m_ActuatorView.velocity[0]; + return (float)m_ActuatorView.actuator_velocity[0]; } return 0.0f; } void UMjActuator::SetGear(const TArray& NewGear) { - if (m_ActuatorView.id != -1 && m_ActuatorView.gear) + if (m_ActuatorView.id != -1 && m_ActuatorView.actuator_gear) { for(int i=0; i& NewGear) TArray UMjActuator::GetGear() const { TArray Res; - if (m_ActuatorView.id != -1 && m_ActuatorView.gear) + if (m_ActuatorView.id != -1 && m_ActuatorView.actuator_gear) { - for(int i=0; i<6; ++i) Res.Add((float)m_ActuatorView.gear[i]); + for(int i=0; i<6; ++i) Res.Add((float)m_ActuatorView.actuator_gear[i]); } return Res; } FVector2D UMjActuator::GetControlRange() const { - if (m_ActuatorView.id < 0 || !m_ActuatorView.ctrlrange) return FVector2D::ZeroVector; - return FVector2D((float)m_ActuatorView.ctrlrange[0], (float)m_ActuatorView.ctrlrange[1]); + if (m_ActuatorView.id < 0 || !m_ActuatorView.actuator_ctrlrange) return FVector2D::ZeroVector; + return FVector2D((float)m_ActuatorView.actuator_ctrlrange[0], (float)m_ActuatorView.actuator_ctrlrange[1]); } float UMjActuator::GetActivation() const @@ -403,19 +394,10 @@ TArray UMjActuator::GetTargetNameOptions() const return GetSiblingComponentOptions(this, FilterClass); } -TArray UMjActuator::GetSliderSiteOptions() const -{ - return GetSiblingComponentOptions(this, UMjSite::StaticClass()); -} - -TArray UMjActuator::GetRefSiteOptions() const -{ - return GetSiblingComponentOptions(this, UMjSite::StaticClass()); -} - -TArray UMjActuator::GetDefaultClassOptions() const -{ - return GetSiblingComponentOptions(this, UMjDefault::StaticClass(), true); -} +// --- CODEGEN_EDITOR_OPTIONS_START --- +TArray UMjActuator::GetSliderSiteOptions() const { return UMjComponent::GetSiblingComponentOptions(this, UMjSite::StaticClass()); } +TArray UMjActuator::GetRefSiteOptions() const { return UMjComponent::GetSiblingComponentOptions(this, UMjSite::StaticClass()); } +TArray UMjActuator::GetDefaultClassOptions() const { return UMjComponent::GetSiblingComponentOptions(this, UMjDefault::StaticClass(), true); } + // --- CODEGEN_EDITOR_OPTIONS_END --- #endif diff --git a/Source/URLab/Private/MuJoCo/Components/Bodies/MjBody.cpp b/Source/URLab/Private/MuJoCo/Components/Bodies/MjBody.cpp index 457b5e5..668ff83 100644 --- a/Source/URLab/Private/MuJoCo/Components/Bodies/MjBody.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Bodies/MjBody.cpp @@ -97,11 +97,11 @@ void UMjBody::ExportTo(mjsBody* Element, mjsDefault* Default) if (!Element) return; // --- CODEGEN_EXPORT_START --- - if (SleepPolicy != EMjBodySleepPolicy::Default) + if (bOverride_SleepPolicy) { Element->sleep = static_cast(static_cast(SleepPolicy)); } - if (bOverride_childclass && !childclass.IsEmpty()) mjs_setString(Element->childclass, TCHAR_TO_UTF8(*childclass)); + if (bOverride_childclass) MjSetString(Element->childclass, childclass); if (bOverride_mocap) Element->mocap = mocap ? 1 : 0; if (bOverride_gravcomp) Element->gravcomp = gravcomp; // --- CODEGEN_EXPORT_END --- @@ -228,6 +228,7 @@ void UMjBody::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& Com if (!Node) return; // --- CODEGEN_IMPORT_START --- + MjXmlUtils::ReadAttrString(Node, TEXT("name"), MjName); if (MjXmlUtils::ReadAttrString(Node, TEXT("childclass"), childclass)) bOverride_childclass = true; MjXmlUtils::ReadAttrBool(Node, TEXT("mocap"), mocap, bOverride_mocap); MjXmlUtils::ReadAttrFloat(Node, TEXT("gravcomp"), gravcomp, bOverride_gravcomp); @@ -240,19 +241,16 @@ void UMjBody::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& Com bOverride_Quat = true; } } - { // canonicalize body.sleep -> EMjBodySleepPolicy + { // canonicalize body.sleep -> EMjBodySleepPolicy + bOverride_SleepPolicy FString S = Node->GetAttribute(TEXT("sleep")); S = S.ToLower(); - if (S == TEXT("never")) SleepPolicy = EMjBodySleepPolicy::Never; - else if (S == TEXT("allowed")) SleepPolicy = EMjBodySleepPolicy::Allowed; - else if (S == TEXT("init")) SleepPolicy = EMjBodySleepPolicy::InitAsleep; + if (S == TEXT("never")) { SleepPolicy = EMjBodySleepPolicy::Never; bOverride_SleepPolicy = true; } + else if (S == TEXT("allowed")) { SleepPolicy = EMjBodySleepPolicy::Allowed; bOverride_SleepPolicy = true; } + else if (S == TEXT("init")) { SleepPolicy = EMjBodySleepPolicy::InitAsleep; bOverride_SleepPolicy = true; } } if (bOverride_Pos) SetRelativeLocation(Pos); if (bOverride_Quat) SetRelativeRotation(Quat); // --- CODEGEN_IMPORT_END --- - - // name attribute → store in MjName for explicit override - MjXmlUtils::ReadAttrString(Node, TEXT("name"), MjName); } void UMjBody::Bind(mjModel* Model, mjData* Data, const FString& Prefix) @@ -261,22 +259,13 @@ void UMjBody::Bind(mjModel* Model, mjData* Data, const FString& Prefix) if (Model && Data) { - m_BodyView = BindToView(Prefix); + BindAndCacheView(m_BodyView, Prefix); - if (m_BodyView.id != -1) - { - m_ID = m_BodyView.id; - m_IsSetup = true; - SetComponentTickEnabled(true); - } - else - { - UE_LOG(LogURLabBind, Warning, TEXT("MjBody::Bind() - FAILED to find body '%s'"), *GetName()); - m_IsSetup = false; - SetComponentTickEnabled(false); - } + const bool bBound = m_BodyView.id != -1; + m_IsSetup = bBound; + SetComponentTickEnabled(bBound); - if (mocap && m_ID >= 0) + if (bBound && mocap) { int mocapid = Model->body_mocapid[m_ID]; if (mocapid >= 0) @@ -432,8 +421,7 @@ void UMjBody::RegisterToSpec(FMujocoSpecWrapper& Wrapper, mjsBody* ParentBody) } #if WITH_EDITOR -TArray UMjBody::GetChildClassOptions() const -{ - return UMjComponent::GetSiblingComponentOptions(this, UMjDefault::StaticClass(), true); -} +// --- CODEGEN_EDITOR_OPTIONS_START --- +TArray UMjBody::GetChildClassOptions() const { return UMjComponent::GetSiblingComponentOptions(this, UMjDefault::StaticClass(), true); } + // --- CODEGEN_EDITOR_OPTIONS_END --- #endif diff --git a/Source/URLab/Private/MuJoCo/Components/Bodies/MjFrame.cpp b/Source/URLab/Private/MuJoCo/Components/Bodies/MjFrame.cpp index 5ca3fb0..7fa6093 100644 --- a/Source/URLab/Private/MuJoCo/Components/Bodies/MjFrame.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Bodies/MjFrame.cpp @@ -64,7 +64,7 @@ void UMjFrame::ExportTo(mjsFrame* Element, mjsDefault* Default) if (!Element) return; // --- CODEGEN_EXPORT_START --- - if (bOverride_childclass && !childclass.IsEmpty()) mjs_setString(Element->childclass, TCHAR_TO_UTF8(*childclass)); + if (bOverride_childclass) MjSetString(Element->childclass, childclass); // --- CODEGEN_EXPORT_END --- } diff --git a/Source/URLab/Private/MuJoCo/Components/Constraints/MjEquality.cpp b/Source/URLab/Private/MuJoCo/Components/Constraints/MjEquality.cpp index 547d11a..c792b1a 100644 --- a/Source/URLab/Private/MuJoCo/Components/Constraints/MjEquality.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Constraints/MjEquality.cpp @@ -103,6 +103,7 @@ void UMjEquality::ExportTo(mjsEquality* Element) // anchor) or site-to-site. URLab's parser collates site1/site2 into // Obj1/Obj2 alongside body1/body2; we use the non-empty site1 // UPROPERTY as the discriminator for "this was a site-mode equality". + // --- CODEGEN_OBJTYPE_DISPATCH_START --- switch (EqualityType) { case EMjEqualityType::Connect: @@ -124,6 +125,7 @@ void UMjEquality::ExportTo(mjsEquality* Element) Element->objtype = mjOBJ_UNKNOWN; break; } + // --- CODEGEN_OBJTYPE_DISPATCH_END --- // --- CODEGEN_EXPORT_START --- if (bOverride_active) Element->active = active; @@ -152,8 +154,8 @@ void UMjEquality::ExportTo(mjsEquality* Element) { Element->data[10] = (mjtNum)torquescale; } - if (!Obj1.IsEmpty()) mjs_setString(Element->name1, TCHAR_TO_UTF8(*Obj1)); - if (!Obj2.IsEmpty()) mjs_setString(Element->name2, TCHAR_TO_UTF8(*Obj2)); + MjSetString(Element->name1, Obj1); + MjSetString(Element->name2, Obj2); // --- CODEGEN_EXPORT_END --- } diff --git a/Source/URLab/Private/MuJoCo/Components/Geometry/MjGeom.cpp b/Source/URLab/Private/MuJoCo/Components/Geometry/MjGeom.cpp index 6eb989c..bc320f0 100644 --- a/Source/URLab/Private/MuJoCo/Components/Geometry/MjGeom.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Geometry/MjGeom.cpp @@ -76,6 +76,7 @@ void UMjGeom::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& Com // on Type to pick size[1] vs size[2] for the half-length write. // --- CODEGEN_IMPORT_START --- + MjXmlUtils::ReadAttrString(Node, TEXT("class"), MjClassName); { // xml_enum: type -> EMjGeomType FString S = Node->GetAttribute(TEXT("type")); S = S.ToLower(); @@ -150,9 +151,6 @@ void UMjGeom::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& Com if (bOverride_Quat) SetRelativeRotation(Quat); // --- CODEGEN_IMPORT_END --- - // MuJoCo class inheritance - MjXmlUtils::ReadAttrString(Node, TEXT("class"), MjClassName); - // Implicit mesh-type detection (mesh attr present but type wasn't set) if (!bOverride_Type && !mesh.IsEmpty()) { @@ -179,29 +177,30 @@ void UMjGeom::ExportTo(mjsGeom* Element, mjsDefault* Default) // Type isn't overridden locally, fall back to the default's geom type. // (The codegen-owned xml_enum export below writes Element->type only when // bOverride_Type is true — exactly the desired behavior.) + // --- CODEGEN_GEOM_FINAL_TYPE_START --- int FinalType = bOverride_Type - ? static_cast(Type) /* placeholder; remapped below */ + ? mjGEOM_PLANE /* placeholder; remapped below */ : (Default ? Default->geom->type : mjGEOM_MESH); if (bOverride_Type) { - switch(Type) + switch (Type) { - case EMjGeomType::Plane: FinalType = mjGEOM_PLANE; break; - case EMjGeomType::Hfield: FinalType = mjGEOM_HFIELD; break; - case EMjGeomType::Sphere: FinalType = mjGEOM_SPHERE; break; - case EMjGeomType::Capsule: FinalType = mjGEOM_CAPSULE; break; - case EMjGeomType::Ellipsoid:FinalType = mjGEOM_ELLIPSOID;break; + case EMjGeomType::Plane: FinalType = mjGEOM_PLANE; break; + case EMjGeomType::Hfield: FinalType = mjGEOM_HFIELD; break; + case EMjGeomType::Sphere: FinalType = mjGEOM_SPHERE; break; + case EMjGeomType::Capsule: FinalType = mjGEOM_CAPSULE; break; + case EMjGeomType::Ellipsoid: FinalType = mjGEOM_ELLIPSOID; break; case EMjGeomType::Cylinder: FinalType = mjGEOM_CYLINDER; break; - case EMjGeomType::Box: FinalType = mjGEOM_BOX; break; - case EMjGeomType::Mesh: FinalType = mjGEOM_MESH; break; - case EMjGeomType::SDF: FinalType = mjGEOM_SDF; break; + case EMjGeomType::Box: FinalType = mjGEOM_BOX; break; + case EMjGeomType::Mesh: FinalType = mjGEOM_MESH; break; + case EMjGeomType::SDF: FinalType = mjGEOM_SDF; break; } } - if (FinalType == mjGEOM_MESH && !MeshName.IsEmpty()) { - mjs_setString(Element->meshname, TCHAR_TO_UTF8(*MeshName)); + MjSetStringRaw(Element->meshname, MeshName); } + // --- CODEGEN_GEOM_FINAL_TYPE_END --- // size: codegen-owned TArray; the default per-attr export writes // Element->size[i] = size[i] up to size.Num(). Clamped to 3 by mjsGeom's @@ -269,7 +268,7 @@ void UMjGeom::ExportTo(mjsGeom* Element, mjsDefault* Default) if (bOverride_solimp) { for (int32 i = 0; i < solimp.Num(); ++i) Element->solimp[i] = solimp[i]; } if (bOverride_margin) Element->margin = margin; if (bOverride_gap) Element->gap = gap; - if (bOverride_mesh && !mesh.IsEmpty()) mjs_setString(Element->meshname, TCHAR_TO_UTF8(*mesh)); + if (bOverride_mesh) MjSetString(Element->meshname, mesh); if (bOverride_fitscale) Element->fitscale = fitscale ? 1 : 0; if (bOverride_rgba) { Element->rgba[0] = rgba.R; Element->rgba[1] = rgba.G; Element->rgba[2] = rgba.B; Element->rgba[3] = rgba.A; } if (bOverride_fluidcoef) { for (int32 i = 0; i < fluidcoef.Num(); ++i) Element->fluid_coefs[i] = fluidcoef[i]; } @@ -279,18 +278,10 @@ void UMjGeom::ExportTo(mjsGeom* Element, mjsDefault* Default) void UMjGeom::Bind(mjModel* Model, mjData* Data, const FString& Prefix) { Super::Bind(Model, Data, Prefix); - m_GeomView = BindToView(Prefix); - + BindAndCacheView(m_GeomView, Prefix); if (m_GeomView.id != -1) { - m_ID = m_GeomView.id; SyncUnrealTransformFromMj(); - UE_LOG(LogURLabBind, Log, TEXT("[MjGeom] Successfully bound '%s' to ID %d (MjName: %s)"), *GetName(), m_ID, *MjName); - } - else - { - UE_LOG(LogURLabBind, Warning, TEXT("[MjGeom] Geom '%s' FAILED bind. Prefix: %s, MjName: %s"), - *GetName(), *Prefix, *MjName); } } @@ -299,10 +290,10 @@ void UMjGeom::UpdateGlobalTransform() if (m_GeomView._m && m_GeomView._d && m_GeomView.id >= 0) { // Get world position from MuJoCo - FVector WorldPos = MjUtils::MjToUEPosition(m_GeomView.xpos); + FVector WorldPos = MjUtils::MjToUEPosition(m_GeomView.geom_xpos); FQuat WorldRot; mjtNum quat[4]; - mju_mat2Quat(quat, m_GeomView.xmat); + mju_mat2Quat(quat, m_GeomView.geom_xmat); WorldRot = MjUtils::MjToUERotation(quat); SetWorldLocation(WorldPos); @@ -314,7 +305,7 @@ FVector UMjGeom::GetWorldLocation() const { if (m_GeomView._m && m_GeomView._d && m_GeomView.id >= 0) { - return MjUtils::MjToUEPosition(m_GeomView.xpos); + return MjUtils::MjToUEPosition(m_GeomView.geom_xpos); } return GetComponentLocation(); } @@ -325,9 +316,9 @@ void UMjGeom::SetFriction(float NewFriction) bOverride_friction = true; // Update runtime model if bound - if (m_GeomView._m && m_GeomView._d && m_GeomView.id >= 0 && m_GeomView.friction) + if (m_GeomView._m && m_GeomView._d && m_GeomView.id >= 0 && m_GeomView.geom_friction) { - m_GeomView.friction[0] = NewFriction; + m_GeomView.geom_friction[0] = NewFriction; } } @@ -935,8 +926,7 @@ void UMjGeom::RemoveDecomposition() {} #endif #if WITH_EDITOR -TArray UMjGeom::GetDefaultClassOptions() const -{ - return GetSiblingComponentOptions(this, UMjDefault::StaticClass(), true); -} +// --- CODEGEN_EDITOR_OPTIONS_START --- +TArray UMjGeom::GetDefaultClassOptions() const { return UMjComponent::GetSiblingComponentOptions(this, UMjDefault::StaticClass(), true); } + // --- CODEGEN_EDITOR_OPTIONS_END --- #endif diff --git a/Source/URLab/Private/MuJoCo/Components/Geometry/MjSite.cpp b/Source/URLab/Private/MuJoCo/Components/Geometry/MjSite.cpp index 5b27f4f..2669fac 100644 --- a/Source/URLab/Private/MuJoCo/Components/Geometry/MjSite.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Geometry/MjSite.cpp @@ -142,24 +142,13 @@ void UMjSite::RegisterToSpec(FMujocoSpecWrapper& Wrapper, mjsBody* ParentBody) void UMjSite::Bind(mjModel* model, mjData* data, const FString& Prefix) { Super::Bind(model, data, Prefix); - m_SiteView = BindToView(Prefix); - - if (m_SiteView.id != -1) - { - m_ID = m_SiteView.id; - UE_LOG(LogURLabBind, Log, TEXT("[MjSite] Successfully bound '%s' to ID %d (MjName: %s)"), *GetName(), m_ID, *MjName); - } - else - { - UE_LOG(LogURLabBind, Warning, TEXT("[MjSite] Site '%s' FAILED bind. Prefix: %s, MjName: %s"), *GetName(), *Prefix, *MjName); - } + BindAndCacheView(m_SiteView, Prefix); } #if WITH_EDITOR -TArray UMjSite::GetDefaultClassOptions() const -{ - return GetSiblingComponentOptions(this, UMjDefault::StaticClass(), true); -} +// --- CODEGEN_EDITOR_OPTIONS_START --- +TArray UMjSite::GetDefaultClassOptions() const { return UMjComponent::GetSiblingComponentOptions(this, UMjDefault::StaticClass(), true); } + // --- CODEGEN_EDITOR_OPTIONS_END --- #endif // --- Multi-UCLASS subclass constructors -------------------------------------- diff --git a/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjBox.cpp b/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjBox.cpp index f240359..f05227a 100644 --- a/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjBox.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjBox.cpp @@ -149,9 +149,9 @@ void UMjBox::SyncUnrealTransformFromMj() // MuJoCo box size is half-extents. Unreal Cube is 100 units. // Size 0.5 -> scale 1.0 float r[3]; - r[0] = m_GeomView.size[0]; - r[1] = m_GeomView.size[1]; - r[2] = m_GeomView.size[2]; + r[0] = m_GeomView.geom_size[0]; + r[1] = m_GeomView.geom_size[1]; + r[2] = m_GeomView.geom_size[2]; FVector NewScale = FVector(r[0], r[1], r[2]) * 2.0f; SetRelativeScale3D(NewScale); diff --git a/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjCapsule.cpp b/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjCapsule.cpp index fb508c4..74bdb03 100644 --- a/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjCapsule.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjCapsule.cpp @@ -184,8 +184,8 @@ void UMjCapsule::SyncUnrealTransformFromMj() if (!bOverride_size) { - const float RadiusVal = m_GeomView.size[0]; - const float HalfLengthVal = m_GeomView.size[1]; + const float RadiusVal = m_GeomView.geom_size[0]; + const float HalfLengthVal = m_GeomView.geom_size[1]; const FVector NewScale = FVector(RadiusVal * 2.0f, RadiusVal * 2.0f, HalfLengthVal * 2.0f); SetRelativeScale3D(NewScale); diff --git a/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjCylinder.cpp b/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjCylinder.cpp index 4035d2b..a16aa88 100644 --- a/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjCylinder.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjCylinder.cpp @@ -131,8 +131,8 @@ void UMjCylinder::SyncUnrealTransformFromMj() { // MuJoCo cylinder size: [radius, half-length] // Unreal Cylinder: diameter=100, Height=100 - float RadiusVal = m_GeomView.size[0]; - float HalfLengthVal = m_GeomView.size[1]; + float RadiusVal = m_GeomView.geom_size[0]; + float HalfLengthVal = m_GeomView.geom_size[1]; FVector NewScale = FVector(RadiusVal * 2.0f, RadiusVal * 2.0f, HalfLengthVal * 2.0f); SetRelativeScale3D(NewScale); diff --git a/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjEllipsoid.cpp b/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjEllipsoid.cpp index 674f5d0..8549126 100644 --- a/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjEllipsoid.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjEllipsoid.cpp @@ -41,7 +41,7 @@ void UMjEllipsoid::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } @@ -52,6 +52,6 @@ void UMjEllipsoid::ExportTo(mjsGeom* Element, mjsDefault* Default) Super::ExportTo(Element, Default); // --- CODEGEN_EXPORT_START --- - + // (no type-specific schema exports) // --- CODEGEN_EXPORT_END --- } diff --git a/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjPlane.cpp b/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjPlane.cpp index d836d7a..00fbd43 100644 --- a/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjPlane.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjPlane.cpp @@ -41,7 +41,7 @@ void UMjPlane::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& Co if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } @@ -52,6 +52,6 @@ void UMjPlane::ExportTo(mjsGeom* Element, mjsDefault* Default) Super::ExportTo(Element, Default); // --- CODEGEN_EXPORT_START --- - + // (no type-specific schema exports) // --- CODEGEN_EXPORT_END --- } diff --git a/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjSdf.cpp b/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjSdf.cpp index 90eff86..318c2cd 100644 --- a/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjSdf.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjSdf.cpp @@ -41,7 +41,7 @@ void UMjSdf::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& Comp if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } @@ -52,6 +52,6 @@ void UMjSdf::ExportTo(mjsGeom* Element, mjsDefault* Default) Super::ExportTo(Element, Default); // --- CODEGEN_EXPORT_START --- - + // (no type-specific schema exports) // --- CODEGEN_EXPORT_END --- } diff --git a/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjSphere.cpp b/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjSphere.cpp index 80fa9e6..8b17e1d 100644 --- a/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjSphere.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjSphere.cpp @@ -126,7 +126,7 @@ void UMjSphere::SyncUnrealTransformFromMj() if (!bOverride_size) { // MuJoCo sphere size is radius. Unreal Sphere is 100 units diameter. - float RadiusVal = m_GeomView.size[0]; + float RadiusVal = m_GeomView.geom_size[0]; FVector NewScale = FVector(RadiusVal * 2.0f); SetRelativeScale3D(NewScale); diff --git a/Source/URLab/Private/MuJoCo/Components/Joints/MjBallJoint.cpp b/Source/URLab/Private/MuJoCo/Components/Joints/MjBallJoint.cpp index 884f5a2..47f6fd2 100644 --- a/Source/URLab/Private/MuJoCo/Components/Joints/MjBallJoint.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Joints/MjBallJoint.cpp @@ -13,31 +13,27 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Joints/MjBallJoint.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjBallJoint::UMjBallJoint() { - bOverride_Type = true; Type = EMjJointType::Ball; -} - -void UMjBallJoint::ExportTo(mjsJoint* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- + bOverride_Type = true; } void UMjBallJoint::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) @@ -46,7 +42,17 @@ void UMjBallJoint::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjBallJoint::ExportTo(mjsJoint* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Joints/MjHingeJoint.cpp b/Source/URLab/Private/MuJoCo/Components/Joints/MjHingeJoint.cpp index f8077a3..3809256 100644 --- a/Source/URLab/Private/MuJoCo/Components/Joints/MjHingeJoint.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Joints/MjHingeJoint.cpp @@ -13,31 +13,27 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Joints/MjHingeJoint.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjHingeJoint::UMjHingeJoint() { - bOverride_Type = true; Type = EMjJointType::Hinge; -} - -void UMjHingeJoint::ExportTo(mjsJoint* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- + bOverride_Type = true; } void UMjHingeJoint::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) @@ -46,7 +42,17 @@ void UMjHingeJoint::ImportFromXml(const FXmlNode* Node, const FMjCompilerSetting if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjHingeJoint::ExportTo(mjsJoint* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Joints/MjJoint.cpp b/Source/URLab/Private/MuJoCo/Components/Joints/MjJoint.cpp index 65b0d8f..1118bba 100644 --- a/Source/URLab/Private/MuJoCo/Components/Joints/MjJoint.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Joints/MjJoint.cpp @@ -42,6 +42,7 @@ void UMjJoint::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& Co if (!Node) return; // --- CODEGEN_IMPORT_START --- + MjXmlUtils::ReadAttrString(Node, TEXT("class"), MjClassName); { // xml_enum: type -> EMjJointType FString S = Node->GetAttribute(TEXT("type")); S = S.ToLower(); @@ -52,16 +53,18 @@ void UMjJoint::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& Co if (!S.IsEmpty()) bOverride_Type = true; } MjXmlUtils::ReadAttrInt(Node, TEXT("group"), group, bOverride_group); + MjXmlUtils::ReadAttrVec3(Node, TEXT("axis"), Axis, bOverride_Axis); + if (bOverride_Axis) Axis.Y = -Axis.Y; MjXmlUtils::ReadAttrFloatArray(Node, TEXT("springdamper"), springdamper, bOverride_springdamper); MjXmlUtils::ReadAttrBool(Node, TEXT("limited"), limited, bOverride_limited); - MjXmlUtils::ReadAttrBool(Node, TEXT("actuatorfrclimited"), actuatorfrclimited, bOverride_actuatorfrclimited); + MjXmlUtils::ReadAttrBool(Node, TEXT("actuatorfrclimited"), ActFrcLimited, bOverride_ActFrcLimited); MjXmlUtils::ReadAttrFloatArray(Node, TEXT("solreflimit"), solreflimit, bOverride_solreflimit); MjXmlUtils::ReadAttrFloatArray(Node, TEXT("solimplimit"), solimplimit, bOverride_solimplimit); MjXmlUtils::ReadAttrFloatArray(Node, TEXT("solreffriction"), solreffriction, bOverride_solreffriction); MjXmlUtils::ReadAttrFloatArray(Node, TEXT("solimpfriction"), solimpfriction, bOverride_solimpfriction); MjXmlUtils::ReadAttrFloatArray(Node, TEXT("stiffness"), stiffness, bOverride_stiffness); MjXmlUtils::ReadAttrFloatArray(Node, TEXT("range"), range, bOverride_range); - MjXmlUtils::ReadAttrFloatArray(Node, TEXT("actuatorfrcrange"), actuatorfrcrange, bOverride_actuatorfrcrange); + MjXmlUtils::ReadAttrFloatArray(Node, TEXT("actuatorfrcrange"), ActFrcRange, bOverride_ActFrcRange); MjXmlUtils::ReadAttrFloat(Node, TEXT("actuatorgravcomp"), actuatorgravcomp, bOverride_actuatorgravcomp); MjXmlUtils::ReadAttrFloat(Node, TEXT("margin"), margin, bOverride_margin); MjXmlUtils::ReadAttrFloat(Node, TEXT("ref"), ref, bOverride_ref); @@ -69,6 +72,8 @@ void UMjJoint::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& Co MjXmlUtils::ReadAttrFloat(Node, TEXT("armature"), armature, bOverride_armature); MjXmlUtils::ReadAttrFloatArray(Node, TEXT("damping"), damping, bOverride_damping); MjXmlUtils::ReadAttrFloat(Node, TEXT("frictionloss"), frictionloss, bOverride_frictionloss); + MjUtils::ReadVec3InMeters(Node, TEXT("pos"), Pos, bOverride_Pos); + if (bOverride_Pos) SetRelativeLocation(Pos); if (bOverride_range) { if (Type == EMjJointType::Slide) { for (float& V : range) { V *= 100.0f; } } @@ -86,26 +91,8 @@ void UMjJoint::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& Co } // --- CODEGEN_IMPORT_END --- - // Class Name - MjXmlUtils::ReadAttrString(Node, TEXT("class"), MjClassName); - - // Axis — convert from MuJoCo to UE direction-vector convention (negate Y, no scale) - FString AxisStr; - if (MjXmlUtils::ReadAttrString(Node, TEXT("axis"), AxisStr)) - { - bOverride_Axis = true; - FVector RawAxis = MjXmlUtils::ParseVector(AxisStr); - Axis = FVector(RawAxis.X, -RawAxis.Y, RawAxis.Z); - } - - - FString PosStr; - if (MjXmlUtils::ReadAttrString(Node, TEXT("pos"), PosStr)) - { - FVector RawPos = MjXmlUtils::ParseVector(PosStr); - double p[3] = { (double)RawPos.X, (double)RawPos.Y, (double)RawPos.Z }; - SetRelativeLocation(MjUtils::MjToUEPosition(p)); - } + // axis (Y-negate vec3_convert) + pos (spatial_pose canon) are + // codegen-owned via the joint rule in codegen_rules.json. // Note: autolimits (limited inferred from range) is handled by the MuJoCo spec // compiler (mjLIMITED_AUTO default). We do not replicate that logic here. @@ -120,20 +107,19 @@ void UMjJoint::ExportTo(mjsJoint* Element, mjsDefault* Default) { if (!Element) return; - FVector _pos = GetRelativeLocation(); - if (!_pos.IsZero()) MjUtils::UEToMjPosition(_pos, Element->pos); - - if (bOverride_Axis) - { - // Convert UE direction vector back to MuJoCo convention (negate Y, no scale) - Element->axis[0] = Axis.X; - Element->axis[1] = -Axis.Y; - Element->axis[2] = Axis.Z; - } + // axis + pos exports are codegen-emitted between the CODEGEN_EXPORT + // markers below (spatial_pose canon writes pos, vec3_convert.axis + // applies the Y-negate to the codegen-emitted axis write). // Slide joints: convert ref from cm (UE) back to meters (MuJoCo) // --- CODEGEN_EXPORT_START --- + if (bOverride_Pos) + { + double TmpPos[3]; + MjUtils::UEToMjPosition(Pos, TmpPos); + Element->pos[0] = TmpPos[0]; Element->pos[1] = TmpPos[1]; Element->pos[2] = TmpPos[2]; + } if (bOverride_Type) { switch (Type) @@ -146,15 +132,16 @@ void UMjJoint::ExportTo(mjsJoint* Element, mjsDefault* Default) } } if (bOverride_group) Element->group = group; + if (bOverride_Axis) { Element->axis[0] = Axis.X; Element->axis[1] = -Axis.Y; Element->axis[2] = Axis.Z; } if (bOverride_springdamper) { for (int32 i = 0; i < springdamper.Num(); ++i) Element->springdamper[i] = springdamper[i]; } if (bOverride_limited) Element->limited = limited ? 1 : 0; - if (bOverride_actuatorfrclimited) Element->actfrclimited = actuatorfrclimited ? 1 : 0; + if (bOverride_ActFrcLimited) Element->actfrclimited = ActFrcLimited ? 1 : 0; if (bOverride_solreflimit) { for (int32 i = 0; i < solreflimit.Num(); ++i) Element->solref_limit[i] = solreflimit[i]; } if (bOverride_solimplimit) { for (int32 i = 0; i < solimplimit.Num(); ++i) Element->solimp_limit[i] = solimplimit[i]; } if (bOverride_solreffriction) { for (int32 i = 0; i < solreffriction.Num(); ++i) Element->solref_friction[i] = solreffriction[i]; } if (bOverride_solimpfriction) { for (int32 i = 0; i < solimpfriction.Num(); ++i) Element->solimp_friction[i] = solimpfriction[i]; } if (bOverride_stiffness) { for (int32 i = 0; i < stiffness.Num(); ++i) Element->stiffness[i] = stiffness[i]; } - if (bOverride_actuatorfrcrange) { for (int32 i = 0; i < actuatorfrcrange.Num(); ++i) Element->actfrcrange[i] = actuatorfrcrange[i]; } + if (bOverride_ActFrcRange) { for (int32 i = 0; i < ActFrcRange.Num(); ++i) Element->actfrcrange[i] = ActFrcRange[i]; } if (bOverride_actuatorgravcomp) Element->actgravcomp = actuatorgravcomp; if (bOverride_margin) Element->margin = margin; if (bOverride_armature) Element->armature = armature; @@ -190,9 +177,7 @@ void UMjJoint::ExportTo(mjsJoint* Element, mjsDefault* Default) void UMjJoint::Bind(mjModel* Model, mjData* Data, const FString& Prefix) { Super::Bind(Model, Data, Prefix); - m_JointView = BindToView(Prefix); - if (m_JointView.id != -1) m_ID = m_JointView.id; - else UE_LOG(LogURLabBind, Warning, TEXT("Failed to bind Joint %s"), *GetName()); + BindAndCacheView(m_JointView, Prefix); } float UMjJoint::GetPosition() const @@ -240,8 +225,8 @@ float UMjJoint::GetAcceleration() const FVector2D UMjJoint::GetJointRange() const { - if (m_JointView.id < 0 || !m_JointView.range) return FVector2D::ZeroVector; - return FVector2D((float)m_JointView.range[0], (float)m_JointView.range[1]); + if (m_JointView.id < 0 || !m_JointView.jnt_range) return FVector2D::ZeroVector; + return FVector2D((float)m_JointView.jnt_range[0], (float)m_JointView.jnt_range[1]); } FVector UMjJoint::GetWorldAnchor() const @@ -290,7 +275,7 @@ EMjJointType UMjJoint::GetResolvedType() const // Runtime: use compiled model if (m_JointView.id >= 0) { - switch (m_JointView.type) + switch (m_JointView.jnt_type) { case mjJNT_FREE: return EMjJointType::Free; case mjJNT_BALL: return EMjJointType::Ball; @@ -378,10 +363,10 @@ FVector2D UMjJoint::GetResolvedRange() const }; // Runtime: use compiled model (rad/m). - if (m_JointView.id >= 0 && m_JointView.range) + if (m_JointView.id >= 0 && m_JointView.jnt_range) { - return FVector2D(MjToUE((float)m_JointView.range[0]), - MjToUE((float)m_JointView.range[1])); + return FVector2D(MjToUE((float)m_JointView.jnt_range[0]), + MjToUE((float)m_JointView.jnt_range[1])); } // Editor: local override wins. Already in UE units. @@ -416,10 +401,10 @@ FVector2D UMjJoint::GetResolvedRange() const bool UMjJoint::GetResolvedLimited() const { // Runtime: use compiled model range - if (m_JointView.id >= 0 && m_JointView.range) + if (m_JointView.id >= 0 && m_JointView.jnt_range) { // MuJoCo sets range to (0,0) when unlimited - return m_JointView.range[0] != 0.0 || m_JointView.range[1] != 0.0; + return m_JointView.jnt_range[0] != 0.0 || m_JointView.jnt_range[1] != 0.0; } // Editor: local override wins @@ -465,13 +450,13 @@ void UMjJoint::BuildBinaryPayload(FBufferArchive& OutBuffer) const int32 JointID = m_ID; OutBuffer << JointID; - float Pos = GetPosition(); - float Vel = GetVelocity(); - float Acc = GetAcceleration(); + float JointPos = GetPosition(); + float JointVel = GetVelocity(); + float JointAcc = GetAcceleration(); - OutBuffer << Pos; - OutBuffer << Vel; - OutBuffer << Acc; + OutBuffer << JointPos; + OutBuffer << JointVel; + OutBuffer << JointAcc; } FString UMjJoint::GetTelemetryTopicName() const @@ -480,8 +465,7 @@ FString UMjJoint::GetTelemetryTopicName() const } #if WITH_EDITOR -TArray UMjJoint::GetDefaultClassOptions() const -{ - return GetSiblingComponentOptions(this, UMjDefault::StaticClass(), true); -} +// --- CODEGEN_EDITOR_OPTIONS_START --- +TArray UMjJoint::GetDefaultClassOptions() const { return UMjComponent::GetSiblingComponentOptions(this, UMjDefault::StaticClass(), true); } + // --- CODEGEN_EDITOR_OPTIONS_END --- #endif diff --git a/Source/URLab/Private/MuJoCo/Components/Joints/MjSlideJoint.cpp b/Source/URLab/Private/MuJoCo/Components/Joints/MjSlideJoint.cpp index 5c159b2..5946baf 100644 --- a/Source/URLab/Private/MuJoCo/Components/Joints/MjSlideJoint.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Joints/MjSlideJoint.cpp @@ -13,31 +13,27 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Joints/MjSlideJoint.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjSlideJoint::UMjSlideJoint() { - bOverride_Type = true; Type = EMjJointType::Slide; -} - -void UMjSlideJoint::ExportTo(mjsJoint* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- + bOverride_Type = true; } void UMjSlideJoint::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) @@ -46,7 +42,17 @@ void UMjSlideJoint::ImportFromXml(const FXmlNode* Node, const FMjCompilerSetting if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjSlideJoint::ExportTo(mjsJoint* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Keyframes/MjKeyframe.cpp b/Source/URLab/Private/MuJoCo/Components/Keyframes/MjKeyframe.cpp index 7bdd43c..2f2336c 100644 --- a/Source/URLab/Private/MuJoCo/Components/Keyframes/MjKeyframe.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Keyframes/MjKeyframe.cpp @@ -26,6 +26,7 @@ #include "MuJoCo/Components/Joints/MjFreeJoint.h" #include "MuJoCo/Components/Actuators/MjActuator.h" #include "MuJoCo/Utils/MjXmlUtils.h" +#include "MuJoCo/Utils/MjUtils.h" #include "XmlNode.h" #include "Utils/URLabLogging.h" @@ -58,36 +59,12 @@ void UMjKeyframe::ExportTo(mjsKey* Element, mjsDefault* Default) // --- CODEGEN_EXPORT_START --- if (bOverride_Time) Element->time = Time; - if (bOverride_Qpos && Element->qpos) - { - Element->qpos->clear(); - for (float V : Qpos) Element->qpos->push_back((double)V); - } - if (bOverride_Qvel && Element->qvel) - { - Element->qvel->clear(); - for (float V : Qvel) Element->qvel->push_back((double)V); - } - if (bOverride_Act && Element->act) - { - Element->act->clear(); - for (float V : Act) Element->act->push_back((double)V); - } - if (bOverride_Ctrl && Element->ctrl) - { - Element->ctrl->clear(); - for (float V : Ctrl) Element->ctrl->push_back((double)V); - } - if (bOverride_Mpos && Element->mpos) - { - Element->mpos->clear(); - for (float V : Mpos) Element->mpos->push_back((double)V); - } - if (bOverride_Mquat && Element->mquat) - { - Element->mquat->clear(); - for (float V : Mquat) Element->mquat->push_back((double)V); - } + if (bOverride_Qpos) MjSetDoubleVec(Element->qpos, Qpos); + if (bOverride_Qvel) MjSetDoubleVec(Element->qvel, Qvel); + if (bOverride_Act) MjSetDoubleVec(Element->act, Act); + if (bOverride_Ctrl) MjSetDoubleVec(Element->ctrl, Ctrl); + if (bOverride_Mpos) MjSetDoubleVec(Element->mpos, Mpos); + if (bOverride_Mquat) MjSetDoubleVec(Element->mquat, Mquat); // --- CODEGEN_EXPORT_END --- } @@ -153,16 +130,8 @@ static FKeyframeDimensions CountDimensions(AActor* Owner) return D; } -namespace -{ - // Helper for overwriting an mjDoubleVec* with a TArray. - void SetVec(mjDoubleVec* Dest, const TArray& Src) - { - if (!Dest) return; - Dest->clear(); - for (float V : Src) Dest->push_back((double)V); - } -} +// Helper consolidated into MjUtils::MjSetDoubleVec (Phase 3e.8). Kept +// here as a thin alias so the padding paths below stay readable. void UMjKeyframe::RegisterToSpec(FMujocoSpecWrapper& Wrapper, mjsBody* ParentBody) { @@ -199,7 +168,7 @@ void UMjKeyframe::RegisterToSpec(FMujocoSpecWrapper& Wrapper, mjsBody* ParentBod Padded.Append({0.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0.0f, 0.0f}); } Padded.Append(Qpos); - SetVec(Key->qpos, Padded); + MjSetDoubleVec(Key->qpos, Padded); UE_LOG(LogURLabImport, Log, TEXT("[MjKeyframe] '%s': padded qpos %d -> %d (%d free joints)"), *TName, Qpos.Num(), Padded.Num(), Dims.NumFreeJoints); } @@ -218,7 +187,7 @@ void UMjKeyframe::RegisterToSpec(FMujocoSpecWrapper& Wrapper, mjsBody* ParentBod Padded.Append({0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}); } Padded.Append(Qvel); - SetVec(Key->qvel, Padded); + MjSetDoubleVec(Key->qvel, Padded); UE_LOG(LogURLabImport, Log, TEXT("[MjKeyframe] '%s': padded qvel %d -> %d"), *TName, Qvel.Num(), Padded.Num()); } diff --git a/Source/URLab/Private/MuJoCo/Components/Physics/MjContactExclude.cpp b/Source/URLab/Private/MuJoCo/Components/Physics/MjContactExclude.cpp index a2da014..54093b3 100644 --- a/Source/URLab/Private/MuJoCo/Components/Physics/MjContactExclude.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Physics/MjContactExclude.cpp @@ -21,6 +21,7 @@ // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. #include "MuJoCo/Components/Physics/MjContactExclude.h" +#include "MuJoCo/Utils/MjUtils.h" #include "XmlFile.h" #include "mujoco/mujoco.h" #include "MuJoCo/Core/Spec/MjSpecWrapper.h" @@ -42,6 +43,7 @@ void UMjContactExclude::BeginPlay() void UMjContactExclude::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { // --- CODEGEN_IMPORT_START --- + MjXmlUtils::ReadAttrString(Node, TEXT("name"), Name); if (MjXmlUtils::ReadAttrString(Node, TEXT("body1"), body1)) bOverride_body1 = true; if (MjXmlUtils::ReadAttrString(Node, TEXT("body2"), body2)) bOverride_body2 = true; // --- CODEGEN_IMPORT_END --- @@ -50,13 +52,6 @@ void UMjContactExclude::ImportFromXml(const FXmlNode* Node, const FMjCompilerSet { return; } - - // Required attributes - body1 = Node->GetAttribute(TEXT("body1")); - body2 = Node->GetAttribute(TEXT("body2")); - - // Optional attributes - Name = Node->GetAttribute(TEXT("name")); } void UMjContactExclude::ExportTo(mjsExclude* Element) @@ -64,8 +59,8 @@ void UMjContactExclude::ExportTo(mjsExclude* Element) if (!Element) return; // --- CODEGEN_EXPORT_START --- - if (bOverride_body1 && !body1.IsEmpty()) mjs_setString(Element->bodyname1, TCHAR_TO_UTF8(*body1)); - if (bOverride_body2 && !body2.IsEmpty()) mjs_setString(Element->bodyname2, TCHAR_TO_UTF8(*body2)); + if (bOverride_body1) MjSetString(Element->bodyname1, body1); + if (bOverride_body2) MjSetString(Element->bodyname2, body2); // --- CODEGEN_EXPORT_END --- } @@ -76,14 +71,8 @@ void UMjContactExclude::RegisterToSpec(FMujocoSpecWrapper& Wrapper, mjsBody* Par UE_LOG(LogURLabWrapper, Log, TEXT("Added contact exclude: %s<->%s"), *body1, *body2); } -void UMjContactExclude::Bind(mjModel* model, mjData* data, const FString& Prefix) -{ - // Contact excludes are global static data. -} - #if WITH_EDITOR -TArray UMjContactExclude::GetBodyOptions() const -{ - return UMjComponent::GetSiblingComponentOptions(this, UMjBody::StaticClass()); -} +// --- CODEGEN_EDITOR_OPTIONS_START --- +TArray UMjContactExclude::GetBodyOptions() const { return UMjComponent::GetSiblingComponentOptions(this, UMjBody::StaticClass()); } + // --- CODEGEN_EDITOR_OPTIONS_END --- #endif diff --git a/Source/URLab/Private/MuJoCo/Components/Physics/MjContactPair.cpp b/Source/URLab/Private/MuJoCo/Components/Physics/MjContactPair.cpp index 9035544..be676ff 100644 --- a/Source/URLab/Private/MuJoCo/Components/Physics/MjContactPair.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Physics/MjContactPair.cpp @@ -21,6 +21,7 @@ // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. #include "MuJoCo/Components/Physics/MjContactPair.h" +#include "MuJoCo/Utils/MjUtils.h" #include "XmlFile.h" #include "mujoco/mujoco.h" #include "MuJoCo/Core/Spec/MjSpecWrapper.h" @@ -43,6 +44,7 @@ void UMjContactPair::BeginPlay() void UMjContactPair::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { // --- CODEGEN_IMPORT_START --- + MjXmlUtils::ReadAttrString(Node, TEXT("name"), Name); if (MjXmlUtils::ReadAttrString(Node, TEXT("geom1"), geom1)) bOverride_geom1 = true; if (MjXmlUtils::ReadAttrString(Node, TEXT("geom2"), geom2)) bOverride_geom2 = true; MjXmlUtils::ReadAttrInt(Node, TEXT("condim"), condim, bOverride_condim); @@ -59,23 +61,6 @@ void UMjContactPair::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettin return; } - // Required attributes - - // Optional attributes - MjXmlUtils::ReadAttrString(Node, TEXT("name"), Name); - - { - bool bCondimOverride = false; - } - - // Parse friction/solref/solimp arrays - { - bool bFrictionOverride = false, bSolrefOverride = false, bSolimpOverride = false; - } - - { - bool bGapOverride = false, bMarginOverride = false; - } } void UMjContactPair::ExportTo(mjsPair* Element) @@ -83,8 +68,8 @@ void UMjContactPair::ExportTo(mjsPair* Element) if (!Element) return; // --- CODEGEN_EXPORT_START --- - if (bOverride_geom1 && !geom1.IsEmpty()) mjs_setString(Element->geomname1, TCHAR_TO_UTF8(*geom1)); - if (bOverride_geom2 && !geom2.IsEmpty()) mjs_setString(Element->geomname2, TCHAR_TO_UTF8(*geom2)); + if (bOverride_geom1) MjSetString(Element->geomname1, geom1); + if (bOverride_geom2) MjSetString(Element->geomname2, geom2); if (bOverride_condim) Element->condim = condim; if (bOverride_friction) { for (int32 i = 0; i < friction.Num(); ++i) Element->friction[i] = friction[i]; } if (bOverride_solref) { for (int32 i = 0; i < solref.Num(); ++i) Element->solref[i] = solref[i]; } @@ -106,14 +91,8 @@ void UMjContactPair::RegisterToSpec(FMujocoSpecWrapper& Wrapper, mjsBody* Parent UE_LOG(LogURLabWrapper, Log, TEXT("Added contact pair: %s->%s"), *geom1, *geom2); } -void UMjContactPair::Bind(mjModel* model, mjData* data, const FString& Prefix) -{ - // Contact pairs are global static data in MuJoCo, usually not bound to runtime indices easily or needed for runtime update. -} - #if WITH_EDITOR -TArray UMjContactPair::GetGeomOptions() const -{ - return UMjComponent::GetSiblingComponentOptions(this, UMjGeom::StaticClass()); -} +// --- CODEGEN_EDITOR_OPTIONS_START --- +TArray UMjContactPair::GetGeomOptions() const { return UMjComponent::GetSiblingComponentOptions(this, UMjGeom::StaticClass()); } + // --- CODEGEN_EDITOR_OPTIONS_END --- #endif diff --git a/Source/URLab/Private/MuJoCo/Components/Physics/MjInertial.cpp b/Source/URLab/Private/MuJoCo/Components/Physics/MjInertial.cpp index 306ad7d..96aafdc 100644 --- a/Source/URLab/Private/MuJoCo/Components/Physics/MjInertial.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Physics/MjInertial.cpp @@ -86,6 +86,3 @@ void UMjInertial::RegisterToSpec(FMujocoSpecWrapper& Wrapper, mjsBody* ParentBod MjUtils::UEToMjRotation(RelTrans.GetRotation(), ParentBody->iquat); } -void UMjInertial::Bind(mjModel* model, mjData* data, const FString& Prefix) -{ -} diff --git a/Source/URLab/Private/MuJoCo/Components/QuickConvert/AMjHeightfieldActor.cpp b/Source/URLab/Private/MuJoCo/Components/QuickConvert/AMjHeightfieldActor.cpp index 6a4d0d1..d1e8c75 100644 --- a/Source/URLab/Private/MuJoCo/Components/QuickConvert/AMjHeightfieldActor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/QuickConvert/AMjHeightfieldActor.cpp @@ -21,6 +21,7 @@ // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. #include "MuJoCo/Components/QuickConvert/AMjHeightfieldActor.h" +#include "MuJoCo/Utils/MjUtils.h" #include "DrawDebugHelpers.h" #include "MuJoCo/Components/QuickConvert/MjQuickConvertComponent.h" @@ -340,7 +341,7 @@ void AMjHeightfieldActor::Setup(mjSpec* Spec, mjVFS* /*VFS*/) mjs_setName(Geom->element, TCHAR_TO_UTF8(*GeomName)); Geom->type = mjGEOM_HFIELD; - mjs_setString(Geom->hfieldname, TCHAR_TO_UTF8(*HFieldName)); + MjSetStringRaw(Geom->hfieldname, HFieldName); Geom->pos[0] = (Bounds.Min.X + Bounds.Max.X) / 200.0; Geom->pos[1] = -(Bounds.Min.Y + Bounds.Max.Y) / 200.0; diff --git a/Source/URLab/Private/MuJoCo/Components/QuickConvert/MjQuickConvertComponent.cpp b/Source/URLab/Private/MuJoCo/Components/QuickConvert/MjQuickConvertComponent.cpp index 8bd095d..495cbd1 100644 --- a/Source/URLab/Private/MuJoCo/Components/QuickConvert/MjQuickConvertComponent.cpp +++ b/Source/URLab/Private/MuJoCo/Components/QuickConvert/MjQuickConvertComponent.cpp @@ -76,10 +76,10 @@ void UMjQuickConvertComponent::DrawDebugCollision() { if (!World) return; for (auto geom_view : m_CreatedBody->GetMj().Geoms()) { - int meshId = geom_view.dataid; + int meshId = geom_view.geom_dataid; - mjtNum* pos = geom_view.xpos; - mjtNum* mat = geom_view.xmat; + mjtNum* pos = geom_view.geom_xpos; + mjtNum* mat = geom_view.geom_xmat; FVector Position = FVector(pos[0], -pos[1], pos[2]); Position *= Multiplier; diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjAccelerometer.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjAccelerometer.cpp index 6e61b1b..15aeed8 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjAccelerometer.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjAccelerometer.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjAccelerometer.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjAccelerometer::UMjAccelerometer() { Type = EMjSensorType::Accelerometer; } -void UMjAccelerometer::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjAccelerometer::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjAccelerometer::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjActuatorFrcSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjActuatorFrcSensor.cpp index 6da948f..8c1c1e1 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjActuatorFrcSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjActuatorFrcSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjActuatorFrcSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjActuatorFrcSensor::UMjActuatorFrcSensor() { Type = EMjSensorType::ActuatorFrc; } -void UMjActuatorFrcSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjActuatorFrcSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjActuatorFrcSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjActuatorPosSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjActuatorPosSensor.cpp index 7264c0b..2667c95 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjActuatorPosSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjActuatorPosSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjActuatorPosSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjActuatorPosSensor::UMjActuatorPosSensor() { Type = EMjSensorType::ActuatorPos; } -void UMjActuatorPosSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjActuatorPosSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjActuatorPosSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjActuatorVelSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjActuatorVelSensor.cpp index 856142f..943ec91 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjActuatorVelSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjActuatorVelSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjActuatorVelSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjActuatorVelSensor::UMjActuatorVelSensor() { Type = EMjSensorType::ActuatorVel; } -void UMjActuatorVelSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjActuatorVelSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjActuatorVelSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjBallAngVelSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjBallAngVelSensor.cpp index 40cb1a2..7b1e8a2 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjBallAngVelSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjBallAngVelSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjBallAngVelSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjBallAngVelSensor::UMjBallAngVelSensor() { Type = EMjSensorType::BallAngVel; } -void UMjBallAngVelSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjBallAngVelSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjBallAngVelSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjBallQuatSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjBallQuatSensor.cpp index 0da6eb5..b81903f 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjBallQuatSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjBallQuatSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjBallQuatSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjBallQuatSensor::UMjBallQuatSensor() { Type = EMjSensorType::BallQuat; } -void UMjBallQuatSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjBallQuatSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjBallQuatSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjCamProjectionSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjCamProjectionSensor.cpp index ce59afb..d7deabf 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjCamProjectionSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjCamProjectionSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjCamProjectionSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjCamProjectionSensor::UMjCamProjectionSensor() { Type = EMjSensorType::CamProjection; } -void UMjCamProjectionSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjCamProjectionSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjCamProjectionSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjCamera.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjCamera.cpp index b41cbf9..d4067ad 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjCamera.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjCamera.cpp @@ -692,7 +692,7 @@ void UMjCamera::ExportTo(mjsCamera* Element, mjsDefault* /*def*/) if (bOverride_ipd) Element->ipd = ipd; if (bOverride_resolution) { for (int32 i = 0; i < resolution.Num(); ++i) Element->resolution[i] = resolution[i]; } if (bOverride_output) Element->output = output; - if (bOverride_target && !target.IsEmpty()) mjs_setString(Element->targetbody, TCHAR_TO_UTF8(*target)); + if (bOverride_target) MjSetString(Element->targetbody, target); if (bOverride_focal) { for (int32 i = 0; i < focal.Num(); ++i) Element->focal_length[i] = focal[i]; } if (bOverride_focalpixel) { for (int32 i = 0; i < focalpixel.Num(); ++i) Element->focal_pixel[i] = focalpixel[i]; } if (bOverride_principal) { for (int32 i = 0; i < principal.Num(); ++i) Element->principal_length[i] = principal[i]; } @@ -712,6 +712,7 @@ void UMjCamera::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& C if (!Node) return; // --- CODEGEN_IMPORT_START --- + MjXmlUtils::ReadAttrString(Node, TEXT("name"), MjName); { // xml_enum: mode -> EMjCameraTrackingMode FString S = Node->GetAttribute(TEXT("mode")); S = S.ToLower(); @@ -752,9 +753,9 @@ void UMjCamera::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& C if (bOverride_Quat) SetRelativeRotation(Quat); // --- CODEGEN_IMPORT_END --- - // Name - if (!MjXmlUtils::ReadAttrString(Node, TEXT("name"), MjName)) - MjName = TEXT("Camera"); + // Name fallback (codegen above reads MjName from the "name" attribute; + // here we provide a sensible default if the user omitted it). + if (MjName.IsEmpty()) MjName = TEXT("Camera"); // fovy FString FovyStr = Node->GetAttribute(TEXT("fovy")); diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjClockSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjClockSensor.cpp index 68fffe2..c57125b 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjClockSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjClockSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjClockSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjClockSensor::UMjClockSensor() { Type = EMjSensorType::Clock; } -void UMjClockSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjClockSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjClockSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjContactSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjContactSensor.cpp index c1f3011..cde9646 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjContactSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjContactSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjContactSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjContactSensor::UMjContactSensor() { Type = EMjSensorType::Contact; } -void UMjContactSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjContactSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjContactSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjEKineticSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjEKineticSensor.cpp index 2542a32..01f7275 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjEKineticSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjEKineticSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjEKineticSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjEKineticSensor::UMjEKineticSensor() { Type = EMjSensorType::EKinetic; } -void UMjEKineticSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjEKineticSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjEKineticSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjEPotentialSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjEPotentialSensor.cpp index a8bd394..202cf62 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjEPotentialSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjEPotentialSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjEPotentialSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjEPotentialSensor::UMjEPotentialSensor() { Type = EMjSensorType::EPotential; } -void UMjEPotentialSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjEPotentialSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjEPotentialSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjForceSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjForceSensor.cpp index 3e140fc..3de8e3a 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjForceSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjForceSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjForceSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjForceSensor::UMjForceSensor() { Type = EMjSensorType::Force; } -void UMjForceSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjForceSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjForceSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameAngAccSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameAngAccSensor.cpp index b597799..9608dcc 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameAngAccSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameAngAccSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjFrameAngAccSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjFrameAngAccSensor::UMjFrameAngAccSensor() { Type = EMjSensorType::FrameAngAcc; } -void UMjFrameAngAccSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjFrameAngAccSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjFrameAngAccSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameAngVelSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameAngVelSensor.cpp index bc614eb..b5952f0 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameAngVelSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameAngVelSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjFrameAngVelSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjFrameAngVelSensor::UMjFrameAngVelSensor() { Type = EMjSensorType::FrameAngVel; } -void UMjFrameAngVelSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjFrameAngVelSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjFrameAngVelSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameLinAccSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameLinAccSensor.cpp index 5421170..925f269 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameLinAccSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameLinAccSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjFrameLinAccSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjFrameLinAccSensor::UMjFrameLinAccSensor() { Type = EMjSensorType::FrameLinAcc; } -void UMjFrameLinAccSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjFrameLinAccSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjFrameLinAccSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameLinVelSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameLinVelSensor.cpp index 29a6c1a..3064df3 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameLinVelSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameLinVelSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjFrameLinVelSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjFrameLinVelSensor::UMjFrameLinVelSensor() { Type = EMjSensorType::FrameLinVel; } -void UMjFrameLinVelSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjFrameLinVelSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjFrameLinVelSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjFramePosSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjFramePosSensor.cpp index 768fb3e..716a940 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjFramePosSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjFramePosSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjFramePosSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjFramePosSensor::UMjFramePosSensor() { Type = EMjSensorType::FramePos; } -void UMjFramePosSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjFramePosSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjFramePosSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameQuatSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameQuatSensor.cpp index 1d1b016..c16132b 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameQuatSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameQuatSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjFrameQuatSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjFrameQuatSensor::UMjFrameQuatSensor() { Type = EMjSensorType::FrameQuat; } -void UMjFrameQuatSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjFrameQuatSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjFrameQuatSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameXAxisSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameXAxisSensor.cpp index b5671a7..a9d2b56 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameXAxisSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameXAxisSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjFrameXAxisSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjFrameXAxisSensor::UMjFrameXAxisSensor() { Type = EMjSensorType::FrameXAxis; } -void UMjFrameXAxisSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjFrameXAxisSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjFrameXAxisSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameYAxisSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameYAxisSensor.cpp index 7de49a0..e9d237a 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameYAxisSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameYAxisSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjFrameYAxisSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjFrameYAxisSensor::UMjFrameYAxisSensor() { Type = EMjSensorType::FrameYAxis; } -void UMjFrameYAxisSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjFrameYAxisSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjFrameYAxisSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameZAxisSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameZAxisSensor.cpp index f12fa5d..79f8c0e 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameZAxisSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjFrameZAxisSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjFrameZAxisSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjFrameZAxisSensor::UMjFrameZAxisSensor() { Type = EMjSensorType::FrameZAxis; } -void UMjFrameZAxisSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjFrameZAxisSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjFrameZAxisSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjGeomDistSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjGeomDistSensor.cpp index f61fb61..72d8040 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjGeomDistSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjGeomDistSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjGeomDistSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjGeomDistSensor::UMjGeomDistSensor() { Type = EMjSensorType::GeomDist; } -void UMjGeomDistSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjGeomDistSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjGeomDistSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjGeomFromToSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjGeomFromToSensor.cpp index 822c0bf..220e01c 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjGeomFromToSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjGeomFromToSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjGeomFromToSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjGeomFromToSensor::UMjGeomFromToSensor() { Type = EMjSensorType::GeomFromTo; } -void UMjGeomFromToSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjGeomFromToSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjGeomFromToSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjGeomNormalSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjGeomNormalSensor.cpp index d30bf53..e7877aa 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjGeomNormalSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjGeomNormalSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjGeomNormalSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjGeomNormalSensor::UMjGeomNormalSensor() { Type = EMjSensorType::GeomNormal; } -void UMjGeomNormalSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjGeomNormalSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjGeomNormalSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjGyro.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjGyro.cpp index 020722e..1aa11ed 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjGyro.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjGyro.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjGyro.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjGyro::UMjGyro() { Type = EMjSensorType::Gyro; } -void UMjGyro::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjGyro::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjGyro::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjInsideSiteSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjInsideSiteSensor.cpp index d7323c9..a31eb6c 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjInsideSiteSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjInsideSiteSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjInsideSiteSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjInsideSiteSensor::UMjInsideSiteSensor() { Type = EMjSensorType::InsideSite; } -void UMjInsideSiteSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjInsideSiteSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjInsideSiteSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjJointActFrcSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjJointActFrcSensor.cpp index b8e2cba..1c4fc29 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjJointActFrcSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjJointActFrcSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjJointActFrcSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjJointActFrcSensor::UMjJointActFrcSensor() { Type = EMjSensorType::JointActFrc; } -void UMjJointActFrcSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjJointActFrcSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjJointActFrcSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjJointLimitFrcSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjJointLimitFrcSensor.cpp index 62becfd..eb80d81 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjJointLimitFrcSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjJointLimitFrcSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjJointLimitFrcSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjJointLimitFrcSensor::UMjJointLimitFrcSensor() { Type = EMjSensorType::JointLimitFrc; } -void UMjJointLimitFrcSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjJointLimitFrcSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjJointLimitFrcSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjJointLimitPosSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjJointLimitPosSensor.cpp index 4217fc9..0276d0e 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjJointLimitPosSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjJointLimitPosSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjJointLimitPosSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjJointLimitPosSensor::UMjJointLimitPosSensor() { Type = EMjSensorType::JointLimitPos; } -void UMjJointLimitPosSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjJointLimitPosSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjJointLimitPosSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjJointLimitVelSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjJointLimitVelSensor.cpp index c16ebbd..4916352 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjJointLimitVelSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjJointLimitVelSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjJointLimitVelSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjJointLimitVelSensor::UMjJointLimitVelSensor() { Type = EMjSensorType::JointLimitVel; } -void UMjJointLimitVelSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjJointLimitVelSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjJointLimitVelSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjJointVelSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjJointVelSensor.cpp index e0830f4..6e3c534 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjJointVelSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjJointVelSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjJointVelSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjJointVelSensor::UMjJointVelSensor() { Type = EMjSensorType::JointVel; } -void UMjJointVelSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjJointVelSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjJointVelSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjMagnetometer.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjMagnetometer.cpp index 977cf39..41afa06 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjMagnetometer.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjMagnetometer.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjMagnetometer.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjMagnetometer::UMjMagnetometer() { Type = EMjSensorType::Magnetometer; } -void UMjMagnetometer::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjMagnetometer::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjMagnetometer::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjPluginSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjPluginSensor.cpp index 261c0ba..eba640b 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjPluginSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjPluginSensor.cpp @@ -41,7 +41,7 @@ void UMjPluginSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSetti if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } @@ -52,6 +52,6 @@ void UMjPluginSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) Super::ExportTo(Element, Default); // --- CODEGEN_EXPORT_START --- - + // (no type-specific schema exports) // --- CODEGEN_EXPORT_END --- } diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjRangeFinderSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjRangeFinderSensor.cpp index 043f546..8fa9413 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjRangeFinderSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjRangeFinderSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjRangeFinderSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjRangeFinderSensor::UMjRangeFinderSensor() { Type = EMjSensorType::RangeFinder; } -void UMjRangeFinderSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjRangeFinderSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjRangeFinderSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjSensor.cpp index b9e2f52..b0bea05 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjSensor.cpp @@ -110,8 +110,8 @@ void UMjSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) { if (!Element) return; - if (!TargetName.IsEmpty()) mjs_setString(Element->objname, TCHAR_TO_UTF8(*TargetName)); - if (!ReferenceName.IsEmpty()) mjs_setString(Element->refname, TCHAR_TO_UTF8(*ReferenceName)); + MjSetString(Element->objname, TargetName); + MjSetString(Element->refname, ReferenceName); // Most built-in sensor types have `dim` derived from the sensor type // during mj_compile (e.g. accelerometer dim=3). Writing 0 here zeros @@ -126,76 +126,66 @@ void UMjSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) switch(Type) { - case EMjSensorType::Touch: Element->type = mjSENS_TOUCH; Element->objtype = mjOBJ_SITE; break; - case EMjSensorType::Accelerometer: Element->type = mjSENS_ACCELEROMETER; Element->objtype = mjOBJ_SITE; break; - case EMjSensorType::Velocimeter: Element->type = mjSENS_VELOCIMETER; Element->objtype = mjOBJ_SITE; break; - case EMjSensorType::Gyro: Element->type = mjSENS_GYRO; Element->objtype = mjOBJ_SITE; break; - case EMjSensorType::Force: Element->type = mjSENS_FORCE; Element->objtype = mjOBJ_SITE; break; - case EMjSensorType::Torque: Element->type = mjSENS_TORQUE; Element->objtype = mjOBJ_SITE; break; - case EMjSensorType::Magnetometer: Element->type = mjSENS_MAGNETOMETER; Element->objtype = mjOBJ_SITE; break; - - case EMjSensorType::CamProjection: - Element->type = mjSENS_CAMPROJECTION; - Element->objtype = mjOBJ_SITE; - Element->reftype = mjOBJ_CAMERA; - break; - + // --- CODEGEN_SENSOR_TYPE_SWITCH_START --- + case EMjSensorType::Touch: Element->type = mjSENS_TOUCH; Element->objtype = mjOBJ_SITE; break; + case EMjSensorType::Accelerometer: Element->type = mjSENS_ACCELEROMETER; Element->objtype = mjOBJ_SITE; break; + case EMjSensorType::Velocimeter: Element->type = mjSENS_VELOCIMETER; Element->objtype = mjOBJ_SITE; break; + case EMjSensorType::Gyro: Element->type = mjSENS_GYRO; Element->objtype = mjOBJ_SITE; break; + case EMjSensorType::Force: Element->type = mjSENS_FORCE; Element->objtype = mjOBJ_SITE; break; + case EMjSensorType::Torque: Element->type = mjSENS_TORQUE; Element->objtype = mjOBJ_SITE; break; + case EMjSensorType::Magnetometer: Element->type = mjSENS_MAGNETOMETER; Element->objtype = mjOBJ_SITE; break; + case EMjSensorType::CamProjection: Element->type = mjSENS_CAMPROJECTION; Element->objtype = mjOBJ_SITE; Element->reftype = mjOBJ_CAMERA; break; case EMjSensorType::RangeFinder: - Element->type = mjSENS_RANGEFINDER; - Element->objtype = (ObjType == EMjObjType::Camera) ? mjOBJ_CAMERA : mjOBJ_SITE; - break; - - case EMjSensorType::JointPos: Element->type = mjSENS_JOINTPOS; Element->objtype = mjOBJ_JOINT; break; - case EMjSensorType::JointVel: Element->type = mjSENS_JOINTVEL; Element->objtype = mjOBJ_JOINT; break; - case EMjSensorType::JointActFrc: Element->type = mjSENS_JOINTACTFRC; Element->objtype = mjOBJ_JOINT; break; - case EMjSensorType::BallQuat: Element->type = mjSENS_BALLQUAT; Element->objtype = mjOBJ_JOINT; break; - case EMjSensorType::BallAngVel: Element->type = mjSENS_BALLANGVEL; Element->objtype = mjOBJ_JOINT; break; - case EMjSensorType::JointLimitPos: Element->type = mjSENS_JOINTLIMITPOS; Element->objtype = mjOBJ_JOINT; break; - case EMjSensorType::JointLimitVel: Element->type = mjSENS_JOINTLIMITVEL; Element->objtype = mjOBJ_JOINT; break; - case EMjSensorType::JointLimitFrc: Element->type = mjSENS_JOINTLIMITFRC; Element->objtype = mjOBJ_JOINT; break; - - case EMjSensorType::TendonPos: Element->type = mjSENS_TENDONPOS; Element->objtype = mjOBJ_TENDON; break; - case EMjSensorType::TendonVel: Element->type = mjSENS_TENDONVEL; Element->objtype = mjOBJ_TENDON; break; - case EMjSensorType::TendonActFrc: Element->type = mjSENS_TENDONACTFRC; Element->objtype = mjOBJ_TENDON; break; - case EMjSensorType::TendonLimitPos: Element->type = mjSENS_TENDONLIMITPOS; Element->objtype = mjOBJ_TENDON; break; - case EMjSensorType::TendonLimitVel: Element->type = mjSENS_TENDONLIMITVEL; Element->objtype = mjOBJ_TENDON; break; - case EMjSensorType::TendonLimitFrc: Element->type = mjSENS_TENDONLIMITFRC; Element->objtype = mjOBJ_TENDON; break; - - case EMjSensorType::ActuatorPos: Element->type = mjSENS_ACTUATORPOS; Element->objtype = mjOBJ_ACTUATOR; break; - case EMjSensorType::ActuatorVel: Element->type = mjSENS_ACTUATORVEL; Element->objtype = mjOBJ_ACTUATOR; break; - case EMjSensorType::ActuatorFrc: Element->type = mjSENS_ACTUATORFRC; Element->objtype = mjOBJ_ACTUATOR; break; - - case EMjSensorType::FramePos: Element->type = mjSENS_FRAMEPOS; break; - case EMjSensorType::FrameQuat: Element->type = mjSENS_FRAMEQUAT; break; - case EMjSensorType::FrameXAxis: Element->type = mjSENS_FRAMEXAXIS; break; - case EMjSensorType::FrameYAxis: Element->type = mjSENS_FRAMEYAXIS; break; - case EMjSensorType::FrameZAxis: Element->type = mjSENS_FRAMEZAXIS; break; - case EMjSensorType::FrameLinVel: Element->type = mjSENS_FRAMELINVEL; break; - case EMjSensorType::FrameAngVel: Element->type = mjSENS_FRAMEANGVEL; break; - case EMjSensorType::FrameLinAcc: Element->type = mjSENS_FRAMELINACC; break; - case EMjSensorType::FrameAngAcc: Element->type = mjSENS_FRAMEANGACC; break; - - case EMjSensorType::InsideSite: Element->type = mjSENS_INSIDESITE; Element->objtype = (mjtObj)EnumToMjObj(ObjType); Element->reftype = mjOBJ_SITE; break; - case EMjSensorType::SubtreeCom: Element->type = mjSENS_SUBTREECOM; Element->objtype = mjOBJ_BODY; break; - case EMjSensorType::SubtreeLinVel: Element->type = mjSENS_SUBTREELINVEL; Element->objtype = mjOBJ_BODY; break; - case EMjSensorType::SubtreeAngMom: Element->type = mjSENS_SUBTREEANGMOM; Element->objtype = mjOBJ_BODY; break; - - case EMjSensorType::GeomDist: Element->type = mjSENS_GEOMDIST; break; - case EMjSensorType::GeomNormal: Element->type = mjSENS_GEOMNORMAL; break; - case EMjSensorType::GeomFromTo: Element->type = mjSENS_GEOMFROMTO; break; - - case EMjSensorType::Contact: Element->type = mjSENS_CONTACT; break; - case EMjSensorType::EPotential: Element->type = mjSENS_E_POTENTIAL; break; - case EMjSensorType::EKinetic: Element->type = mjSENS_E_KINETIC; break; - case EMjSensorType::Clock: Element->type = mjSENS_CLOCK; break; - - case EMjSensorType::Tactile: Element->type = mjSENS_TACTILE; Element->objtype = mjOBJ_MESH; Element->reftype = mjOBJ_GEOM; break; - case EMjSensorType::Plugin: Element->type = mjSENS_PLUGIN; break; - case EMjSensorType::User: Element->type = mjSENS_USER; break; - - default: Element->type = mjSENS_ACCELEROMETER; Element->objtype = mjOBJ_SITE; break; + Element->type = mjSENS_RANGEFINDER; Element->objtype = (ObjType == EMjObjType::Camera) ? mjOBJ_CAMERA : mjOBJ_SITE; break; + case EMjSensorType::JointPos: Element->type = mjSENS_JOINTPOS; Element->objtype = mjOBJ_JOINT; break; + case EMjSensorType::JointVel: Element->type = mjSENS_JOINTVEL; Element->objtype = mjOBJ_JOINT; break; + case EMjSensorType::BallQuat: Element->type = mjSENS_BALLQUAT; Element->objtype = mjOBJ_JOINT; break; + case EMjSensorType::BallAngVel: Element->type = mjSENS_BALLANGVEL; Element->objtype = mjOBJ_JOINT; break; + case EMjSensorType::JointLimitPos: Element->type = mjSENS_JOINTLIMITPOS; Element->objtype = mjOBJ_JOINT; break; + case EMjSensorType::JointLimitVel: Element->type = mjSENS_JOINTLIMITVEL; Element->objtype = mjOBJ_JOINT; break; + case EMjSensorType::JointLimitFrc: Element->type = mjSENS_JOINTLIMITFRC; Element->objtype = mjOBJ_JOINT; break; + case EMjSensorType::TendonPos: Element->type = mjSENS_TENDONPOS; Element->objtype = mjOBJ_TENDON; break; + case EMjSensorType::TendonVel: Element->type = mjSENS_TENDONVEL; Element->objtype = mjOBJ_TENDON; break; + case EMjSensorType::TendonLimitPos: Element->type = mjSENS_TENDONLIMITPOS; Element->objtype = mjOBJ_TENDON; break; + case EMjSensorType::TendonLimitVel: Element->type = mjSENS_TENDONLIMITVEL; Element->objtype = mjOBJ_TENDON; break; + case EMjSensorType::TendonLimitFrc: Element->type = mjSENS_TENDONLIMITFRC; Element->objtype = mjOBJ_TENDON; break; + case EMjSensorType::ActuatorPos: Element->type = mjSENS_ACTUATORPOS; Element->objtype = mjOBJ_ACTUATOR; break; + case EMjSensorType::ActuatorVel: Element->type = mjSENS_ACTUATORVEL; Element->objtype = mjOBJ_ACTUATOR; break; + case EMjSensorType::ActuatorFrc: Element->type = mjSENS_ACTUATORFRC; Element->objtype = mjOBJ_ACTUATOR; break; + case EMjSensorType::JointActFrc: Element->type = mjSENS_JOINTACTFRC; Element->objtype = mjOBJ_JOINT; break; + case EMjSensorType::TendonActFrc: Element->type = mjSENS_TENDONACTFRC; Element->objtype = mjOBJ_TENDON; break; + case EMjSensorType::FramePos: Element->type = mjSENS_FRAMEPOS; break; + case EMjSensorType::FrameQuat: Element->type = mjSENS_FRAMEQUAT; break; + case EMjSensorType::FrameXAxis: Element->type = mjSENS_FRAMEXAXIS; break; + case EMjSensorType::FrameYAxis: Element->type = mjSENS_FRAMEYAXIS; break; + case EMjSensorType::FrameZAxis: Element->type = mjSENS_FRAMEZAXIS; break; + case EMjSensorType::FrameLinVel: Element->type = mjSENS_FRAMELINVEL; break; + case EMjSensorType::FrameAngVel: Element->type = mjSENS_FRAMEANGVEL; break; + case EMjSensorType::FrameLinAcc: Element->type = mjSENS_FRAMELINACC; break; + case EMjSensorType::FrameAngAcc: Element->type = mjSENS_FRAMEANGACC; break; + case EMjSensorType::SubtreeCom: Element->type = mjSENS_SUBTREECOM; Element->objtype = mjOBJ_BODY; break; + case EMjSensorType::SubtreeLinVel: Element->type = mjSENS_SUBTREELINVEL; Element->objtype = mjOBJ_BODY; break; + case EMjSensorType::SubtreeAngMom: Element->type = mjSENS_SUBTREEANGMOM; Element->objtype = mjOBJ_BODY; break; + case EMjSensorType::InsideSite: Element->type = mjSENS_INSIDESITE; Element->reftype = mjOBJ_SITE; break; + case EMjSensorType::GeomDist: Element->type = mjSENS_GEOMDIST; break; + case EMjSensorType::GeomNormal: Element->type = mjSENS_GEOMNORMAL; break; + case EMjSensorType::GeomFromTo: Element->type = mjSENS_GEOMFROMTO; break; + case EMjSensorType::Contact: Element->type = mjSENS_CONTACT; break; + case EMjSensorType::EPotential: Element->type = mjSENS_E_POTENTIAL; Element->objtype = mjOBJ_UNKNOWN; break; + case EMjSensorType::EKinetic: Element->type = mjSENS_E_KINETIC; Element->objtype = mjOBJ_UNKNOWN; break; + case EMjSensorType::Clock: Element->type = mjSENS_CLOCK; Element->objtype = mjOBJ_UNKNOWN; break; + case EMjSensorType::Tactile: Element->type = mjSENS_TACTILE; Element->objtype = mjOBJ_MESH; Element->reftype = mjOBJ_GEOM; break; + case EMjSensorType::User: Element->type = mjSENS_USER; break; + case EMjSensorType::Plugin: Element->type = mjSENS_PLUGIN; break; + default: Element->type = mjSENS_ACCELEROMETER; Element->objtype = mjOBJ_SITE; break; + // --- CODEGEN_SENSOR_TYPE_SWITCH_END --- } + // Variable objtype / reftype handling. The codegen switch above sets + // STATIC objtype/reftype literals when sensor_per_type carries a + // mjOBJ_X value. For sensors whose objtype/reftype is "from_xml" or + // "computed" in MuJoCo, the UE side reads ObjType / RefType properties + // and translates them here AFTER the switch fires. if (Element->type >= mjSENS_FRAMEPOS && Element->type <= mjSENS_FRAMEANGACC) { Element->objtype = (mjtObj)EnumToMjObj(ObjType); @@ -206,8 +196,10 @@ void UMjSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) Element->objtype = (mjtObj)EnumToMjObj(ObjType); Element->reftype = (mjtObj)EnumToMjObj(RefType); } - else if (Type == EMjSensorType::User) + else if (Type == EMjSensorType::User || Type == EMjSensorType::InsideSite) { + // InsideSite's reftype = mjOBJ_SITE is already set by the codegen + // switch above; here we add the UE-driven objtype. Element->objtype = (mjtObj)EnumToMjObj(ObjType); } @@ -218,6 +210,8 @@ void UMjSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) if (bOverride_interval) { for (int32 i = 0; i < interval.Num(); ++i) Element->interval[i] = interval[i]; } if (bOverride_cutoff) Element->cutoff = cutoff; if (bOverride_noise) Element->noise = noise; + MjSetString(Element->objname, TargetName); + MjSetString(Element->refname, ReferenceName); // --- CODEGEN_EXPORT_END --- } @@ -226,72 +220,45 @@ void UMjSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& C if (!Node) return; // --- CODEGEN_IMPORT_START --- + MjXmlUtils::ReadAttrString(Node, TEXT("class"), MjClassName); + { // xml_enum: objtype -> EMjObjType + FString S = Node->GetAttribute(TEXT("objtype")); + S = S.ToLower(); + if (S == TEXT("body")) ObjType = EMjObjType::Body; + else if (S == TEXT("xbody")) ObjType = EMjObjType::XBody; + else if (S == TEXT("joint")) ObjType = EMjObjType::Joint; + else if (S == TEXT("dof")) ObjType = EMjObjType::DoF; + else if (S == TEXT("geom")) ObjType = EMjObjType::Geom; + else if (S == TEXT("site")) ObjType = EMjObjType::Site; + else if (S == TEXT("camera")) ObjType = EMjObjType::Camera; + else if (S == TEXT("light")) ObjType = EMjObjType::Light; + else if (S == TEXT("mesh")) ObjType = EMjObjType::Mesh; + else if (S == TEXT("hfield")) ObjType = EMjObjType::HField; + else if (S == TEXT("texture")) ObjType = EMjObjType::Texture; + else if (S == TEXT("material")) ObjType = EMjObjType::Material; + else if (S == TEXT("pair")) ObjType = EMjObjType::Pair; + else if (S == TEXT("exclude")) ObjType = EMjObjType::Exclude; + else if (S == TEXT("equality")) ObjType = EMjObjType::Equality; + else if (S == TEXT("tendon")) ObjType = EMjObjType::Tendon; + else if (S == TEXT("actuator")) ObjType = EMjObjType::Actuator; + } + { // xml_enum: reftype -> EMjObjType + FString S = Node->GetAttribute(TEXT("reftype")); + S = S.ToLower(); + if (S == TEXT("body")) RefType = EMjObjType::Body; + else if (S == TEXT("xbody")) RefType = EMjObjType::XBody; + else if (S == TEXT("joint")) RefType = EMjObjType::Joint; + else if (S == TEXT("geom")) RefType = EMjObjType::Geom; + else if (S == TEXT("site")) RefType = EMjObjType::Site; + else if (S == TEXT("camera")) RefType = EMjObjType::Camera; + } MjXmlUtils::ReadAttrInt(Node, TEXT("nsample"), nsample, bOverride_nsample); MjXmlUtils::ReadAttrInt(Node, TEXT("interp"), interp, bOverride_interp); MjXmlUtils::ReadAttrFloat(Node, TEXT("delay"), delay, bOverride_delay); MjXmlUtils::ReadAttrFloatArray(Node, TEXT("interval"), interval, bOverride_interval); MjXmlUtils::ReadAttrFloat(Node, TEXT("cutoff"), cutoff, bOverride_cutoff); MjXmlUtils::ReadAttrFloat(Node, TEXT("noise"), noise, bOverride_noise); - // --- CODEGEN_IMPORT_END --- - - // Determine sensor type from the XML tag name - static const TMap TagToType = { - {TEXT("touch"), EMjSensorType::Touch}, - {TEXT("accelerometer"), EMjSensorType::Accelerometer}, - {TEXT("velocimeter"), EMjSensorType::Velocimeter}, - {TEXT("gyro"), EMjSensorType::Gyro}, - {TEXT("force"), EMjSensorType::Force}, - {TEXT("torque"), EMjSensorType::Torque}, - {TEXT("magnetometer"), EMjSensorType::Magnetometer}, - {TEXT("rangefinder"), EMjSensorType::RangeFinder}, - {TEXT("camprojection"), EMjSensorType::CamProjection}, - {TEXT("jointpos"), EMjSensorType::JointPos}, - {TEXT("jointvel"), EMjSensorType::JointVel}, - {TEXT("jointactfrc"), EMjSensorType::JointActFrc}, - {TEXT("tendonpos"), EMjSensorType::TendonPos}, - {TEXT("tendonvel"), EMjSensorType::TendonVel}, - {TEXT("tendonactfrc"), EMjSensorType::TendonActFrc}, - {TEXT("actuatorpos"), EMjSensorType::ActuatorPos}, - {TEXT("actuatorvel"), EMjSensorType::ActuatorVel}, - {TEXT("actuatorfrc"), EMjSensorType::ActuatorFrc}, - {TEXT("ballquat"), EMjSensorType::BallQuat}, - {TEXT("ballangvel"), EMjSensorType::BallAngVel}, - {TEXT("jointlimitpos"), EMjSensorType::JointLimitPos}, - {TEXT("jointlimitvel"), EMjSensorType::JointLimitVel}, - {TEXT("jointlimitfrc"), EMjSensorType::JointLimitFrc}, - {TEXT("tendonlimitpos"), EMjSensorType::TendonLimitPos}, - {TEXT("tendonlimitvel"), EMjSensorType::TendonLimitVel}, - {TEXT("tendonlimitfrc"), EMjSensorType::TendonLimitFrc}, - {TEXT("framepos"), EMjSensorType::FramePos}, - {TEXT("framequat"), EMjSensorType::FrameQuat}, - {TEXT("framexaxis"), EMjSensorType::FrameXAxis}, - {TEXT("frameyaxis"), EMjSensorType::FrameYAxis}, - {TEXT("framezaxis"), EMjSensorType::FrameZAxis}, - {TEXT("framelinvel"), EMjSensorType::FrameLinVel}, - {TEXT("frameangvel"), EMjSensorType::FrameAngVel}, - {TEXT("framelinacc"), EMjSensorType::FrameLinAcc}, - {TEXT("frameangacc"), EMjSensorType::FrameAngAcc}, - {TEXT("subtreecom"), EMjSensorType::SubtreeCom}, - {TEXT("subtreelinvel"), EMjSensorType::SubtreeLinVel}, - {TEXT("subtreeangmom"), EMjSensorType::SubtreeAngMom}, - {TEXT("insidesite"), EMjSensorType::InsideSite}, - {TEXT("geomdist"), EMjSensorType::GeomDist}, - {TEXT("geomnormal"), EMjSensorType::GeomNormal}, - {TEXT("geomfromto"), EMjSensorType::GeomFromTo}, - {TEXT("contact"), EMjSensorType::Contact}, - {TEXT("e_potential"), EMjSensorType::EPotential}, - {TEXT("e_kinetic"), EMjSensorType::EKinetic}, - {TEXT("clock"), EMjSensorType::Clock}, - {TEXT("tactile"), EMjSensorType::Tactile}, - {TEXT("plugin"), EMjSensorType::Plugin}, - {TEXT("user"), EMjSensorType::User}, - }; - const FString Tag = Node->GetTag().ToLower(); - const EMjSensorType* Found = TagToType.Find(Tag); - if (Found) Type = *Found; - - - // Object name: try each attribute in priority order + // target_collation: -> TargetName TargetName = Node->GetAttribute(TEXT("site")); if (TargetName.IsEmpty()) TargetName = Node->GetAttribute(TEXT("joint")); if (TargetName.IsEmpty()) TargetName = Node->GetAttribute(TEXT("tendon")); @@ -299,46 +266,77 @@ void UMjSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& C if (TargetName.IsEmpty()) TargetName = Node->GetAttribute(TEXT("body")); if (TargetName.IsEmpty()) TargetName = Node->GetAttribute(TEXT("geom")); if (TargetName.IsEmpty()) TargetName = Node->GetAttribute(TEXT("objname")); - - // Reference name (for frame sensors, camprojection, etc.) + if (TargetName.IsEmpty()) TargetName = Node->GetAttribute(TEXT("camera")); + if (TargetName.IsEmpty()) TargetName = Node->GetAttribute(TEXT("mesh")); + // target_collation: -> ReferenceName ReferenceName = Node->GetAttribute(TEXT("refname")); + // --- CODEGEN_IMPORT_END --- - // objtype / reftype — string attributes specifying object/reference type for frame, - // geomfromto, contact, user, and camprojection sensors. - // Map from MJCF string → EMjObjType so ExportTo() can write the correct mjtObj enum. - static const TMap ObjTypeStrMap = { - {TEXT("body"), EMjObjType::Body}, - {TEXT("xbody"), EMjObjType::XBody}, - {TEXT("joint"), EMjObjType::Joint}, - {TEXT("dof"), EMjObjType::DoF}, - {TEXT("geom"), EMjObjType::Geom}, - {TEXT("site"), EMjObjType::Site}, - {TEXT("camera"), EMjObjType::Camera}, - {TEXT("light"), EMjObjType::Light}, - {TEXT("mesh"), EMjObjType::Mesh}, - {TEXT("hfield"), EMjObjType::HField}, - {TEXT("texture"), EMjObjType::Texture}, - {TEXT("material"), EMjObjType::Material}, - {TEXT("pair"), EMjObjType::Pair}, - {TEXT("exclude"), EMjObjType::Exclude}, - {TEXT("equality"), EMjObjType::Equality}, - {TEXT("tendon"), EMjObjType::Tendon}, - {TEXT("actuator"), EMjObjType::Actuator}, + // Determine sensor type from the XML tag name + static const TMap TagToType = { + // --- CODEGEN_SENSOR_TAG_TO_TYPE_START --- + {TEXT("touch"), EMjSensorType::Touch}, + {TEXT("accelerometer"), EMjSensorType::Accelerometer}, + {TEXT("velocimeter"), EMjSensorType::Velocimeter}, + {TEXT("gyro"), EMjSensorType::Gyro}, + {TEXT("force"), EMjSensorType::Force}, + {TEXT("torque"), EMjSensorType::Torque}, + {TEXT("magnetometer"), EMjSensorType::Magnetometer}, + {TEXT("camprojection"), EMjSensorType::CamProjection}, + {TEXT("rangefinder"), EMjSensorType::RangeFinder}, + {TEXT("jointpos"), EMjSensorType::JointPos}, + {TEXT("jointvel"), EMjSensorType::JointVel}, + {TEXT("ballquat"), EMjSensorType::BallQuat}, + {TEXT("ballangvel"), EMjSensorType::BallAngVel}, + {TEXT("jointlimitpos"), EMjSensorType::JointLimitPos}, + {TEXT("jointlimitvel"), EMjSensorType::JointLimitVel}, + {TEXT("jointlimitfrc"), EMjSensorType::JointLimitFrc}, + {TEXT("tendonpos"), EMjSensorType::TendonPos}, + {TEXT("tendonvel"), EMjSensorType::TendonVel}, + {TEXT("tendonlimitpos"), EMjSensorType::TendonLimitPos}, + {TEXT("tendonlimitvel"), EMjSensorType::TendonLimitVel}, + {TEXT("tendonlimitfrc"), EMjSensorType::TendonLimitFrc}, + {TEXT("actuatorpos"), EMjSensorType::ActuatorPos}, + {TEXT("actuatorvel"), EMjSensorType::ActuatorVel}, + {TEXT("actuatorfrc"), EMjSensorType::ActuatorFrc}, + {TEXT("jointactuatorfrc"), EMjSensorType::JointActFrc}, + {TEXT("tendonactuatorfrc"), EMjSensorType::TendonActFrc}, + {TEXT("framepos"), EMjSensorType::FramePos}, + {TEXT("framequat"), EMjSensorType::FrameQuat}, + {TEXT("framexaxis"), EMjSensorType::FrameXAxis}, + {TEXT("frameyaxis"), EMjSensorType::FrameYAxis}, + {TEXT("framezaxis"), EMjSensorType::FrameZAxis}, + {TEXT("framelinvel"), EMjSensorType::FrameLinVel}, + {TEXT("frameangvel"), EMjSensorType::FrameAngVel}, + {TEXT("framelinacc"), EMjSensorType::FrameLinAcc}, + {TEXT("frameangacc"), EMjSensorType::FrameAngAcc}, + {TEXT("subtreecom"), EMjSensorType::SubtreeCom}, + {TEXT("subtreelinvel"), EMjSensorType::SubtreeLinVel}, + {TEXT("subtreeangmom"), EMjSensorType::SubtreeAngMom}, + {TEXT("insidesite"), EMjSensorType::InsideSite}, + {TEXT("distance"), EMjSensorType::GeomDist}, + {TEXT("normal"), EMjSensorType::GeomNormal}, + {TEXT("fromto"), EMjSensorType::GeomFromTo}, + {TEXT("contact"), EMjSensorType::Contact}, + {TEXT("e_potential"), EMjSensorType::EPotential}, + {TEXT("e_kinetic"), EMjSensorType::EKinetic}, + {TEXT("clock"), EMjSensorType::Clock}, + {TEXT("tactile"), EMjSensorType::Tactile}, + {TEXT("user"), EMjSensorType::User}, + {TEXT("plugin"), EMjSensorType::Plugin}, + // --- CODEGEN_SENSOR_TAG_TO_TYPE_END --- }; + const FString Tag = Node->GetTag().ToLower(); + const EMjSensorType* Found = TagToType.Find(Tag); + if (Found) Type = *Found; - FString ObjTypeStr = Node->GetAttribute(TEXT("objtype")).ToLower(); - if (!ObjTypeStr.IsEmpty()) - { - const EMjObjType* FoundObjType = ObjTypeStrMap.Find(ObjTypeStr); - if (FoundObjType) ObjType = *FoundObjType; - } - FString RefTypeStr = Node->GetAttribute(TEXT("reftype")).ToLower(); - if (!RefTypeStr.IsEmpty()) - { - const EMjObjType* FoundRefType = ObjTypeStrMap.Find(RefTypeStr); - if (FoundRefType) RefType = *FoundRefType; - } + // TargetName / ReferenceName (target_collations), ObjType / RefType + // (xml_enum_attrs), MjClassName (common_imports) are all codegen-emitted + // inside the CODEGEN_IMPORT block above. dim / adr remain hand-written + // here because they need bespoke handling: dim is conditionally written + // (only if XML provides it, preserving the compile-time default), and + // adr is an out-of-band override for user sensors only. // dim override — used by user sensors where the dimension is not fixed by type FString DimStr = Node->GetAttribute(TEXT("dim")); @@ -353,23 +351,12 @@ void UMjSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& C bool bAdrOverride = false; MjXmlUtils::ReadAttrInt(Node, TEXT("adr"), UserAdr, bAdrOverride); } - - MjXmlUtils::ReadAttrString(Node, TEXT("class"), MjClassName); } void UMjSensor::Bind(mjModel* Model, mjData* Data, const FString& Prefix) { Super::Bind(Model, Data, Prefix); - m_SensorView = BindToView(Prefix); - - if (m_SensorView.id != -1) - { - m_ID = m_SensorView.id; - } - else - { - UE_LOG(LogURLabBind, Warning, TEXT("[MjSensor] Sensor '%s' could not bind! Prefix: %s"), *GetName(), *Prefix); - } + BindAndCacheView(m_SensorView, Prefix); } // Apply the MuJoCo → UE coordinate transform appropriate for each sensor type. @@ -452,10 +439,10 @@ static void TransformSensorReading(TArray& R, EMjSensorType Type) TArray UMjSensor::GetReading() const { TArray Result; - if (m_SensorView.id != -1 && m_SensorView.data) + if (m_SensorView.id != -1 && m_SensorView.sensordata) { - for (int i = 0; i < m_SensorView.dim; ++i) - Result.Add((float)m_SensorView.data[i]); + for (int i = 0; i < m_SensorView.sensor_dim; ++i) + Result.Add((float)m_SensorView.sensordata[i]); TransformSensorReading(Result, Type); } return Result; @@ -463,9 +450,9 @@ TArray UMjSensor::GetReading() const float UMjSensor::GetScalarReading() const { - if (m_SensorView.id != -1 && m_SensorView.data && m_SensorView.dim > 0) + if (m_SensorView.id != -1 && m_SensorView.sensordata && m_SensorView.sensor_dim > 0) { - return (float)m_SensorView.data[0]; + return (float)m_SensorView.sensordata[0]; } return 0.0f; } @@ -473,7 +460,7 @@ float UMjSensor::GetScalarReading() const int UMjSensor::GetDimension() const { if (m_SensorView.id != -1) - return m_SensorView.dim; + return m_SensorView.sensor_dim; return 0; } @@ -502,11 +489,11 @@ void UMjSensor::BuildBinaryPayload(FBufferArchive& OutBuffer) const int32 NumElements = GetDimension(); OutBuffer << NumElements; - if (m_SensorView.id != -1 && m_SensorView.data && NumElements > 0) + if (m_SensorView.id != -1 && m_SensorView.sensordata && NumElements > 0) { for (int i = 0; i < NumElements; ++i) { - float Val = (float)m_SensorView.data[i]; + float Val = (float)m_SensorView.sensordata[i]; OutBuffer << Val; } } @@ -547,8 +534,7 @@ TArray UMjSensor::GetReferenceNameOptions() const return UMjComponent::GetSiblingComponentOptions(this, GetClassForObjType(RefType)); } -TArray UMjSensor::GetDefaultClassOptions() const -{ - return UMjComponent::GetSiblingComponentOptions(this, UMjDefault::StaticClass(), true); -} +// --- CODEGEN_EDITOR_OPTIONS_START --- +TArray UMjSensor::GetDefaultClassOptions() const { return UMjComponent::GetSiblingComponentOptions(this, UMjDefault::StaticClass(), true); } + // --- CODEGEN_EDITOR_OPTIONS_END --- #endif diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjSubtreeAngMomSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjSubtreeAngMomSensor.cpp index 4f24533..9a43d3c 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjSubtreeAngMomSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjSubtreeAngMomSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjSubtreeAngMomSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjSubtreeAngMomSensor::UMjSubtreeAngMomSensor() { Type = EMjSensorType::SubtreeAngMom; } -void UMjSubtreeAngMomSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjSubtreeAngMomSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjSubtreeAngMomSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjSubtreeComSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjSubtreeComSensor.cpp index 5686734..de7e384 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjSubtreeComSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjSubtreeComSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjSubtreeComSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjSubtreeComSensor::UMjSubtreeComSensor() { Type = EMjSensorType::SubtreeCom; } -void UMjSubtreeComSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjSubtreeComSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjSubtreeComSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjSubtreeLinVelSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjSubtreeLinVelSensor.cpp index 3368496..fdef06c 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjSubtreeLinVelSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjSubtreeLinVelSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjSubtreeLinVelSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjSubtreeLinVelSensor::UMjSubtreeLinVelSensor() { Type = EMjSensorType::SubtreeLinVel; } -void UMjSubtreeLinVelSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjSubtreeLinVelSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjSubtreeLinVelSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonActFrcSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonActFrcSensor.cpp index 35d1e69..7a0929f 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonActFrcSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonActFrcSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjTendonActFrcSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjTendonActFrcSensor::UMjTendonActFrcSensor() { Type = EMjSensorType::TendonActFrc; } -void UMjTendonActFrcSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjTendonActFrcSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjTendonActFrcSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonLimitFrcSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonLimitFrcSensor.cpp index 6b070c1..c0863bc 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonLimitFrcSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonLimitFrcSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjTendonLimitFrcSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjTendonLimitFrcSensor::UMjTendonLimitFrcSensor() { Type = EMjSensorType::TendonLimitFrc; } -void UMjTendonLimitFrcSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjTendonLimitFrcSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjTendonLimitFrcSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonLimitPosSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonLimitPosSensor.cpp index 9561b40..f5dfa90 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonLimitPosSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonLimitPosSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjTendonLimitPosSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjTendonLimitPosSensor::UMjTendonLimitPosSensor() { Type = EMjSensorType::TendonLimitPos; } -void UMjTendonLimitPosSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjTendonLimitPosSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjTendonLimitPosSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonLimitVelSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonLimitVelSensor.cpp index fc06ebc..1b0574f 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonLimitVelSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonLimitVelSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjTendonLimitVelSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjTendonLimitVelSensor::UMjTendonLimitVelSensor() { Type = EMjSensorType::TendonLimitVel; } -void UMjTendonLimitVelSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjTendonLimitVelSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjTendonLimitVelSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonPosSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonPosSensor.cpp index c7898f8..0ed5e05 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonPosSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonPosSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjTendonPosSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjTendonPosSensor::UMjTendonPosSensor() { Type = EMjSensorType::TendonPos; } -void UMjTendonPosSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjTendonPosSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjTendonPosSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonVelSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonVelSensor.cpp index c3731b8..5cc0fc5 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonVelSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjTendonVelSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjTendonVelSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjTendonVelSensor::UMjTendonVelSensor() { Type = EMjSensorType::TendonVel; } -void UMjTendonVelSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjTendonVelSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjTendonVelSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjTorqueSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjTorqueSensor.cpp index 1687d15..6153425 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjTorqueSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjTorqueSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjTorqueSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjTorqueSensor::UMjTorqueSensor() { Type = EMjSensorType::Torque; } -void UMjTorqueSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjTorqueSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjTorqueSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjTouchSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjTouchSensor.cpp index dea2e54..be4fc56 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjTouchSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjTouchSensor.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjTouchSensor.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjTouchSensor::UMjTouchSensor() { Type = EMjSensorType::Touch; } -void UMjTouchSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjTouchSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjTouchSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjUserSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjUserSensor.cpp index e9b860b..1d2f578 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjUserSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjUserSensor.cpp @@ -41,7 +41,7 @@ void UMjUserSensor::ImportFromXml(const FXmlNode* Node, const FMjCompilerSetting if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } @@ -52,6 +52,6 @@ void UMjUserSensor::ExportTo(mjsSensor* Element, mjsDefault* Default) Super::ExportTo(Element, Default); // --- CODEGEN_EXPORT_START --- - + // (no type-specific schema exports) // --- CODEGEN_EXPORT_END --- } diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjVelocimeter.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjVelocimeter.cpp index 7c7c1a4..ba10c86 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjVelocimeter.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjVelocimeter.cpp @@ -13,39 +13,45 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #include "MuJoCo/Components/Sensors/MjVelocimeter.h" +#include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" +#include "MuJoCo/Utils/MjUtils.h" +#include "XmlNode.h" +#include "mujoco/mjspec.h" UMjVelocimeter::UMjVelocimeter() { Type = EMjSensorType::Velocimeter; } -void UMjVelocimeter::ExportTo(mjsSensor* Element, mjsDefault* Default) -{ - if (!Element) return; - - Super::ExportTo(Element, Default); - - // --- CODEGEN_EXPORT_START --- - - // --- CODEGEN_EXPORT_END --- -} - void UMjVelocimeter::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& CompilerSettings) { Super::ImportFromXml(Node, CompilerSettings); if (!Node) return; // --- CODEGEN_IMPORT_START --- - + // (no type-specific schema imports) // --- CODEGEN_IMPORT_END --- } +void UMjVelocimeter::ExportTo(mjsSensor* Element, mjsDefault* Default) +{ + if (!Element) return; + + Super::ExportTo(Element, Default); + + // --- CODEGEN_EXPORT_START --- + // (no type-specific schema exports) + // --- CODEGEN_EXPORT_END --- +} diff --git a/Source/URLab/Private/MuJoCo/Components/Tendons/MjTendon.cpp b/Source/URLab/Private/MuJoCo/Components/Tendons/MjTendon.cpp index 361f907..b8ee162 100644 --- a/Source/URLab/Private/MuJoCo/Components/Tendons/MjTendon.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Tendons/MjTendon.cpp @@ -46,11 +46,12 @@ void UMjTendon::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& C if (!Node) return; // --- CODEGEN_IMPORT_START --- + MjXmlUtils::ReadAttrString(Node, TEXT("class"), MjClassName); MjXmlUtils::ReadAttrInt(Node, TEXT("group"), group, bOverride_group); MjXmlUtils::ReadAttrBool(Node, TEXT("limited"), limited, bOverride_limited); - MjXmlUtils::ReadAttrBool(Node, TEXT("actuatorfrclimited"), actuatorfrclimited, bOverride_actuatorfrclimited); + MjXmlUtils::ReadAttrBool(Node, TEXT("actuatorfrclimited"), ActFrcLimited, bOverride_ActFrcLimited); MjXmlUtils::ReadAttrFloatArray(Node, TEXT("range"), range, bOverride_range); - MjXmlUtils::ReadAttrFloatArray(Node, TEXT("actuatorfrcrange"), actuatorfrcrange, bOverride_actuatorfrcrange); + MjXmlUtils::ReadAttrFloatArray(Node, TEXT("actuatorfrcrange"), ActFrcRange, bOverride_ActFrcRange); MjXmlUtils::ReadAttrFloatArray(Node, TEXT("solreflimit"), solreflimit, bOverride_solreflimit); MjXmlUtils::ReadAttrFloatArray(Node, TEXT("solimplimit"), solimplimit, bOverride_solimplimit); MjXmlUtils::ReadAttrFloatArray(Node, TEXT("solreffriction"), solreffriction, bOverride_solreffriction); @@ -66,15 +67,6 @@ void UMjTendon::ImportFromXml(const FXmlNode* Node, const FMjCompilerSettings& C MjXmlUtils::ReadAttrColor(Node, TEXT("rgba"), rgba, bOverride_rgba); // --- CODEGEN_IMPORT_END --- - // Class name - MjXmlUtils::ReadAttrString(Node, TEXT("class"), MjClassName); - - // --- Physics --- - - // --- Limits --- - MjXmlUtils::ReadAttrBool(Node, TEXT("actfrclimited"), bActFrcLimited, bOverride_ActFrcLimited); - MjXmlUtils::ReadAttrFloatArray(Node, TEXT("actfrcrange"), ActFrcRange, bOverride_ActFrcRange); - // --- Solver --- // --- Visual --- @@ -131,25 +123,12 @@ void UMjTendon::ExportTo(mjsTendon* Element, mjsDefault* def) // --- Physics properties --- - // --- Limits --- - - if (bOverride_ActFrcLimited) Element->actfrclimited = bActFrcLimited ? mjLIMITED_TRUE : mjLIMITED_FALSE; - if (bOverride_ActFrcRange) - { - for (int i = 0; i < ActFrcRange.Num() && i < 2; ++i) - Element->actfrcrange[i] = ActFrcRange[i]; - } - - // --- Solver --- - - // --- Visuals --- - - // --- CODEGEN_EXPORT_START --- + // --- CODEGEN_EXPORT_START --- if (bOverride_group) Element->group = group; if (bOverride_limited) Element->limited = limited ? 1 : 0; - if (bOverride_actuatorfrclimited) Element->actfrclimited = actuatorfrclimited ? 1 : 0; + if (bOverride_ActFrcLimited) Element->actfrclimited = ActFrcLimited ? 1 : 0; if (bOverride_range) { for (int32 i = 0; i < range.Num(); ++i) Element->range[i] = range[i]; } - if (bOverride_actuatorfrcrange) { for (int32 i = 0; i < actuatorfrcrange.Num(); ++i) Element->actfrcrange[i] = actuatorfrcrange[i]; } + if (bOverride_ActFrcRange) { for (int32 i = 0; i < ActFrcRange.Num(); ++i) Element->actfrcrange[i] = ActFrcRange[i]; } if (bOverride_solreflimit) { for (int32 i = 0; i < solreflimit.Num(); ++i) Element->solref_limit[i] = solreflimit[i]; } if (bOverride_solimplimit) { for (int32 i = 0; i < solimplimit.Num(); ++i) Element->solimp_limit[i] = solimplimit[i]; } if (bOverride_solreffriction) { for (int32 i = 0; i < solreffriction.Num(); ++i) Element->solref_friction[i] = solreffriction[i]; } @@ -248,16 +227,7 @@ void UMjTendon::RegisterToSpec(FMujocoSpecWrapper& Wrapper, mjsBody* ParentBody) void UMjTendon::Bind(mjModel* model, mjData* data, const FString& Prefix) { Super::Bind(model, data, Prefix); - m_TendonView = BindToView(Prefix); - if (m_TendonView.id != -1) - { - m_ID = m_TendonView.id; - } - else - { - UE_LOG(LogURLabImport, Warning, TEXT("[MjTendon] Failed to bind tendon '%s' (prefix='%s')"), - *GetName(), *Prefix); - } + BindAndCacheView(m_TendonView, Prefix); } float UMjTendon::GetLength() const @@ -277,10 +247,9 @@ FString UMjTendon::GetMjName() const } #if WITH_EDITOR -TArray UMjTendon::GetDefaultClassOptions() const -{ - return GetSiblingComponentOptions(this, UMjDefault::StaticClass(), true); -} +// --- CODEGEN_EDITOR_OPTIONS_START --- +TArray UMjTendon::GetDefaultClassOptions() const { return UMjComponent::GetSiblingComponentOptions(this, UMjDefault::StaticClass(), true); } + // --- CODEGEN_EDITOR_OPTIONS_END --- #endif // --- Multi-UCLASS subclass constructors -------------------------------------- diff --git a/Source/URLab/Private/MuJoCo/Core/MjArticulation.cpp b/Source/URLab/Private/MuJoCo/Core/MjArticulation.cpp index ec7f8d9..721360a 100644 --- a/Source/URLab/Private/MuJoCo/Core/MjArticulation.cpp +++ b/Source/URLab/Private/MuJoCo/Core/MjArticulation.cpp @@ -238,11 +238,30 @@ void AMjArticulation::UnPossessed() } +// Local helper for Phase 3e.9: collapses the 7 identical "GetComponents + +// for-loop + RegisterToSpec" blocks below into a one-liner per category. +// Flex stays special (needs ParentSpecBody resolution). +template +static void RegisterAllOf(AActor* Owner, FMujocoSpecWrapper& Wrapper, + bool bSkipDefaults = true) +{ + if (!Owner) return; + TArray All; + Owner->GetComponents(All); + for (T* C : All) + { + if (!C) continue; + if (bSkipDefaults && C->bIsDefault) continue; + C->RegisterToSpec(Wrapper); + } +} + + void AMjArticulation::Setup(mjSpec* Spec, mjVFS* VFS) { m_spec = Spec; m_vfs = VFS; - + m_ChildSpec = mj_makeSpec(); m_ChildSpec->compiler.degree = false; @@ -410,60 +429,30 @@ void AMjArticulation::Setup(mjSpec* Spec, mjVFS* VFS) } // 4. Add Tendons (into child spec, after bodies so joint names are set) - TArray Tendons; - GetComponents(Tendons); - for (UMjTendon* Tendon : Tendons) - { - if (Tendon && !Tendon->bIsDefault) - Tendon->RegisterToSpec(*m_wrapper); - } + RegisterAllOf(this, *m_wrapper); - // 5. Add Sensors and Actuators (into child spec, after tendons strings might be referenced) - TArray Sensors; - GetComponents(Sensors); - for (UMjSensor* Sensor : Sensors) - { - if (Sensor && !Sensor->bIsDefault) - Sensor->RegisterToSpec(*m_wrapper); - } + // 5. Add Sensors / Actuators (after tendons so tendon names resolve). + RegisterAllOf(this, *m_wrapper); + RegisterAllOf(this, *m_wrapper); - TArray Actuators; - GetComponents(Actuators); - for (UMjActuator* Actuator : Actuators) + // 6. Contact pairs / excludes inherit from IMjSpecElement (not + // UMjComponent) so they have no bIsDefault field — register all. { - if (Actuator && !Actuator->bIsDefault) - Actuator->RegisterToSpec(*m_wrapper); + TArray Pairs; + GetComponents(Pairs); + for (UMjContactPair* Pair : Pairs) + if (Pair) Pair->RegisterToSpec(*m_wrapper); } - - TArray ContactPairs; - GetComponents(ContactPairs); - for (UMjContactPair* Pair : ContactPairs) { - Pair->RegisterToSpec(*m_wrapper); + TArray Excludes; + GetComponents(Excludes); + for (UMjContactExclude* Excl : Excludes) + if (Excl) Excl->RegisterToSpec(*m_wrapper); } - TArray ContactExcludes; - GetComponents(ContactExcludes); - for (UMjContactExclude* Exclude : ContactExcludes) - { - Exclude->RegisterToSpec(*m_wrapper); - } - - TArray Equalities; - GetComponents(Equalities); - for (UMjEquality* Equality : Equalities) - { - if (Equality && !Equality->bIsDefault) - Equality->RegisterToSpec(*m_wrapper); - } - - TArray Keyframes; - GetComponents(Keyframes); - for (UMjKeyframe* Keyframe : Keyframes) - { - if (Keyframe && !Keyframe->bIsDefault) - Keyframe->RegisterToSpec(*m_wrapper); - } + // 7. Equalities + Keyframes. + RegisterAllOf(this, *m_wrapper); + RegisterAllOf(this, *m_wrapper); mjsBody* parentWorld = mjs_findBody(Spec, "world"); mjsFrame* attachmentFrame = mjs_addFrame(parentWorld, 0); @@ -695,73 +684,16 @@ void AMjArticulation::ApplyControls() // Blueprint Runtime API — Discovery // ========================================================================= -TArray AMjArticulation::GetActuatorNames() const -{ - TArray Names; - for (auto& Elem : ActuatorIdMap) - { - if (Elem.Value) Names.Add(Elem.Value->GetMjName()); - } - return Names; -} - -TArray AMjArticulation::GetActuators() const -{ - TArray Components; - ActuatorIdMap.GenerateValueArray(Components); - return Components; -} - -TArray AMjArticulation::GetJointNames() const -{ - TArray Names; - for (auto& Elem : JointIdMap) - { - if (Elem.Value) Names.Add(Elem.Value->GetMjName()); - } - return Names; -} - -TArray AMjArticulation::GetJoints() const -{ - TArray Components; - JointIdMap.GenerateValueArray(Components); - return Components; -} - -TArray AMjArticulation::GetSensorNames() const -{ - TArray Names; - for (auto& Elem : SensorIdMap) - { - if (Elem.Value) Names.Add(Elem.Value->GetMjName()); - } - return Names; -} - -TArray AMjArticulation::GetSensors() const -{ - TArray Components; - SensorIdMap.GenerateValueArray(Components); - return Components; -} +// --- Templated map-lookup wrappers (v8: implementations in MjArticulation.h templates) --- -TArray AMjArticulation::GetBodyNames() const -{ - TArray Names; - for (auto& Elem : BodyIdMap) - { - if (Elem.Value) Names.Add(Elem.Value->GetMjName()); - } - return Names; -} - -TArray AMjArticulation::GetBodies() const -{ - TArray Components; - BodyIdMap.GenerateValueArray(Components); - return Components; -} +TArray AMjArticulation::GetActuatorNames() const { return GetComponentNamesFromMap(ActuatorIdMap); } +TArray AMjArticulation::GetActuators() const { return GetComponentsFromMap(ActuatorIdMap); } +TArray AMjArticulation::GetJointNames() const { return GetComponentNamesFromMap(JointIdMap); } +TArray AMjArticulation::GetJoints() const { return GetComponentsFromMap(JointIdMap); } +TArray AMjArticulation::GetSensorNames() const { return GetComponentNamesFromMap(SensorIdMap); } +TArray AMjArticulation::GetSensors() const { return GetComponentsFromMap(SensorIdMap); } +TArray AMjArticulation::GetBodyNames() const { return GetComponentNamesFromMap(BodyIdMap); } +TArray AMjArticulation::GetBodies() const { return GetComponentsFromMap(BodyIdMap); } void AMjArticulation::WakeAll() { @@ -786,60 +718,15 @@ TArray AMjArticulation::GetFrames() const return Components; } -TArray AMjArticulation::GetGeoms() const -{ - TArray Components; - GeomIdMap.GenerateValueArray(Components); - return Components; -} - +TArray AMjArticulation::GetGeoms() const { return GetComponentsFromMap(GeomIdMap); } +TArray AMjArticulation::GetTendons() const { return GetComponentsFromMap(TendonIdMap); } +TArray AMjArticulation::GetTendonNames() const { return GetComponentNamesFromMap(TendonIdMap); } -UMjActuator* AMjArticulation::GetActuator(const FString& Name) const -{ - if (const auto* Ptr = ActuatorComponentMap.Find(Name)) return *Ptr; - return nullptr; -} - -UMjJoint* AMjArticulation::GetJoint(const FString& Name) const -{ - if (const auto* Ptr = JointComponentMap.Find(Name)) return *Ptr; - return nullptr; -} - -UMjSensor* AMjArticulation::GetSensor(const FString& Name) const -{ - if (const auto* Ptr = SensorComponentMap.Find(Name)) return *Ptr; - return nullptr; -} - -UMjBody* AMjArticulation::GetBody(const FString& Name) const -{ - if (const auto* Ptr = BodyComponentMap.Find(Name)) return *Ptr; - return nullptr; -} - -TArray AMjArticulation::GetTendons() const -{ - TArray Components; - TendonIdMap.GenerateValueArray(Components); - return Components; -} - -TArray AMjArticulation::GetTendonNames() const -{ - TArray Names; - for (auto& Elem : TendonIdMap) - { - if (Elem.Value) Names.Add(Elem.Value->GetMjName()); - } - return Names; -} - -UMjTendon* AMjArticulation::GetTendon(const FString& Name) const -{ - if (const auto* Ptr = TendonComponentMap.Find(Name)) return *Ptr; - return nullptr; -} +UMjActuator* AMjArticulation::GetActuator(const FString& Name) const { return GetComponentByNameInMap(Name, ActuatorComponentMap); } +UMjJoint* AMjArticulation::GetJoint (const FString& Name) const { return GetComponentByNameInMap(Name, JointComponentMap); } +UMjSensor* AMjArticulation::GetSensor (const FString& Name) const { return GetComponentByNameInMap(Name, SensorComponentMap); } +UMjBody* AMjArticulation::GetBody (const FString& Name) const { return GetComponentByNameInMap(Name, BodyComponentMap); } +UMjTendon* AMjArticulation::GetTendon (const FString& Name) const { return GetComponentByNameInMap(Name, TendonComponentMap); } TArray AMjArticulation::GetEqualities() const { @@ -1013,28 +900,22 @@ void AMjArticulation::StopHoldKeyframe() UMjComponent* AMjArticulation::GetComponentByMjId(mjtObj type, int32 id) const { + // Single-lookup dispatch via GetComponentByIdInMap (v8). Each branch + // is a single Map.Find + nullptr-return, matching the standalone Get*ByMjId + // helpers below. switch (type) { - case mjOBJ_BODY: return GetBodyByMjId(id); - case mjOBJ_GEOM: return GetGeomByMjId(id); - case mjOBJ_JOINT: return JointIdMap.Contains(id) ? JointIdMap[id] : nullptr; - case mjOBJ_SENSOR: return SensorIdMap.Contains(id) ? SensorIdMap[id] : nullptr; - case mjOBJ_ACTUATOR: return ActuatorIdMap.Contains(id) ? ActuatorIdMap[id] : nullptr; + case mjOBJ_BODY: return GetComponentByIdInMap(id, BodyIdMap); + case mjOBJ_GEOM: return GetComponentByIdInMap(id, GeomIdMap); + case mjOBJ_JOINT: return GetComponentByIdInMap(id, JointIdMap); + case mjOBJ_SENSOR: return GetComponentByIdInMap(id, SensorIdMap); + case mjOBJ_ACTUATOR: return GetComponentByIdInMap(id, ActuatorIdMap); default: return nullptr; } } -UMjBody* AMjArticulation::GetBodyByMjId(int32 id) const -{ - if (const auto* Ptr = BodyIdMap.Find(id)) return *Ptr; - return nullptr; -} - -UMjGeom* AMjArticulation::GetGeomByMjId(int32 id) const -{ - if (const auto* Ptr = GeomIdMap.Find(id)) return *Ptr; - return nullptr; -} +UMjBody* AMjArticulation::GetBodyByMjId(int32 id) const { return GetComponentByIdInMap(id, BodyIdMap); } +UMjGeom* AMjArticulation::GetGeomByMjId(int32 id) const { return GetComponentByIdInMap(id, GeomIdMap); } bool AMjArticulation::SetActuatorControl(const FString& ActuatorName, float Value) { @@ -1140,14 +1021,14 @@ void AMjArticulation::DrawDebugJoints() { // Runtime mode: use compiled model data const JointView& JV = Joint->GetMj(); - MjType = JV.type; + MjType = JV.jnt_type; Anchor = Joint->GetWorldAnchor(); Axis = Joint->GetWorldAxis(); - if (JV.range) + if (JV.jnt_range) { - RangeMin = (float)JV.range[0]; - RangeMax = (float)JV.range[1]; + RangeMin = (float)JV.jnt_range[0]; + RangeMax = (float)JV.jnt_range[1]; bLimited = (RangeMin != 0.0f || RangeMax != 0.0f); } else @@ -1229,13 +1110,13 @@ void AMjArticulation::DrawDebugSites() { // Runtime: use compiled model data const SiteView& SV = Site->GetMj(); - if (!SV.xpos) continue; + if (!SV.site_xpos) continue; - Pos = MjUtils::MjToUEPosition(SV.xpos); - Radius = (SV.size) ? (float)SV.size[0] * 100.0f : 1.0f; // meters → cm - Color = (SV.rgba) ? FColor( - (uint8)(SV.rgba[0] * 255), (uint8)(SV.rgba[1] * 255), - (uint8)(SV.rgba[2] * 255), 200) : FColor(128, 128, 128, 200); + Pos = MjUtils::MjToUEPosition(SV.site_xpos); + Radius = (SV.site_size) ? (float)SV.site_size[0] * 100.0f : 1.0f; // meters → cm + Color = (SV.site_rgba) ? FColor( + (uint8)(SV.site_rgba[0] * 255), (uint8)(SV.site_rgba[1] * 255), + (uint8)(SV.site_rgba[2] * 255), 200) : FColor(128, 128, 128, 200); } else { diff --git a/Source/URLab/Private/MuJoCo/Core/MjDebugVisualizer.cpp b/Source/URLab/Private/MuJoCo/Core/MjDebugVisualizer.cpp index 5c32888..3fc5fef 100644 --- a/Source/URLab/Private/MuJoCo/Core/MjDebugVisualizer.cpp +++ b/Source/URLab/Private/MuJoCo/Core/MjDebugVisualizer.cpp @@ -495,7 +495,7 @@ void UMjDebugVisualizer::UpdateBodyOverlays() for (UMjGeom* Geom : Geoms) { if (!Geom || !Geom->IsBound()) continue; - const int32 BodyId = Geom->GetMj().body_id; + const int32 BodyId = Geom->GetMj().geom_bodyid; ApplyToMesh(Geom->GetVisualizerMesh(), BodyId, ArtHash); @@ -654,7 +654,7 @@ void UMjDebugVisualizer::BuildSegPool(EMjCameraMode mode) for (UMjGeom* Geom : Geoms) { if (!Geom || !Geom->IsBound()) continue; - const int32 BodyId = Geom->GetMj().body_id; + const int32 BodyId = Geom->GetMj().geom_bodyid; AddSibling(Geom->GetVisualizerMesh(), BodyId, ArtHash); diff --git a/Source/URLab/Private/MuJoCo/Core/MjSimOptions.cpp b/Source/URLab/Private/MuJoCo/Core/MjSimOptions.cpp deleted file mode 100644 index af9a63c..0000000 --- a/Source/URLab/Private/MuJoCo/Core/MjSimOptions.cpp +++ /dev/null @@ -1,142 +0,0 @@ -// Copyright (c) 2026 Jonathan Embley-Riches. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -// -// --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are -// trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. -// -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), -// CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. -#include "MuJoCo/Core/MjSimOptions.h" -#include - -void FMuJoCoOptions::ApplyToSpec(mjSpec* Spec) const -{ - if (!Spec) return; - - if (bOverride_MemoryMB) - { - Spec->memory = static_cast(MemoryMB) * 1024 * 1024; - } - - Spec->option.timestep = Timestep; - - // Gravity: UE cm/s² → MuJoCo m/s², negate Y for handedness - Spec->option.gravity[0] = Gravity.X / 100.0; - Spec->option.gravity[1] = -Gravity.Y / 100.0; - Spec->option.gravity[2] = Gravity.Z / 100.0; - - Spec->option.wind[0] = Wind.X / 100.0; - Spec->option.wind[1] = -Wind.Y / 100.0; - Spec->option.wind[2] = Wind.Z / 100.0; - - Spec->option.magnetic[0] = Magnetic.X; - Spec->option.magnetic[1] = -Magnetic.Y; - Spec->option.magnetic[2] = Magnetic.Z; - - Spec->option.density = Density; - Spec->option.viscosity = Viscosity; - Spec->option.impratio = Impratio; - Spec->option.tolerance = Tolerance; - Spec->option.iterations = Iterations; - Spec->option.ls_iterations = LsIterations; - - if (bOverride_Integrator) Spec->option.integrator = (int)Integrator; - if (bOverride_Cone) Spec->option.cone = (int)Cone; - if (bOverride_Solver) Spec->option.solver = (int)Solver; - - if (bOverride_NoslipIterations) Spec->option.noslip_iterations = NoslipIterations; - if (bOverride_NoslipTolerance) Spec->option.noslip_tolerance = NoslipTolerance; - if (bOverride_CCD_Iterations) Spec->option.ccd_iterations = CCD_Iterations; - if (bOverride_CCD_Tolerance) Spec->option.ccd_tolerance = CCD_Tolerance; - - // MultiCCD - constexpr int MJ_ENBL_MULTICCD = 1 << 4; - if (bEnableMultiCCD) - Spec->option.enableflags |= MJ_ENBL_MULTICCD; - else - Spec->option.enableflags &= ~MJ_ENBL_MULTICCD; - - // Sleep - constexpr int MJ_ENBL_SLEEP = 1 << 5; - if (bEnableSleep) - { - Spec->option.enableflags |= MJ_ENBL_SLEEP; - Spec->option.sleep_tolerance = SleepTolerance; - } -} - -void FMuJoCoOptions::ApplyOverridesToModel(mjModel* Model) const -{ - if (!Model) return; - - if (bOverride_Timestep) Model->opt.timestep = Timestep; - - if (bOverride_Gravity) - { - Model->opt.gravity[0] = Gravity.X / 100.0; - Model->opt.gravity[1] = -Gravity.Y / 100.0; - Model->opt.gravity[2] = Gravity.Z / 100.0; - } - - if (bOverride_Wind) - { - Model->opt.wind[0] = Wind.X / 100.0; - Model->opt.wind[1] = -Wind.Y / 100.0; - Model->opt.wind[2] = Wind.Z / 100.0; - } - - if (bOverride_Magnetic) - { - Model->opt.magnetic[0] = Magnetic.X; - Model->opt.magnetic[1] = -Magnetic.Y; - Model->opt.magnetic[2] = Magnetic.Z; - } - - if (bOverride_Density) Model->opt.density = Density; - if (bOverride_Viscosity) Model->opt.viscosity = Viscosity; - if (bOverride_Impratio) Model->opt.impratio = Impratio; - if (bOverride_Tolerance) Model->opt.tolerance = Tolerance; - if (bOverride_Iterations) Model->opt.iterations = Iterations; - if (bOverride_LsIterations) Model->opt.ls_iterations = LsIterations; - - if (bOverride_Integrator) Model->opt.integrator = (int)Integrator; - if (bOverride_Cone) Model->opt.cone = (int)Cone; - if (bOverride_Solver) Model->opt.solver = (int)Solver; - - if (bOverride_NoslipIterations) Model->opt.noslip_iterations = NoslipIterations; - if (bOverride_NoslipTolerance) Model->opt.noslip_tolerance = NoslipTolerance; - if (bOverride_CCD_Iterations) Model->opt.ccd_iterations = CCD_Iterations; - if (bOverride_CCD_Tolerance) Model->opt.ccd_tolerance = CCD_Tolerance; - - // MultiCCD - constexpr int MJ_ENBL_MULTICCD = 1 << 4; - if (bEnableMultiCCD) - Model->opt.enableflags |= MJ_ENBL_MULTICCD; - else - Model->opt.enableflags &= ~MJ_ENBL_MULTICCD; - - // Sleep - constexpr int MJ_ENBL_SLEEP = 1 << 5; - if (bEnableSleep) - { - Model->opt.enableflags |= MJ_ENBL_SLEEP; - Model->opt.sleep_tolerance = SleepTolerance; - } - else - { - Model->opt.enableflags &= ~MJ_ENBL_SLEEP; - } -} diff --git a/Source/URLab/Private/MuJoCo/Core/Spec/MjSpecWrapper.cpp b/Source/URLab/Private/MuJoCo/Core/Spec/MjSpecWrapper.cpp index a9fbd4c..a1abd63 100644 --- a/Source/URLab/Private/MuJoCo/Core/Spec/MjSpecWrapper.cpp +++ b/Source/URLab/Private/MuJoCo/Core/Spec/MjSpecWrapper.cpp @@ -97,7 +97,7 @@ FString FMujocoSpecWrapper::AddMeshAsset(const FString& MeshName, const FString& mjsMesh* MeshAsset = mjs_addMesh(Spec, nullptr); mjs_setName(MeshAsset->element, TCHAR_TO_UTF8(*UniqueMeshName)); - mjs_setString(MeshAsset->file, TCHAR_TO_UTF8(*FilePath)); + MjSetStringRaw(MeshAsset->file, FilePath); MeshAsset->scale[0] = scale.X; MeshAsset->scale[1] = scale.Y; diff --git a/Source/URLab/Private/MuJoCo/Generated/MjOptionGenerated.cpp b/Source/URLab/Private/MuJoCo/Generated/MjOptionGenerated.cpp new file mode 100644 index 0000000..9bc1607 --- /dev/null +++ b/Source/URLab/Private/MuJoCo/Generated/MjOptionGenerated.cpp @@ -0,0 +1,79 @@ +// Copyright (c) 2026 Jonathan Embley-Riches. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// --- LEGAL DISCLAIMER --- +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. +// +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. + +#include "MuJoCo/Generated/MjOptionGenerated.h" +#include + +void FMjOptionGenerated::ApplyToSpec(mjSpec* Spec) const +{ + if (!Spec) return; + Spec->option.timestep = Timestep; + Spec->option.impratio = Impratio; + Spec->option.tolerance = Tolerance; + Spec->option.ls_tolerance = LsTolerance; + if (bOverride_NoslipTolerance) { Spec->option.noslip_tolerance = NoslipTolerance; } + if (bOverride_CCD_Tolerance) { Spec->option.ccd_tolerance = CCD_Tolerance; } + Spec->option.gravity[0] = Gravity.X / 100.0; Spec->option.gravity[1] = -Gravity.Y / 100.0; Spec->option.gravity[2] = Gravity.Z / 100.0; + Spec->option.wind[0] = Wind.X / 100.0; Spec->option.wind[1] = -Wind.Y / 100.0; Spec->option.wind[2] = Wind.Z / 100.0; + Spec->option.magnetic[0] = Magnetic.X; Spec->option.magnetic[1] = -Magnetic.Y; Spec->option.magnetic[2] = Magnetic.Z; + Spec->option.density = Density; + Spec->option.viscosity = Viscosity; + Spec->option.o_margin = OMargin; + if (bOverride_Integrator) { Spec->option.integrator = (int)Integrator; } + if (bOverride_Cone) { Spec->option.cone = (int)Cone; } + Spec->option.jacobian = Jacobian; + if (bOverride_Solver) { Spec->option.solver = (int)Solver; } + Spec->option.iterations = Iterations; + Spec->option.ls_iterations = LsIterations; + if (bOverride_NoslipIterations) { Spec->option.noslip_iterations = NoslipIterations; } + if (bOverride_CCD_Iterations) { Spec->option.ccd_iterations = CCD_Iterations; } + ApplyMjOptionExtras(Spec ? &Spec->option : nullptr, *this, Spec); +} + +void FMjOptionGenerated::ApplyOverridesToModel(mjModel* Model) const +{ + if (!Model) return; + if (bOverride_Timestep) { Model->opt.timestep = Timestep; } + if (bOverride_Impratio) { Model->opt.impratio = Impratio; } + if (bOverride_Tolerance) { Model->opt.tolerance = Tolerance; } + if (bOverride_LsTolerance) { Model->opt.ls_tolerance = LsTolerance; } + if (bOverride_NoslipTolerance) { Model->opt.noslip_tolerance = NoslipTolerance; } + if (bOverride_CCD_Tolerance) { Model->opt.ccd_tolerance = CCD_Tolerance; } + if (bOverride_Gravity) { Model->opt.gravity[0] = Gravity.X / 100.0; Model->opt.gravity[1] = -Gravity.Y / 100.0; Model->opt.gravity[2] = Gravity.Z / 100.0; } + if (bOverride_Wind) { Model->opt.wind[0] = Wind.X / 100.0; Model->opt.wind[1] = -Wind.Y / 100.0; Model->opt.wind[2] = Wind.Z / 100.0; } + if (bOverride_Magnetic) { Model->opt.magnetic[0] = Magnetic.X; Model->opt.magnetic[1] = -Magnetic.Y; Model->opt.magnetic[2] = Magnetic.Z; } + if (bOverride_Density) { Model->opt.density = Density; } + if (bOverride_Viscosity) { Model->opt.viscosity = Viscosity; } + if (bOverride_OMargin) { Model->opt.o_margin = OMargin; } + if (bOverride_Integrator) { Model->opt.integrator = (int)Integrator; } + if (bOverride_Cone) { Model->opt.cone = (int)Cone; } + if (bOverride_Jacobian) { Model->opt.jacobian = Jacobian; } + if (bOverride_Solver) { Model->opt.solver = (int)Solver; } + if (bOverride_Iterations) { Model->opt.iterations = Iterations; } + if (bOverride_LsIterations) { Model->opt.ls_iterations = LsIterations; } + if (bOverride_NoslipIterations) { Model->opt.noslip_iterations = NoslipIterations; } + if (bOverride_CCD_Iterations) { Model->opt.ccd_iterations = CCD_Iterations; } + ApplyMjOptionExtras(Model ? &Model->opt : nullptr, *this, nullptr, Model); +} diff --git a/Source/URLab/Private/MuJoCo/Generated/MjOptionGeneratedExtras.cpp b/Source/URLab/Private/MuJoCo/Generated/MjOptionGeneratedExtras.cpp new file mode 100644 index 0000000..79958ca --- /dev/null +++ b/Source/URLab/Private/MuJoCo/Generated/MjOptionGeneratedExtras.cpp @@ -0,0 +1,46 @@ +// Copyright (c) 2026 Jonathan Embley-Riches. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// URLab pseudo-field side of FMjOptionGenerated. The codegen emits the +// mjOption mirror struct + its ApplyToSpec / ApplyOverridesToModel +// bodies (in MjOptionGenerated.cpp) and ends each with a call to +// ApplyMjOptionExtras for the URLab-specific bits the spec/model layout +// doesn't carry (MemoryMB, MultiCCD bitflag, Sleep bitflag + tolerance). +// Edit this file directly — it is NOT codegen-managed. + +#include "MuJoCo/Generated/MjOptionGenerated.h" +#include + +// Bit positions in mjOption.enableflags. Match mjENBL_MULTICCD / mjENBL_SLEEP +// from mjmodel.h; hardcoded to avoid pulling mjtEnableBit into the header. +static constexpr int MJ_ENBL_MULTICCD = 1 << 4; +static constexpr int MJ_ENBL_SLEEP = 1 << 5; + +void ApplyMjOptionExtras(mjOption* Opt, const FMjOptionGenerated& Self, + mjSpec* Spec, mjModel* /*Model*/) +{ + if (!Opt) return; + + if (Spec && Self.bOverride_MemoryMB) + { + Spec->memory = static_cast(Self.MemoryMB) * 1024 * 1024; + } + + if (Self.bEnableMultiCCD) Opt->enableflags |= MJ_ENBL_MULTICCD; + else Opt->enableflags &= ~MJ_ENBL_MULTICCD; + + if (Self.bEnableSleep) + { + Opt->enableflags |= MJ_ENBL_SLEEP; + Opt->sleep_tolerance = Self.SleepTolerance; + } + else + { + Opt->enableflags &= ~MJ_ENBL_SLEEP; + } +} diff --git a/Source/URLab/Private/MuJoCo/Input/MjPerturbation.cpp b/Source/URLab/Private/MuJoCo/Input/MjPerturbation.cpp index 222371e..f2bf226 100644 --- a/Source/URLab/Private/MuJoCo/Input/MjPerturbation.cpp +++ b/Source/URLab/Private/MuJoCo/Input/MjPerturbation.cpp @@ -117,7 +117,7 @@ int32 UMjPerturbation::ResolveBodyIdFromActor(const AActor* Actor, const FVector if (!Actor) return -1; // Articulation path: find the nearest UMjGeom to the hit point (any geom - // on the actor belongs to a body via Geom->GetMj().body_id). + // on the actor belongs to a body via Geom->GetMj().geom_bodyid). TArray Geoms; const_cast(Actor)->GetComponents(Geoms); if (Geoms.Num() > 0) @@ -132,7 +132,7 @@ int32 UMjPerturbation::ResolveBodyIdFromActor(const AActor* Actor, const FVector } if (Best) { - return Best->GetMj().body_id; + return Best->GetMj().geom_bodyid; } } diff --git a/Source/URLab/Private/MuJoCo/Utils/MjOrientationUtils.cpp b/Source/URLab/Private/MuJoCo/Utils/MjOrientationUtils.cpp index 3e8d7b9..2c6878c 100644 --- a/Source/URLab/Private/MuJoCo/Utils/MjOrientationUtils.cpp +++ b/Source/URLab/Private/MuJoCo/Utils/MjOrientationUtils.cpp @@ -24,6 +24,7 @@ #include "XmlNode.h" #include "MuJoCo/Utils/MjXmlUtils.h" #include "Utils/URLabLogging.h" +#include "mujoco/mujoco.h" // ============================================================================ // Compiler Settings @@ -126,7 +127,7 @@ bool MjOrientationUtils::OrientationToMjQuat(const FXmlNode* Node, const FMjComp OutQuat[1] = (double)Parts[1]; OutQuat[2] = (double)Parts[2]; OutQuat[3] = (double)Parts[3]; - QuatNormalize(OutQuat); + mju_normalize4(OutQuat); return true; } } @@ -213,49 +214,19 @@ bool MjOrientationUtils::OrientationToMjQuat(const FXmlNode* Node, const FMjComp void MjOrientationUtils::AxisAngleToQuat(double x, double y, double z, double AngleRad, double OutQuat[4]) { - // Normalize axis - double Len = FMath::Sqrt(x * x + y * y + z * z); - if (Len < 1e-10) + double Axis[3] = { x, y, z }; + if (mju_normalize3(Axis) < 1e-10) { OutQuat[0] = 1.0; OutQuat[1] = 0.0; OutQuat[2] = 0.0; OutQuat[3] = 0.0; return; } - - double InvLen = 1.0 / Len; - double nx = x * InvLen; - double ny = y * InvLen; - double nz = z * InvLen; - - double HalfAngle = AngleRad * 0.5; - double s = FMath::Sin(HalfAngle); - double c = FMath::Cos(HalfAngle); - - OutQuat[0] = c; - OutQuat[1] = s * nx; - OutQuat[2] = s * ny; - OutQuat[3] = s * nz; - QuatNormalize(OutQuat); + mju_axisAngle2Quat(OutQuat, Axis, AngleRad); } // ============================================================================ // Euler → Quaternion // ============================================================================ -void MjOrientationUtils::ElementalRotQuat(int AxisIndex, double AngleRad, double OutQuat[4]) -{ - double HalfAngle = AngleRad * 0.5; - double s = FMath::Sin(HalfAngle); - double c = FMath::Cos(HalfAngle); - - OutQuat[0] = c; - OutQuat[1] = 0.0; - OutQuat[2] = 0.0; - OutQuat[3] = 0.0; - - // AxisIndex: 0=x, 1=y, 2=z - OutQuat[1 + AxisIndex] = s; -} - void MjOrientationUtils::EulerToQuat(double e1, double e2, double e3, const FString& EulerSeq, double OutQuat[4]) { if (EulerSeq.Len() != 3) @@ -265,62 +236,9 @@ void MjOrientationUtils::EulerToQuat(double e1, double e2, double e3, const FStr return; } - double Angles[3] = { e1, e2, e3 }; - int AxisIndices[3]; - bool bExtrinsic[3]; - - for (int i = 0; i < 3; ++i) - { - TCHAR Ch = EulerSeq[i]; - switch (Ch) - { - case 'x': AxisIndices[i] = 0; bExtrinsic[i] = false; break; - case 'y': AxisIndices[i] = 1; bExtrinsic[i] = false; break; - case 'z': AxisIndices[i] = 2; bExtrinsic[i] = false; break; - case 'X': AxisIndices[i] = 0; bExtrinsic[i] = true; break; - case 'Y': AxisIndices[i] = 1; bExtrinsic[i] = true; break; - case 'Z': AxisIndices[i] = 2; bExtrinsic[i] = true; break; - default: - UE_LOG(LogURLabImport, Warning, TEXT("[MjOrientationUtils] Invalid euler axis character '%c'"), Ch); - AxisIndices[i] = 0; bExtrinsic[i] = false; - break; - } - } - - // Build three elemental rotation quaternions - double Q1[4], Q2[4], Q3[4]; - ElementalRotQuat(AxisIndices[0], Angles[0], Q1); - ElementalRotQuat(AxisIndices[1], Angles[1], Q2); - ElementalRotQuat(AxisIndices[2], Angles[2], Q3); - - // Per-axis composition following MuJoCo convention (user_objects.cc): - // Lowercase (intrinsic): rotate in body-fixed frame → accumulate on the right: R = R_prev * Ri - // Uppercase (extrinsic): rotate in world-fixed frame → accumulate on the left: R = Ri * R_prev - // This handles pure intrinsic, pure extrinsic, and mixed sequences correctly. - - const double* Qi[3] = { Q1, Q2, Q3 }; - // Start with identity - double Result[4] = { 1.0, 0.0, 0.0, 0.0 }; - double Temp[4]; - - for (int i = 0; i < 3; ++i) - { - if (bExtrinsic[i]) - { - // Extrinsic: new = Qi * Result - QuatMul(Qi[i], Result, Temp); - } - else - { - // Intrinsic: new = Result * Qi - QuatMul(Result, Qi[i], Temp); - } - Result[0] = Temp[0]; Result[1] = Temp[1]; Result[2] = Temp[2]; Result[3] = Temp[3]; - } - - OutQuat[0] = Result[0]; OutQuat[1] = Result[1]; OutQuat[2] = Result[2]; OutQuat[3] = Result[3]; - - QuatNormalize(OutQuat); + double Euler[3] = { e1, e2, e3 }; + const auto SeqAnsi = StringCast(*EulerSeq); + mju_euler2Quat(OutQuat, Euler, SeqAnsi.Get()); } // ============================================================================ @@ -329,43 +247,37 @@ void MjOrientationUtils::EulerToQuat(double e1, double e2, double e3, const FStr void MjOrientationUtils::XYAxesToQuat(const double XYAxes[6], double OutQuat[4]) { - // X axis - double Xx = XYAxes[0], Xy = XYAxes[1], Xz = XYAxes[2]; - double XLen = FMath::Sqrt(Xx * Xx + Xy * Xy + Xz * Xz); - if (XLen < 1e-10) + double X[3] = { XYAxes[0], XYAxes[1], XYAxes[2] }; + if (mju_normalize3(X) < 1e-10) { OutQuat[0] = 1.0; OutQuat[1] = 0.0; OutQuat[2] = 0.0; OutQuat[3] = 0.0; return; } - Xx /= XLen; Xy /= XLen; Xz /= XLen; - - // Y axis (orthogonalize against X) - double Yx = XYAxes[3], Yy = XYAxes[4], Yz = XYAxes[5]; - double Dot = Xx * Yx + Xy * Yy + Xz * Yz; - Yx -= Dot * Xx; - Yy -= Dot * Xy; - Yz -= Dot * Xz; - double YLen = FMath::Sqrt(Yx * Yx + Yy * Yy + Yz * Yz); - if (YLen < 1e-10) + + double Y[3] = { XYAxes[3], XYAxes[4], XYAxes[5] }; + const double Dot = X[0]*Y[0] + X[1]*Y[1] + X[2]*Y[2]; + Y[0] -= Dot*X[0]; Y[1] -= Dot*X[1]; Y[2] -= Dot*X[2]; + if (mju_normalize3(Y) < 1e-10) { OutQuat[0] = 1.0; OutQuat[1] = 0.0; OutQuat[2] = 0.0; OutQuat[3] = 0.0; return; } - Yx /= YLen; Yy /= YLen; Yz /= YLen; - - // Z axis = X cross Y - double Zx = Xy * Yz - Xz * Yy; - double Zy = Xz * Yx - Xx * Yz; - double Zz = Xx * Yy - Xy * Yx; - - // Build rotation matrix (row-major): row 0 = X, row 1 = Y, row 2 = Z - double R[9] = { - Xx, Xy, Xz, - Yx, Yy, Yz, - Zx, Zy, Zz - }; - RotMatToQuat(R, OutQuat); + double Z[3]; + mju_cross(Z, X, Y); + if (mju_normalize3(Z) < 1e-10) + { + OutQuat[0] = 1.0; OutQuat[1] = 0.0; OutQuat[2] = 0.0; OutQuat[3] = 0.0; + return; + } + + // MuJoCo rotation matrix is row-major with COLUMNS = local axes (mjuu_frame2quat convention). + const double Mat[9] = { + X[0], Y[0], Z[0], + X[1], Y[1], Z[1], + X[2], Y[2], Z[2] + }; + mju_mat2Quat(OutQuat, Mat); } // ============================================================================ @@ -374,119 +286,27 @@ void MjOrientationUtils::XYAxesToQuat(const double XYAxes[6], double OutQuat[4]) void MjOrientationUtils::ZAxisToQuat(const double ZAxis[3], double OutQuat[4]) { - double Zx = ZAxis[0], Zy = ZAxis[1], Zz = ZAxis[2]; - double Len = FMath::Sqrt(Zx * Zx + Zy * Zy + Zz * Zz); - if (Len < 1e-10) + double Vec[3] = { ZAxis[0], ZAxis[1], ZAxis[2] }; + if (mju_normalize3(Vec) < 1e-10) { OutQuat[0] = 1.0; OutQuat[1] = 0.0; OutQuat[2] = 0.0; OutQuat[3] = 0.0; return; } - Zx /= Len; Zy /= Len; Zz /= Len; - - // Source direction: (0, 0, 1) - // target direction: (Zx, Zy, Zz) - // Rotation axis = cross(source, target), angle = acos(dot(source, target)) - - double DotVal = Zz; // dot((0,0,1), (Zx,Zy,Zz)) = Zz - if (DotVal > 0.9999999) + if (Vec[2] > 0.9999999) { - // Nearly identical — identity rotation OutQuat[0] = 1.0; OutQuat[1] = 0.0; OutQuat[2] = 0.0; OutQuat[3] = 0.0; return; } - - if (DotVal < -0.9999999) + if (Vec[2] < -0.9999999) { - // Nearly opposite — 180 degree rotation around any perpendicular axis - // Choose X axis as the rotation axis OutQuat[0] = 0.0; OutQuat[1] = 1.0; OutQuat[2] = 0.0; OutQuat[3] = 0.0; return; } - // cross((0,0,1), (Zx,Zy,Zz)) = (-Zy, Zx, 0) - double Ax = -Zy; - double Ay = Zx; - double Az = 0.0; - - double Angle = FMath::Acos(FMath::Clamp(DotVal, -1.0, 1.0)); - AxisAngleToQuat(Ax, Ay, Az, Angle, OutQuat); -} - -// ============================================================================ -// Quaternion Helpers -// ============================================================================ - -void MjOrientationUtils::QuatMul(const double A[4], const double B[4], double Result[4]) -{ - // Hamilton product: A * B with layout [w, x, y, z] - Result[0] = A[0]*B[0] - A[1]*B[1] - A[2]*B[2] - A[3]*B[3]; - Result[1] = A[0]*B[1] + A[1]*B[0] + A[2]*B[3] - A[3]*B[2]; - Result[2] = A[0]*B[2] - A[1]*B[3] + A[2]*B[0] + A[3]*B[1]; - Result[3] = A[0]*B[3] + A[1]*B[2] - A[2]*B[1] + A[3]*B[0]; -} - -void MjOrientationUtils::QuatNormalize(double Q[4]) -{ - double Len = FMath::Sqrt(Q[0]*Q[0] + Q[1]*Q[1] + Q[2]*Q[2] + Q[3]*Q[3]); - if (Len < 1e-10) - { - Q[0] = 1.0; Q[1] = 0.0; Q[2] = 0.0; Q[3] = 0.0; - return; - } - double InvLen = 1.0 / Len; - Q[0] *= InvLen; Q[1] *= InvLen; Q[2] *= InvLen; Q[3] *= InvLen; -} - -void MjOrientationUtils::RotMatToQuat(const double R[9], double OutQuat[4]) -{ - // Rotation matrix in row-major order: - // R[0] R[1] R[2] = row 0 (X axis) - // R[3] R[4] R[5] = row 1 (Y axis) - // R[6] R[7] R[8] = row 2 (Z axis) - // - // MuJoCo stores rotation matrices as 3x3 row-major where columns are frame axes. - // For xyaxes, we constructed R with rows = axes, so the rotation matrix for MuJoCo - // frame would have the columns as the axes. Since our R has rows as axes, - // the equivalent rotation matrix (transforms world to local) has columns as the axes. - // We need to convert from this rotation matrix to quaternion. - // - // Standard Shepperd method for robust matrix-to-quaternion conversion: - - double Trace = R[0] + R[4] + R[8]; - - if (Trace > 0.0) - { - double s = FMath::Sqrt(Trace + 1.0) * 2.0; // s = 4*w - OutQuat[0] = 0.25 * s; - OutQuat[1] = (R[5] - R[7]) / s; // (R[1][2] - R[2][1]) / s - OutQuat[2] = (R[6] - R[2]) / s; // (R[2][0] - R[0][2]) / s - OutQuat[3] = (R[1] - R[3]) / s; // (R[0][1] - R[1][0]) / s - } - else if (R[0] > R[4] && R[0] > R[8]) - { - double s = FMath::Sqrt(1.0 + R[0] - R[4] - R[8]) * 2.0; // s = 4*x - OutQuat[0] = (R[5] - R[7]) / s; - OutQuat[1] = 0.25 * s; - OutQuat[2] = (R[1] + R[3]) / s; - OutQuat[3] = (R[2] + R[6]) / s; - } - else if (R[4] > R[8]) - { - double s = FMath::Sqrt(1.0 + R[4] - R[0] - R[8]) * 2.0; // s = 4*y - OutQuat[0] = (R[6] - R[2]) / s; - OutQuat[1] = (R[1] + R[3]) / s; - OutQuat[2] = 0.25 * s; - OutQuat[3] = (R[5] + R[7]) / s; - } - else - { - double s = FMath::Sqrt(1.0 + R[8] - R[0] - R[4]) * 2.0; // s = 4*z - OutQuat[0] = (R[1] - R[3]) / s; - OutQuat[1] = (R[2] + R[6]) / s; - OutQuat[2] = (R[5] + R[7]) / s; - OutQuat[3] = 0.25 * s; - } - - QuatNormalize(OutQuat); + // axis = cross((0,0,1), Vec) = (-Vec[1], Vec[0], 0) + double Axis[3] = { -Vec[1], Vec[0], 0.0 }; + const double Angle = FMath::Acos(FMath::Clamp(Vec[2], -1.0, 1.0)); + mju_normalize3(Axis); + mju_axisAngle2Quat(OutQuat, Axis, Angle); } diff --git a/Source/URLab/Private/MuJoCo/Utils/MjUtils.cpp b/Source/URLab/Private/MuJoCo/Utils/MjUtils.cpp index 38b2061..5adb75c 100644 --- a/Source/URLab/Private/MuJoCo/Utils/MjUtils.cpp +++ b/Source/URLab/Private/MuJoCo/Utils/MjUtils.cpp @@ -142,9 +142,9 @@ void MjUtils::DrawDebugGeom(UWorld* World, const mjModel* m, const GeomView& geo { if (!World || !m) return; - mjtNum* pos = geom_view.xpos; - mjtNum* mat = geom_view.xmat; - mjtNum* size = geom_view.size; + mjtNum* pos = geom_view.geom_xpos; + mjtNum* mat = geom_view.geom_xmat; + mjtNum* size = geom_view.geom_size; // Draw if group 3 (collision convention) OR if both contype and conaffinity are non-zero (active collider) int group = geom_view._m->geom_group[geom_view.id]; @@ -163,7 +163,7 @@ void MjUtils::DrawDebugGeom(UWorld* World, const mjModel* m, const GeomView& geo mju_mat2Quat(_quat, mat); FQuat Rotation = MjToUERotation(_quat); - switch (geom_view.type) { + switch (geom_view.geom_type) { case mjGEOM_BOX: { FColor Color = DrawColor != FColor::Magenta ? DrawColor : FColor::Cyan; @@ -200,7 +200,7 @@ void MjUtils::DrawDebugGeom(UWorld* World, const mjModel* m, const GeomView& geo case mjGEOM_MESH: { FColor Color = DrawColor != FColor::Magenta ? DrawColor : FColor::Magenta; - int meshId = geom_view.dataid; + int meshId = geom_view.geom_dataid; if (meshId < 0) break; float* vertices = m->mesh_vert + m->mesh_vertadr[meshId] * 3; diff --git a/Source/URLab/Public/MuJoCo/Components/Actuators/MjActuator.h b/Source/URLab/Public/MuJoCo/Components/Actuators/MjActuator.h index a630ff5..c5fbc0a 100644 --- a/Source/URLab/Public/MuJoCo/Components/Actuators/MjActuator.h +++ b/Source/URLab/Public/MuJoCo/Components/Actuators/MjActuator.h @@ -79,7 +79,8 @@ enum class EMjGainType : uint8 Fixed, Affine, Muscle, - User + User, + DcMotor }; /** @@ -92,7 +93,8 @@ enum class EMjBiasType : uint8 None, Affine, Muscle, - User + User, + DcMotor }; /** @@ -107,7 +109,8 @@ enum class EMjDynType : uint8 Filter, FilterExact, Muscle, - User + User, + DcMotor }; /** @@ -124,137 +127,120 @@ class URLAB_API UMjActuator : public UMjComponent public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_group = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_group")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_group")) int32 group = 0; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_nsample = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_nsample")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_nsample")) int32 nsample = 0; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_interp = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_interp")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_interp")) int32 interp = 0; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_delay = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_delay")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_delay")) float delay = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_ctrllimited = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_ctrllimited")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_ctrllimited")) bool ctrllimited = false; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_forcelimited = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_forcelimited")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_forcelimited")) bool forcelimited = false; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_actlimited = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_actlimited")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_actlimited")) bool actlimited = false; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_ctrlrange = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_ctrlrange")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_ctrlrange")) TArray ctrlrange = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_forcerange = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_forcerange")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_forcerange")) TArray forcerange = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_actrange = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_actrange")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_actrange")) TArray actrange = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_lengthrange = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_lengthrange")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_lengthrange")) TArray lengthrange = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_gear = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_gear")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_gear")) TArray gear = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_damping = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_damping")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_damping")) TArray damping = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_armature = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_armature")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_armature")) float armature = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_cranklength = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_cranklength")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_cranklength")) float cranklength = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_gainprm = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_gainprm")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_gainprm")) TArray gainprm = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_biasprm = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_biasprm")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_biasprm")) TArray biasprm = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_dynprm = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_dynprm")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_dynprm")) TArray dynprm = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_actdim = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_actdim")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_actdim")) int32 actdim = 0; - // --- CODEGEN_PROPERTIES_END --- - UMjActuator(); - - /** @brief The type of actuator dynamics (e.g. Motor, Position). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator") - EMjActuatorType Type; - - /** @brief The transmission type connecting the actuator to the system. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator") - EMjActuatorTrnType TransmissionType; - - // gaintype / biastype / dyntype: hand-declared because the UPROPERTY type - // is a URLab enum. Codegen owns the XML-string -> enum import and the - // enum -> mjtGain/mjtBias/mjtDyn export switch via xml_enum_attrs in - // codegen_rules.json. Useful primarily on actuators; for - // motor/position/velocity/etc. subtypes the mjs_setToX preset writes - // these fields and overrides the user's choice. UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_GainType = false; @@ -272,13 +258,32 @@ class URLAB_API UMjActuator : public UMjComponent UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_DynType")) EMjDynType DynType = EMjDynType::None; + // --- CODEGEN_PROPERTIES_END --- + + UMjActuator(); + + /** @brief The type of actuator dynamics (e.g. Motor, Position). */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator") + EMjActuatorType Type; + + /** @brief The transmission type connecting the actuator to the system. */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator") + EMjActuatorTrnType TransmissionType; + + // gaintype / biastype / dyntype UPROPERTYs are codegen-emitted inside + // CODEGEN_PROPERTIES via xml_enum_attrs.emit_property_decl. Useful + // primarily on actuators; for motor/position/velocity/etc. + // subtypes the mjs_setToX preset writes these fields and overrides + // the user's choice. /** @brief Optional MuJoCo class name to inherit defaults from (string fallback). */ UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(GetOptions="GetDefaultClassOptions")) FString MjClassName; - /** @brief Reference to a UMjDefault component for default class inheritance. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator") + /** @brief Reference to a UMjDefault component for default class inheritance. Hidden from the + * Details panel — synced from MjClassName via the editor dropdown. */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", + meta=(EditCondition="false", EditConditionHides)) UMjDefault* DefaultClass = nullptr; virtual FString GetMjClassName() const override diff --git a/Source/URLab/Public/MuJoCo/Components/Actuators/MjAdhesionActuator.h b/Source/URLab/Public/MuJoCo/Components/Actuators/MjAdhesionActuator.h index eddad98..aebb876 100644 --- a/Source/URLab/Public/MuJoCo/Components/Actuators/MjAdhesionActuator.h +++ b/Source/URLab/Public/MuJoCo/Components/Actuators/MjAdhesionActuator.h @@ -36,10 +36,10 @@ class URLAB_API UMjAdhesionActuator : public UMjActuator GENERATED_BODY() public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_gain = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_gain")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_gain")) float gain = 0.0f; // --- CODEGEN_PROPERTIES_END --- diff --git a/Source/URLab/Public/MuJoCo/Components/Actuators/MjCylinderActuator.h b/Source/URLab/Public/MuJoCo/Components/Actuators/MjCylinderActuator.h index d9b20c9..263bb3b 100644 --- a/Source/URLab/Public/MuJoCo/Components/Actuators/MjCylinderActuator.h +++ b/Source/URLab/Public/MuJoCo/Components/Actuators/MjCylinderActuator.h @@ -36,28 +36,28 @@ class URLAB_API UMjCylinderActuator : public UMjActuator GENERATED_BODY() public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_timeconst = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_timeconst")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_timeconst")) TArray timeconst = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_area = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_area")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_area")) float area = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_diameter = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_diameter")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_diameter")) float diameter = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_bias = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_bias")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_bias")) float bias = 0.0f; // --- CODEGEN_PROPERTIES_END --- diff --git a/Source/URLab/Public/MuJoCo/Components/Actuators/MjDamperActuator.h b/Source/URLab/Public/MuJoCo/Components/Actuators/MjDamperActuator.h index eab9d3e..3a94e06 100644 --- a/Source/URLab/Public/MuJoCo/Components/Actuators/MjDamperActuator.h +++ b/Source/URLab/Public/MuJoCo/Components/Actuators/MjDamperActuator.h @@ -36,10 +36,10 @@ class URLAB_API UMjDamperActuator : public UMjActuator GENERATED_BODY() public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_kv = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_kv")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_kv")) float kv = 0.0f; // --- CODEGEN_PROPERTIES_END --- diff --git a/Source/URLab/Public/MuJoCo/Components/Actuators/MjDcMotorActuator.h b/Source/URLab/Public/MuJoCo/Components/Actuators/MjDcMotorActuator.h index 03255e3..eafe9e5 100644 --- a/Source/URLab/Public/MuJoCo/Components/Actuators/MjDcMotorActuator.h +++ b/Source/URLab/Public/MuJoCo/Components/Actuators/MjDcMotorActuator.h @@ -57,58 +57,58 @@ class URLAB_API UMjDcMotorActuator : public UMjActuator public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_motorconst = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_motorconst")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_motorconst")) TArray motorconst = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_resistance = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_resistance")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_resistance")) float resistance = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_nominal = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_nominal")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_nominal")) TArray nominal = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_saturation = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_saturation")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_saturation")) TArray saturation = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_inductance = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_inductance")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_inductance")) TArray inductance = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_cogging = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_cogging")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_cogging")) TArray cogging = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_controller = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_controller")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_controller")) TArray controller = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_thermal = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_thermal")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_thermal")) TArray thermal = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_lugre = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_lugre")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_lugre")) TArray lugre = {}; // --- CODEGEN_PROPERTIES_END --- diff --git a/Source/URLab/Public/MuJoCo/Components/Actuators/MjGeneralActuator.h b/Source/URLab/Public/MuJoCo/Components/Actuators/MjGeneralActuator.h index 2ec662d..0d83b74 100644 --- a/Source/URLab/Public/MuJoCo/Components/Actuators/MjGeneralActuator.h +++ b/Source/URLab/Public/MuJoCo/Components/Actuators/MjGeneralActuator.h @@ -36,10 +36,10 @@ class URLAB_API UMjGeneralActuator : public UMjActuator GENERATED_BODY() public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_actearly = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_actearly")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_actearly")) bool actearly = false; // --- CODEGEN_PROPERTIES_END --- diff --git a/Source/URLab/Public/MuJoCo/Components/Actuators/MjIntVelocityActuator.h b/Source/URLab/Public/MuJoCo/Components/Actuators/MjIntVelocityActuator.h index 404890c..038ebd9 100644 --- a/Source/URLab/Public/MuJoCo/Components/Actuators/MjIntVelocityActuator.h +++ b/Source/URLab/Public/MuJoCo/Components/Actuators/MjIntVelocityActuator.h @@ -36,28 +36,28 @@ class URLAB_API UMjIntVelocityActuator : public UMjActuator GENERATED_BODY() public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_inheritrange = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_inheritrange")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_inheritrange")) float inheritrange = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_kp = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_kp")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_kp")) float kp = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_kv = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_kv")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_kv")) float kv = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_dampratio = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_dampratio")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_dampratio")) float dampratio = 0.0f; // --- CODEGEN_PROPERTIES_END --- diff --git a/Source/URLab/Public/MuJoCo/Components/Actuators/MjMuscleActuator.h b/Source/URLab/Public/MuJoCo/Components/Actuators/MjMuscleActuator.h index c140a8f..5bbd3e2 100644 --- a/Source/URLab/Public/MuJoCo/Components/Actuators/MjMuscleActuator.h +++ b/Source/URLab/Public/MuJoCo/Components/Actuators/MjMuscleActuator.h @@ -36,64 +36,64 @@ class URLAB_API UMjMuscleActuator : public UMjActuator GENERATED_BODY() public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_timeconst = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_timeconst")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_timeconst")) TArray timeconst = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_tausmooth = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_tausmooth")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_tausmooth")) float tausmooth = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_range = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_range")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_range")) TArray range = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_force = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_force")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_force")) float force = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_scale = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_scale")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_scale")) TArray scale = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_lmin = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_lmin")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_lmin")) float lmin = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_lmax = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_lmax")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_lmax")) float lmax = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_vmax = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_vmax")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_vmax")) float vmax = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_fpmax = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_fpmax")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_fpmax")) float fpmax = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_fvmax = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_fvmax")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_fvmax")) float fvmax = 0.0f; // --- CODEGEN_PROPERTIES_END --- diff --git a/Source/URLab/Public/MuJoCo/Components/Actuators/MjPositionActuator.h b/Source/URLab/Public/MuJoCo/Components/Actuators/MjPositionActuator.h index 837bad4..373d052 100644 --- a/Source/URLab/Public/MuJoCo/Components/Actuators/MjPositionActuator.h +++ b/Source/URLab/Public/MuJoCo/Components/Actuators/MjPositionActuator.h @@ -36,34 +36,34 @@ class URLAB_API UMjPositionActuator : public UMjActuator GENERATED_BODY() public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_inheritrange = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_inheritrange")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_inheritrange")) float inheritrange = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_kp = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_kp")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_kp")) float kp = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_kv = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_kv")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_kv")) float kv = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_dampratio = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_dampratio")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_dampratio")) float dampratio = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_timeconst = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_timeconst")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_timeconst")) TArray timeconst = {}; // --- CODEGEN_PROPERTIES_END --- diff --git a/Source/URLab/Public/MuJoCo/Components/Actuators/MjVelocityActuator.h b/Source/URLab/Public/MuJoCo/Components/Actuators/MjVelocityActuator.h index 78799f9..1d535b1 100644 --- a/Source/URLab/Public/MuJoCo/Components/Actuators/MjVelocityActuator.h +++ b/Source/URLab/Public/MuJoCo/Components/Actuators/MjVelocityActuator.h @@ -36,10 +36,10 @@ class URLAB_API UMjVelocityActuator : public UMjActuator GENERATED_BODY() public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjActuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_kv = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjActuator", meta=(EditCondition="bOverride_kv")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_kv")) float kv = 0.0f; // --- CODEGEN_PROPERTIES_END --- diff --git a/Source/URLab/Public/MuJoCo/Components/Bodies/MjBody.h b/Source/URLab/Public/MuJoCo/Components/Bodies/MjBody.h index e8ad076..58ac77a 100644 --- a/Source/URLab/Public/MuJoCo/Components/Bodies/MjBody.h +++ b/Source/URLab/Public/MuJoCo/Components/Bodies/MjBody.h @@ -34,13 +34,20 @@ /** * @enum EMjBodySleepPolicy - * @brief Per-body sleep policy, matching MuJoCo's mjtSleepPolicy (user-settable subset). + * @brief Per-body sleep policy, matching MuJoCo's mjtSleepPolicy. + * + * The canonical way to opt out of per-body override is the + * bOverride_SleepPolicy toggle on UMjBody (toggle off => no per-body sleep + * value is written; mjsBody.sleep keeps the compiled default). The Auto + * entry exists because UHT requires UENUMs to have a 0-valued entry; it + * maps to mjSLEEP_AUTO so writing it explicitly is equivalent to not + * overriding at all. */ UENUM(BlueprintType) enum class EMjBodySleepPolicy : uint8 { - /** Let the compiler/global policy decide (mjSLEEP_AUTO). */ - Default = 0 UMETA(DisplayName="Default (Auto)"), + /** Use the global option (mjSLEEP_AUTO). Equivalent to leaving the override toggle off. */ + Auto = 0 UMETA(DisplayName="Auto (use global)"), /** This body's tree is never allowed to sleep (mjSLEEP_NEVER). */ Never = 3 UMETA(DisplayName="Never"), /** This body's tree is allowed to sleep (mjSLEEP_ALLOWED). */ @@ -56,34 +63,34 @@ class URLAB_API UMjBody : public UMjComponent public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjBody|Spatial Pose", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Body|Spatial Pose", meta=(InlineEditConditionToggle)) bool bOverride_Pos = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjBody|Spatial Pose", meta=(EditCondition="bOverride_Pos")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Body|Spatial Pose", meta=(EditCondition="bOverride_Pos")) FVector Pos = FVector::ZeroVector; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjBody|Orientation", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Body|Orientation", meta=(InlineEditConditionToggle)) bool bOverride_Quat = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjBody|Orientation", meta=(EditCondition="bOverride_Quat")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Body|Orientation", meta=(EditCondition="bOverride_Quat")) FQuat Quat = FQuat::Identity; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjBody", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Body", meta=(InlineEditConditionToggle)) bool bOverride_childclass = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjBody", meta=(EditCondition="bOverride_childclass", GetOptions="GetChildClassOptions")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Body", meta=(EditCondition="bOverride_childclass", GetOptions="GetChildClassOptions")) FString childclass = TEXT(""); - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjBody", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Body", meta=(InlineEditConditionToggle)) bool bOverride_mocap = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjBody", meta=(EditCondition="bOverride_mocap", DisplayName="Driven By Unreal")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Body", meta=(EditCondition="bOverride_mocap", DisplayName="Driven By Unreal")) bool mocap = false; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjBody", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Body", meta=(InlineEditConditionToggle)) bool bOverride_gravcomp = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjBody", meta=(EditCondition="bOverride_gravcomp")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Body", meta=(EditCondition="bOverride_gravcomp")) float gravcomp = 0.0f; // --- CODEGEN_PROPERTIES_END --- @@ -97,10 +104,15 @@ class URLAB_API UMjBody : public UMjComponent TArray GetChildClassOptions() const; #endif - /** @brief Per-body sleep policy (MuJoCo 3.4+). Default lets the global option decide. */ + UPROPERTY(EditAnywhere, Category = "MuJoCo|Body|sleep", meta=(InlineEditConditionToggle)) + bool bOverride_SleepPolicy = false; + + /** @brief Per-body sleep policy (MuJoCo 3.4+). When the override toggle is off, + * the global option decides; when on, this value is written to mjsBody.sleep. */ UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Body|sleep", - meta=(ToolTip="sleep policy for this body's kinematic tree. Only has effect when sleep is enabled in AMjManager Options.")) - EMjBodySleepPolicy SleepPolicy = EMjBodySleepPolicy::Default; + meta=(EditCondition="bOverride_SleepPolicy", + ToolTip="sleep policy for this body's kinematic tree. Only has effect when sleep is enabled in AMjManager Options.")) + EMjBodySleepPolicy SleepPolicy = EMjBodySleepPolicy::Never; /** * @brief Registers this body to the MuJoCo spec. diff --git a/Source/URLab/Public/MuJoCo/Components/Bodies/MjFrame.h b/Source/URLab/Public/MuJoCo/Components/Bodies/MjFrame.h index cdc2fbf..6086af2 100644 --- a/Source/URLab/Public/MuJoCo/Components/Bodies/MjFrame.h +++ b/Source/URLab/Public/MuJoCo/Components/Bodies/MjFrame.h @@ -45,22 +45,22 @@ class URLAB_API UMjFrame : public UMjComponent public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFrame|Spatial Pose", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Frame|Spatial Pose", meta=(InlineEditConditionToggle)) bool bOverride_Pos = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFrame|Spatial Pose", meta=(EditCondition="bOverride_Pos")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Frame|Spatial Pose", meta=(EditCondition="bOverride_Pos")) FVector Pos = FVector::ZeroVector; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFrame|Orientation", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Frame|Orientation", meta=(InlineEditConditionToggle)) bool bOverride_Quat = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFrame|Orientation", meta=(EditCondition="bOverride_Quat")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Frame|Orientation", meta=(EditCondition="bOverride_Quat")) FQuat Quat = FQuat::Identity; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFrame", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Frame", meta=(InlineEditConditionToggle)) bool bOverride_childclass = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFrame", meta=(EditCondition="bOverride_childclass")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Frame", meta=(EditCondition="bOverride_childclass")) FString childclass = TEXT(""); // --- CODEGEN_PROPERTIES_END --- diff --git a/Source/URLab/Public/MuJoCo/Components/Constraints/MjEquality.h b/Source/URLab/Public/MuJoCo/Components/Constraints/MjEquality.h index ef60903..1227205 100644 --- a/Source/URLab/Public/MuJoCo/Components/Constraints/MjEquality.h +++ b/Source/URLab/Public/MuJoCo/Components/Constraints/MjEquality.h @@ -58,58 +58,58 @@ class URLAB_API UMjEquality : public UMjComponent public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjEquality", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Equality", meta=(InlineEditConditionToggle)) bool bOverride_relpose = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjEquality", meta=(EditCondition="bOverride_relpose")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Equality", meta=(EditCondition="bOverride_relpose")) TArray relpose = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjEquality", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Equality", meta=(InlineEditConditionToggle)) bool bOverride_anchor = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjEquality", meta=(EditCondition="bOverride_anchor")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Equality", meta=(EditCondition="bOverride_anchor")) TArray anchor = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjEquality", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Equality", meta=(InlineEditConditionToggle)) bool bOverride_site1 = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjEquality", meta=(EditCondition="bOverride_site1")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Equality", meta=(EditCondition="bOverride_site1")) FString site1 = TEXT(""); - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjEquality", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Equality", meta=(InlineEditConditionToggle)) bool bOverride_site2 = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjEquality", meta=(EditCondition="bOverride_site2")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Equality", meta=(EditCondition="bOverride_site2")) FString site2 = TEXT(""); - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjEquality", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Equality", meta=(InlineEditConditionToggle)) bool bOverride_active = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjEquality", meta=(EditCondition="bOverride_active")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Equality", meta=(EditCondition="bOverride_active")) float active = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjEquality", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Equality", meta=(InlineEditConditionToggle)) bool bOverride_solref = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjEquality", meta=(EditCondition="bOverride_solref")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Equality", meta=(EditCondition="bOverride_solref")) TArray solref = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjEquality", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Equality", meta=(InlineEditConditionToggle)) bool bOverride_solimp = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjEquality", meta=(EditCondition="bOverride_solimp")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Equality", meta=(EditCondition="bOverride_solimp")) TArray solimp = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjEquality", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Equality", meta=(InlineEditConditionToggle)) bool bOverride_torquescale = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjEquality", meta=(EditCondition="bOverride_torquescale")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Equality", meta=(EditCondition="bOverride_torquescale")) float torquescale = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjEquality", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Equality", meta=(InlineEditConditionToggle)) bool bOverride_polycoef = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjEquality", meta=(EditCondition="bOverride_polycoef")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Equality", meta=(EditCondition="bOverride_polycoef")) TArray polycoef = {}; // --- CODEGEN_PROPERTIES_END --- diff --git a/Source/URLab/Public/MuJoCo/Components/Defaults/MjDefault.h b/Source/URLab/Public/MuJoCo/Components/Defaults/MjDefault.h index 0956192..3bab9ed 100644 --- a/Source/URLab/Public/MuJoCo/Components/Defaults/MjDefault.h +++ b/Source/URLab/Public/MuJoCo/Components/Defaults/MjDefault.h @@ -55,12 +55,16 @@ class URLAB_API UMjDefault : public UMjComponent /** @brief Default constructor. */ UMjDefault(); - /** @brief Name of the default class. If empty, these defaults apply to the global scope. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Default") + /** @brief Name of the default class. If empty, these defaults apply to the global scope. + * Hidden from the Details panel — synced from the SCS hierarchy. */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Default", + meta=(EditCondition="false", EditConditionHides)) FString ClassName; - /** @brief Name of the parent default class for inheritance. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Default") + /** @brief Name of the parent default class for inheritance. Hidden from the Details panel — + * synced from the SCS hierarchy. */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Default", + meta=(EditCondition="false", EditConditionHides)) FString ParentClassName; /** diff --git a/Source/URLab/Public/MuJoCo/Components/Deformable/MjFlexcomp.h b/Source/URLab/Public/MuJoCo/Components/Deformable/MjFlexcomp.h index 7d60c16..98020f6 100644 --- a/Source/URLab/Public/MuJoCo/Components/Deformable/MjFlexcomp.h +++ b/Source/URLab/Public/MuJoCo/Components/Deformable/MjFlexcomp.h @@ -71,124 +71,124 @@ class URLAB_API UMjFlexcomp : public UMjComponent public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFlexcomp|Spatial Pose", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Flexcomp|Spatial Pose", meta=(InlineEditConditionToggle)) bool bOverride_Pos = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFlexcomp|Spatial Pose", meta=(EditCondition="bOverride_Pos")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Flexcomp|Spatial Pose", meta=(EditCondition="bOverride_Pos")) FVector Pos = FVector::ZeroVector; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFlexcomp|Orientation", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Flexcomp|Orientation", meta=(InlineEditConditionToggle)) bool bOverride_Quat = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFlexcomp|Orientation", meta=(EditCondition="bOverride_Quat")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Flexcomp|Orientation", meta=(EditCondition="bOverride_Quat")) FQuat Quat = FQuat::Identity; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFlexcomp", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Flexcomp", meta=(InlineEditConditionToggle)) bool bOverride_group = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFlexcomp", meta=(EditCondition="bOverride_group")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Flexcomp", meta=(EditCondition="bOverride_group")) int32 group = 0; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFlexcomp", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Flexcomp", meta=(InlineEditConditionToggle)) bool bOverride_dim = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFlexcomp", meta=(EditCondition="bOverride_dim")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Flexcomp", meta=(EditCondition="bOverride_dim")) int32 dim = 0; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFlexcomp", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Flexcomp", meta=(InlineEditConditionToggle)) bool bOverride_count = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFlexcomp", meta=(EditCondition="bOverride_count")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Flexcomp", meta=(EditCondition="bOverride_count")) TArray count = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFlexcomp", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Flexcomp", meta=(InlineEditConditionToggle)) bool bOverride_cellcount = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFlexcomp", meta=(EditCondition="bOverride_cellcount")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Flexcomp", meta=(EditCondition="bOverride_cellcount")) TArray cellcount = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFlexcomp", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Flexcomp", meta=(InlineEditConditionToggle)) bool bOverride_spacing = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFlexcomp", meta=(EditCondition="bOverride_spacing")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Flexcomp", meta=(EditCondition="bOverride_spacing")) TArray spacing = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFlexcomp", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Flexcomp", meta=(InlineEditConditionToggle)) bool bOverride_radius = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFlexcomp", meta=(EditCondition="bOverride_radius")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Flexcomp", meta=(EditCondition="bOverride_radius")) float radius = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFlexcomp", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Flexcomp", meta=(InlineEditConditionToggle)) bool bOverride_rigid = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFlexcomp", meta=(EditCondition="bOverride_rigid")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Flexcomp", meta=(EditCondition="bOverride_rigid")) bool rigid = false; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFlexcomp", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Flexcomp", meta=(InlineEditConditionToggle)) bool bOverride_mass = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFlexcomp", meta=(EditCondition="bOverride_mass")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Flexcomp", meta=(EditCondition="bOverride_mass")) float mass = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFlexcomp", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Flexcomp", meta=(InlineEditConditionToggle)) bool bOverride_inertiabox = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFlexcomp", meta=(EditCondition="bOverride_inertiabox")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Flexcomp", meta=(EditCondition="bOverride_inertiabox")) float inertiabox = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFlexcomp", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Flexcomp", meta=(InlineEditConditionToggle)) bool bOverride_scale = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFlexcomp", meta=(EditCondition="bOverride_scale")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Flexcomp", meta=(EditCondition="bOverride_scale")) TArray scale = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFlexcomp", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Flexcomp", meta=(InlineEditConditionToggle)) bool bOverride_file = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFlexcomp", meta=(EditCondition="bOverride_file")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Flexcomp", meta=(EditCondition="bOverride_file")) FString file = TEXT(""); - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFlexcomp", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Flexcomp", meta=(InlineEditConditionToggle)) bool bOverride_point = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFlexcomp", meta=(EditCondition="bOverride_point")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Flexcomp", meta=(EditCondition="bOverride_point")) TArray point = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFlexcomp", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Flexcomp", meta=(InlineEditConditionToggle)) bool bOverride_element = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFlexcomp", meta=(EditCondition="bOverride_element")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Flexcomp", meta=(EditCondition="bOverride_element")) TArray element = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFlexcomp", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Flexcomp", meta=(InlineEditConditionToggle)) bool bOverride_texcoord = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFlexcomp", meta=(EditCondition="bOverride_texcoord")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Flexcomp", meta=(EditCondition="bOverride_texcoord")) TArray texcoord = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFlexcomp", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Flexcomp", meta=(InlineEditConditionToggle)) bool bOverride_material = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFlexcomp", meta=(EditCondition="bOverride_material")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Flexcomp", meta=(EditCondition="bOverride_material")) FString material = TEXT(""); - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFlexcomp", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Flexcomp", meta=(InlineEditConditionToggle)) bool bOverride_rgba = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFlexcomp", meta=(EditCondition="bOverride_rgba")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Flexcomp", meta=(EditCondition="bOverride_rgba")) FLinearColor rgba = FLinearColor::White; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFlexcomp", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Flexcomp", meta=(InlineEditConditionToggle)) bool bOverride_flatskin = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFlexcomp", meta=(EditCondition="bOverride_flatskin")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Flexcomp", meta=(EditCondition="bOverride_flatskin")) bool flatskin = false; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjFlexcomp", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Flexcomp", meta=(InlineEditConditionToggle)) bool bOverride_origin = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjFlexcomp", meta=(EditCondition="bOverride_origin")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Flexcomp", meta=(EditCondition="bOverride_origin")) TArray origin = {}; // --- CODEGEN_PROPERTIES_END --- diff --git a/Source/URLab/Public/MuJoCo/Components/Geometry/MjGeom.h b/Source/URLab/Public/MuJoCo/Components/Geometry/MjGeom.h index 58c24f0..224be98 100644 --- a/Source/URLab/Public/MuJoCo/Components/Geometry/MjGeom.h +++ b/Source/URLab/Public/MuJoCo/Components/Geometry/MjGeom.h @@ -97,136 +97,136 @@ class URLAB_API UMjGeom : public UMjComponent public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom|Spatial Pose", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom|Spatial Pose", meta=(InlineEditConditionToggle)) bool bOverride_Pos = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom|Spatial Pose", meta=(EditCondition="bOverride_Pos")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom|Spatial Pose", meta=(EditCondition="bOverride_Pos")) FVector Pos = FVector::ZeroVector; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom|Orientation", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom|Orientation", meta=(InlineEditConditionToggle)) bool bOverride_Quat = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom|Orientation", meta=(EditCondition="bOverride_Quat")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom|Orientation", meta=(EditCondition="bOverride_Quat")) FQuat Quat = FQuat::Identity; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom", meta=(InlineEditConditionToggle)) bool bOverride_contype = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom", meta=(EditCondition="bOverride_contype")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(EditCondition="bOverride_contype")) int32 contype = 0; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom", meta=(InlineEditConditionToggle)) bool bOverride_conaffinity = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom", meta=(EditCondition="bOverride_conaffinity")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(EditCondition="bOverride_conaffinity")) int32 conaffinity = 0; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom", meta=(InlineEditConditionToggle)) bool bOverride_condim = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom", meta=(EditCondition="bOverride_condim")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(EditCondition="bOverride_condim")) int32 condim = 0; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom", meta=(InlineEditConditionToggle)) bool bOverride_group = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom", meta=(EditCondition="bOverride_group")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(EditCondition="bOverride_group")) int32 group = 0; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom", meta=(InlineEditConditionToggle)) bool bOverride_priority = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom", meta=(EditCondition="bOverride_priority")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(EditCondition="bOverride_priority")) int32 priority = 0; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom", meta=(InlineEditConditionToggle)) bool bOverride_size = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom", meta=(EditCondition="bOverride_size")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(EditCondition="bOverride_size")) TArray size = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom", meta=(InlineEditConditionToggle)) bool bOverride_material = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom", meta=(EditCondition="bOverride_material")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(EditCondition="bOverride_material")) FString material = TEXT(""); - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom", meta=(InlineEditConditionToggle)) bool bOverride_friction = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom", meta=(EditCondition="bOverride_friction")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(EditCondition="bOverride_friction")) TArray friction = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom", meta=(InlineEditConditionToggle)) bool bOverride_mass = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom", meta=(EditCondition="bOverride_mass")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(EditCondition="bOverride_mass")) float mass = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom", meta=(InlineEditConditionToggle)) bool bOverride_density = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom", meta=(EditCondition="bOverride_density")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(EditCondition="bOverride_density")) float density = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom", meta=(InlineEditConditionToggle)) bool bOverride_solmix = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom", meta=(EditCondition="bOverride_solmix")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(EditCondition="bOverride_solmix")) float solmix = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom", meta=(InlineEditConditionToggle)) bool bOverride_solref = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom", meta=(EditCondition="bOverride_solref")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(EditCondition="bOverride_solref")) TArray solref = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom", meta=(InlineEditConditionToggle)) bool bOverride_solimp = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom", meta=(EditCondition="bOverride_solimp")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(EditCondition="bOverride_solimp")) TArray solimp = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom", meta=(InlineEditConditionToggle)) bool bOverride_margin = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom", meta=(EditCondition="bOverride_margin")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(EditCondition="bOverride_margin")) float margin = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom", meta=(InlineEditConditionToggle)) bool bOverride_gap = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom", meta=(EditCondition="bOverride_gap")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(EditCondition="bOverride_gap")) float gap = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom", meta=(InlineEditConditionToggle)) bool bOverride_hfield = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom", meta=(EditCondition="bOverride_hfield")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(EditCondition="bOverride_hfield")) FString hfield = TEXT(""); - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom", meta=(InlineEditConditionToggle)) bool bOverride_mesh = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom", meta=(EditCondition="bOverride_mesh")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(EditCondition="bOverride_mesh")) FString mesh = TEXT(""); - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom", meta=(InlineEditConditionToggle)) bool bOverride_fitscale = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom", meta=(EditCondition="bOverride_fitscale")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(EditCondition="bOverride_fitscale")) bool fitscale = false; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom", meta=(InlineEditConditionToggle)) bool bOverride_rgba = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom", meta=(EditCondition="bOverride_rgba")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(EditCondition="bOverride_rgba")) FLinearColor rgba = FLinearColor::White; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjGeom", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Geom", meta=(InlineEditConditionToggle)) bool bOverride_fluidcoef = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjGeom", meta=(EditCondition="bOverride_fluidcoef")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(EditCondition="bOverride_fluidcoef")) TArray fluidcoef = {}; // --- CODEGEN_PROPERTIES_END --- @@ -418,9 +418,11 @@ class URLAB_API UMjGeom : public UMjComponent meta=(EditCondition="Type != EMjGeomType::Mesh", EditConditionHides)) TObjectPtr OverrideMaterial; - /** @brief Reference to a UMjDefault component for default class inheritance. Set via detail customization dropdown. */ - UPROPERTY(BlueprintReadWrite, Category = "MuJoCo|Geom") - UMjDefault* DefaultClass; + /** @brief Reference to a UMjDefault component for default class inheritance. Hidden from the + * Details panel — synced from MjClassName via the editor dropdown. */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", + meta=(EditCondition="false", EditConditionHides)) + UMjDefault* DefaultClass = nullptr; /** * @brief Registers this geom to the MuJoCo spec. diff --git a/Source/URLab/Public/MuJoCo/Components/Geometry/MjSite.h b/Source/URLab/Public/MuJoCo/Components/Geometry/MjSite.h index 1a1b1e5..a65ca84 100644 --- a/Source/URLab/Public/MuJoCo/Components/Geometry/MjSite.h +++ b/Source/URLab/Public/MuJoCo/Components/Geometry/MjSite.h @@ -61,40 +61,40 @@ class URLAB_API UMjSite : public UMjComponent public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjSite|Spatial Pose", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Site|Spatial Pose", meta=(InlineEditConditionToggle)) bool bOverride_Pos = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjSite|Spatial Pose", meta=(EditCondition="bOverride_Pos")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Site|Spatial Pose", meta=(EditCondition="bOverride_Pos")) FVector Pos = FVector::ZeroVector; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjSite|Orientation", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Site|Orientation", meta=(InlineEditConditionToggle)) bool bOverride_Quat = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjSite|Orientation", meta=(EditCondition="bOverride_Quat")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Site|Orientation", meta=(EditCondition="bOverride_Quat")) FQuat Quat = FQuat::Identity; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjSite", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Site", meta=(InlineEditConditionToggle)) bool bOverride_group = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjSite", meta=(EditCondition="bOverride_group")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Site", meta=(EditCondition="bOverride_group")) int32 group = 0; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjSite", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Site", meta=(InlineEditConditionToggle)) bool bOverride_material = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjSite", meta=(EditCondition="bOverride_material")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Site", meta=(EditCondition="bOverride_material")) FString material = TEXT(""); - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjSite", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Site", meta=(InlineEditConditionToggle)) bool bOverride_size = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjSite", meta=(EditCondition="bOverride_size")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Site", meta=(EditCondition="bOverride_size")) TArray size = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjSite", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Site", meta=(InlineEditConditionToggle)) bool bOverride_rgba = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjSite", meta=(EditCondition="bOverride_rgba")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Site", meta=(EditCondition="bOverride_rgba")) FLinearColor rgba = FLinearColor::White; // --- CODEGEN_PROPERTIES_END --- @@ -145,8 +145,10 @@ class URLAB_API UMjSite : public UMjComponent TArray GetDefaultClassOptions() const; #endif - /** @brief Reference to a UMjDefault component for default class inheritance. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Site") + /** @brief Reference to a UMjDefault component for default class inheritance. Hidden from the + * Details panel — synced from MjClassName via the editor dropdown. */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Site", + meta=(EditCondition="false", EditConditionHides)) UMjDefault* DefaultClass = nullptr; virtual FString GetMjClassName() const override diff --git a/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjEllipsoid.h b/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjEllipsoid.h index 4bd629c..1b3be16 100644 --- a/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjEllipsoid.h +++ b/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjEllipsoid.h @@ -44,7 +44,7 @@ class URLAB_API UMjEllipsoid : public UMjGeom UMjEllipsoid(); // --- CODEGEN_PROPERTIES_START --- - + // (no type-specific schema attrs) // --- CODEGEN_PROPERTIES_END --- virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; diff --git a/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjPlane.h b/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjPlane.h index 3a43e87..0d1a3ce 100644 --- a/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjPlane.h +++ b/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjPlane.h @@ -44,7 +44,7 @@ class URLAB_API UMjPlane : public UMjGeom UMjPlane(); // --- CODEGEN_PROPERTIES_START --- - + // (no type-specific schema attrs) // --- CODEGEN_PROPERTIES_END --- virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; diff --git a/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjSdf.h b/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjSdf.h index be1a853..9d37141 100644 --- a/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjSdf.h +++ b/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjSdf.h @@ -44,7 +44,7 @@ class URLAB_API UMjSdf : public UMjGeom UMjSdf(); // --- CODEGEN_PROPERTIES_START --- - + // (no type-specific schema attrs) // --- CODEGEN_PROPERTIES_END --- virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; diff --git a/Source/URLab/Public/MuJoCo/Components/Joints/MjBallJoint.h b/Source/URLab/Public/MuJoCo/Components/Joints/MjBallJoint.h index 58550ed..a22c5f1 100644 --- a/Source/URLab/Public/MuJoCo/Components/Joints/MjBallJoint.h +++ b/Source/URLab/Public/MuJoCo/Components/Joints/MjBallJoint.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjBallJoint - * @brief Specific Ball Joint component. + * @brief Autogenerated component representing the MuJoCo 'ball' element. + * + * Subclass of UMjJoint. Sets Type = Ball in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjBallJoint : public UMjJoint { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjBallJoint(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsJoint* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Joints/MjHingeJoint.h b/Source/URLab/Public/MuJoCo/Components/Joints/MjHingeJoint.h index 05a8c55..7639668 100644 --- a/Source/URLab/Public/MuJoCo/Components/Joints/MjHingeJoint.h +++ b/Source/URLab/Public/MuJoCo/Components/Joints/MjHingeJoint.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjHingeJoint - * @brief Specific Hinge Joint component. + * @brief Autogenerated component representing the MuJoCo 'hinge' element. + * + * Subclass of UMjJoint. Sets Type = Hinge in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjHingeJoint : public UMjJoint { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjHingeJoint(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsJoint* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Joints/MjJoint.h b/Source/URLab/Public/MuJoCo/Components/Joints/MjJoint.h index f479928..68bca9f 100644 --- a/Source/URLab/Public/MuJoCo/Components/Joints/MjJoint.h +++ b/Source/URLab/Public/MuJoCo/Components/Joints/MjJoint.h @@ -59,112 +59,124 @@ class URLAB_API UMjJoint : public UMjComponent public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjJoint", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint|Spatial Pose", meta=(InlineEditConditionToggle)) + bool bOverride_Pos = false; + + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint|Spatial Pose", meta=(EditCondition="bOverride_Pos")) + FVector Pos = FVector::ZeroVector; + + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) bool bOverride_group = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjJoint", meta=(EditCondition="bOverride_group")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_group")) int32 group = 0; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjJoint", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) + bool bOverride_Axis = false; + + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_Axis")) + FVector Axis = FVector(0.0f, 0.0f, 1.0f); + + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) bool bOverride_springdamper = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjJoint", meta=(EditCondition="bOverride_springdamper")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_springdamper")) TArray springdamper = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjJoint", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) bool bOverride_limited = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjJoint", meta=(EditCondition="bOverride_limited")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_limited")) bool limited = false; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjJoint", meta=(InlineEditConditionToggle)) - bool bOverride_actuatorfrclimited = false; + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) + bool bOverride_ActFrcLimited = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjJoint", meta=(EditCondition="bOverride_actuatorfrclimited")) - bool actuatorfrclimited = false; + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_ActFrcLimited")) + bool ActFrcLimited = false; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjJoint", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) bool bOverride_solreflimit = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjJoint", meta=(EditCondition="bOverride_solreflimit")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_solreflimit")) TArray solreflimit = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjJoint", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) bool bOverride_solimplimit = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjJoint", meta=(EditCondition="bOverride_solimplimit")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_solimplimit")) TArray solimplimit = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjJoint", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) bool bOverride_solreffriction = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjJoint", meta=(EditCondition="bOverride_solreffriction")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_solreffriction")) TArray solreffriction = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjJoint", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) bool bOverride_solimpfriction = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjJoint", meta=(EditCondition="bOverride_solimpfriction")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_solimpfriction")) TArray solimpfriction = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjJoint", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) bool bOverride_stiffness = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjJoint", meta=(EditCondition="bOverride_stiffness")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_stiffness")) TArray stiffness = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjJoint", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) bool bOverride_range = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjJoint", meta=(EditCondition="bOverride_range")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_range")) TArray range = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjJoint", meta=(InlineEditConditionToggle)) - bool bOverride_actuatorfrcrange = false; + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) + bool bOverride_ActFrcRange = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjJoint", meta=(EditCondition="bOverride_actuatorfrcrange")) - TArray actuatorfrcrange = {}; + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_ActFrcRange")) + TArray ActFrcRange = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjJoint", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) bool bOverride_actuatorgravcomp = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjJoint", meta=(EditCondition="bOverride_actuatorgravcomp")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_actuatorgravcomp")) float actuatorgravcomp = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjJoint", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) bool bOverride_margin = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjJoint", meta=(EditCondition="bOverride_margin")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_margin")) float margin = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjJoint", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) bool bOverride_ref = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjJoint", meta=(EditCondition="bOverride_ref")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_ref")) float ref = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjJoint", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) bool bOverride_springref = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjJoint", meta=(EditCondition="bOverride_springref")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_springref")) float springref = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjJoint", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) bool bOverride_armature = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjJoint", meta=(EditCondition="bOverride_armature")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_armature")) float armature = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjJoint", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) bool bOverride_damping = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjJoint", meta=(EditCondition="bOverride_damping")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_damping")) TArray damping = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjJoint", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) bool bOverride_frictionloss = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjJoint", meta=(EditCondition="bOverride_frictionloss")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_frictionloss")) float frictionloss = 0.0f; // --- CODEGEN_PROPERTIES_END --- @@ -255,8 +267,10 @@ class URLAB_API UMjJoint : public UMjComponent TArray GetDefaultClassOptions() const; #endif - /** @brief Reference to a UMjDefault component for default class inheritance. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint") + /** @brief Reference to a UMjDefault component for default class inheritance. Hidden from the + * Details panel — synced from MjClassName via the editor dropdown. */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", + meta=(EditCondition="false", EditConditionHides)) class UMjDefault* DefaultClass = nullptr; virtual FString GetMjClassName() const override @@ -289,15 +303,10 @@ class URLAB_API UMjJoint : public UMjComponent UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_Type")) EMjJointType Type = EMjJointType::Hinge; - /** @brief Override toggle for Axis. */ - UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) - bool bOverride_Axis = false; - - /** @brief Local joint axis vector (relative to parent body). Ignored for Free/Ball joints. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_Axis")) - FVector Axis = FVector(0.0f, 0.0f, 1.0f); - - + // Axis UPROPERTY is codegen-emitted (rules.joint.vec3_convert.axis = + // y_negate, property_renames.axis = "Axis", property_defaults.axis = + // FVector(0,0,1)). The Pos UPROPERTY is codegen-emitted via the + // spatial_pose canon. // --- Physics Properties (with override toggles) --- diff --git a/Source/URLab/Public/MuJoCo/Components/Joints/MjSlideJoint.h b/Source/URLab/Public/MuJoCo/Components/Joints/MjSlideJoint.h index 68c7a6f..775e35c 100644 --- a/Source/URLab/Public/MuJoCo/Components/Joints/MjSlideJoint.h +++ b/Source/URLab/Public/MuJoCo/Components/Joints/MjSlideJoint.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjSlideJoint - * @brief Specific Slide Joint component. + * @brief Autogenerated component representing the MuJoCo 'slide' element. + * + * Subclass of UMjJoint. Sets Type = Slide in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjSlideJoint : public UMjJoint { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjSlideJoint(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsJoint* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Keyframes/MjKeyframe.h b/Source/URLab/Public/MuJoCo/Components/Keyframes/MjKeyframe.h index 4016eeb..cfec868 100644 --- a/Source/URLab/Public/MuJoCo/Components/Keyframes/MjKeyframe.h +++ b/Source/URLab/Public/MuJoCo/Components/Keyframes/MjKeyframe.h @@ -41,46 +41,46 @@ class URLAB_API UMjKeyframe : public UMjComponent public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjKeyframe", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Keyframe", meta=(InlineEditConditionToggle)) bool bOverride_Time = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjKeyframe", meta=(EditCondition="bOverride_Time")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Keyframe", meta=(EditCondition="bOverride_Time")) float Time = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjKeyframe", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Keyframe", meta=(InlineEditConditionToggle)) bool bOverride_Qpos = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjKeyframe", meta=(EditCondition="bOverride_Qpos")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Keyframe", meta=(EditCondition="bOverride_Qpos")) TArray Qpos = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjKeyframe", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Keyframe", meta=(InlineEditConditionToggle)) bool bOverride_Qvel = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjKeyframe", meta=(EditCondition="bOverride_Qvel")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Keyframe", meta=(EditCondition="bOverride_Qvel")) TArray Qvel = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjKeyframe", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Keyframe", meta=(InlineEditConditionToggle)) bool bOverride_Act = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjKeyframe", meta=(EditCondition="bOverride_Act")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Keyframe", meta=(EditCondition="bOverride_Act")) TArray Act = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjKeyframe", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Keyframe", meta=(InlineEditConditionToggle)) bool bOverride_Mpos = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjKeyframe", meta=(EditCondition="bOverride_Mpos")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Keyframe", meta=(EditCondition="bOverride_Mpos")) TArray Mpos = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjKeyframe", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Keyframe", meta=(InlineEditConditionToggle)) bool bOverride_Mquat = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjKeyframe", meta=(EditCondition="bOverride_Mquat")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Keyframe", meta=(EditCondition="bOverride_Mquat")) TArray Mquat = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjKeyframe", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Keyframe", meta=(InlineEditConditionToggle)) bool bOverride_Ctrl = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjKeyframe", meta=(EditCondition="bOverride_Ctrl")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Keyframe", meta=(EditCondition="bOverride_Ctrl")) TArray Ctrl = {}; // --- CODEGEN_PROPERTIES_END --- diff --git a/Source/URLab/Public/MuJoCo/Components/MjComponent.h b/Source/URLab/Public/MuJoCo/Components/MjComponent.h index 9c2ef78..091ff90 100644 --- a/Source/URLab/Public/MuJoCo/Components/MjComponent.h +++ b/Source/URLab/Public/MuJoCo/Components/MjComponent.h @@ -105,10 +105,14 @@ class URLAB_API UMjComponent : public USceneComponent, public IMjSpecElement return ViewType(); } - // 1. Try ID based binding via spec element - // NOTE: mjs_getId can return stale/garbage IDs after mjs_attach merges - // a child spec into the root. We validate the ID against model bounds - // before using it. + // 1. Try ID based binding via spec element (the primary path) + // EMPIRICAL (probe test 2026-05-27, MjBindingPathProbeTest): + // mjs_getId returns the correct compiled-model id after mjs_attach + // in current MuJoCo (mj=6882095). Path 1 == Path 2 == Bind in every + // tested scenario. We keep the bounds check + Path 2 fallback as + // safety nets for edge cases not yet observed (recompile mid-PIE, + // multi-attach order, runtime component churn). The old v0.1-alpha + // comment claiming "stale/garbage IDs after mjs_attach" is obsolete. if (m_SpecElement) { int id = mjs_getId(m_SpecElement); @@ -150,6 +154,39 @@ class URLAB_API UMjComponent : public USceneComponent, public IMjSpecElement return ViewType(); } + /** + * @brief Bind a typed view AND cache the resulting mjId on the component. + * + * Collapses the 4-line pattern that 16 base components currently hand-roll: + * Super::Bind(model, data, prefix); + * m_View = BindToView(prefix); + * if (m_View.id != -1) m_ID = m_View.id; + * else UE_LOG warning; + * + * After v8 the per-category Bind() override becomes: + * Super::Bind(model, data, prefix); + * BindAndCacheView(m_View, prefix); + * + * 3 components keep their own Bind() override for real work + * (MjTactileSensor runtime Dim sync, MjPDController, MjFlexcomp); they + * are free to call this helper too if they want. + */ + template + void BindAndCacheView(ViewType& OutView, const FString& Prefix) + { + OutView = BindToView(Prefix); + if (OutView.id != -1) + { + m_ID = OutView.id; + } + else + { + UE_LOG(LogURLabBind, Warning, + TEXT("[BindAndCacheView] '%s' — failed to bind (Prefix='%s', type=%d). m_ID stays -1."), + *GetName(), *Prefix, ViewType::obj_type); + } + } + /** @brief Checks if the component is successfully bound to MuJoCo runtime. */ UFUNCTION(BlueprintCallable, Category = "MuJoCo|Base") bool IsBound() const; @@ -158,6 +195,9 @@ class URLAB_API UMjComponent : public USceneComponent, public IMjSpecElement UFUNCTION(BlueprintCallable, Category = "MuJoCo|Base") int GetMjID() const { return m_ID; } + /** @brief Diagnostic-only accessor for the spec element pointer. Used by binding-path probes. */ + mjsElement* GetSpecElementForDiagnostics() const { return m_SpecElement; } + /** @brief If true, this component is a template in a block. Auto-resolved in Setup(). */ UPROPERTY() bool bIsDefault = false; diff --git a/Source/URLab/Public/MuJoCo/Components/Physics/MjContactExclude.h b/Source/URLab/Public/MuJoCo/Components/Physics/MjContactExclude.h index 6bc92f5..2617a59 100644 --- a/Source/URLab/Public/MuJoCo/Components/Physics/MjContactExclude.h +++ b/Source/URLab/Public/MuJoCo/Components/Physics/MjContactExclude.h @@ -44,24 +44,25 @@ class URLAB_API UMjContactExclude : public USceneComponent, public IMjSpecElemen public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjContactExclude", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|ContactExclude", meta=(InlineEditConditionToggle)) bool bOverride_body1 = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjContactExclude", meta=(EditCondition="bOverride_body1")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|ContactExclude", meta=(EditCondition="bOverride_body1")) FString body1 = TEXT(""); - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjContactExclude", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|ContactExclude", meta=(InlineEditConditionToggle)) bool bOverride_body2 = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjContactExclude", meta=(EditCondition="bOverride_body2")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|ContactExclude", meta=(EditCondition="bOverride_body2")) FString body2 = TEXT(""); // --- CODEGEN_PROPERTIES_END --- /** @brief Default constructor. */ UMjContactExclude(); - /** @brief Name of the contact exclusion (optional). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Contact Exclude") + /** @brief Name of the contact exclusion (optional). Hidden from the Details panel — synced from MjName. */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Contact Exclude", + meta=(EditCondition="false", EditConditionHides)) FString Name; @@ -85,7 +86,8 @@ class URLAB_API UMjContactExclude : public USceneComponent, public IMjSpecElemen */ virtual void RegisterToSpec(class FMujocoSpecWrapper& Wrapper, mjsBody* ParentBody = nullptr) override; - virtual void Bind(mjModel* model, mjData* data, const FString& Prefix = TEXT("")) override; + /** No-op: contact excludes are global static data, no per-instance runtime binding. Required by IMjSpecElement. */ + virtual void Bind(mjModel* model, mjData* data, const FString& Prefix = TEXT("")) override {} #if WITH_EDITOR UFUNCTION() diff --git a/Source/URLab/Public/MuJoCo/Components/Physics/MjContactPair.h b/Source/URLab/Public/MuJoCo/Components/Physics/MjContactPair.h index 580fd4e..4c51f08 100644 --- a/Source/URLab/Public/MuJoCo/Components/Physics/MjContactPair.h +++ b/Source/URLab/Public/MuJoCo/Components/Physics/MjContactPair.h @@ -44,66 +44,67 @@ class URLAB_API UMjContactPair : public USceneComponent, public IMjSpecElement public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjContactPair", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|ContactPair", meta=(InlineEditConditionToggle)) bool bOverride_geom1 = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjContactPair", meta=(EditCondition="bOverride_geom1")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|ContactPair", meta=(EditCondition="bOverride_geom1")) FString geom1 = TEXT(""); - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjContactPair", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|ContactPair", meta=(InlineEditConditionToggle)) bool bOverride_geom2 = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjContactPair", meta=(EditCondition="bOverride_geom2")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|ContactPair", meta=(EditCondition="bOverride_geom2")) FString geom2 = TEXT(""); - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjContactPair", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|ContactPair", meta=(InlineEditConditionToggle)) bool bOverride_condim = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjContactPair", meta=(EditCondition="bOverride_condim")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|ContactPair", meta=(EditCondition="bOverride_condim")) int32 condim = 0; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjContactPair", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|ContactPair", meta=(InlineEditConditionToggle)) bool bOverride_friction = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjContactPair", meta=(EditCondition="bOverride_friction")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|ContactPair", meta=(EditCondition="bOverride_friction")) TArray friction = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjContactPair", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|ContactPair", meta=(InlineEditConditionToggle)) bool bOverride_solref = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjContactPair", meta=(EditCondition="bOverride_solref")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|ContactPair", meta=(EditCondition="bOverride_solref")) TArray solref = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjContactPair", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|ContactPair", meta=(InlineEditConditionToggle)) bool bOverride_solreffriction = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjContactPair", meta=(EditCondition="bOverride_solreffriction")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|ContactPair", meta=(EditCondition="bOverride_solreffriction")) TArray solreffriction = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjContactPair", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|ContactPair", meta=(InlineEditConditionToggle)) bool bOverride_solimp = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjContactPair", meta=(EditCondition="bOverride_solimp")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|ContactPair", meta=(EditCondition="bOverride_solimp")) TArray solimp = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjContactPair", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|ContactPair", meta=(InlineEditConditionToggle)) bool bOverride_gap = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjContactPair", meta=(EditCondition="bOverride_gap")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|ContactPair", meta=(EditCondition="bOverride_gap")) float gap = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjContactPair", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|ContactPair", meta=(InlineEditConditionToggle)) bool bOverride_margin = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjContactPair", meta=(EditCondition="bOverride_margin")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|ContactPair", meta=(EditCondition="bOverride_margin")) float margin = 0.0f; // --- CODEGEN_PROPERTIES_END --- /** @brief Default constructor. */ UMjContactPair(); - /** @brief Name of the contact pair (optional). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Contact Pair") + /** @brief Name of the contact pair (optional). Hidden from the Details panel — synced from MjName. */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Contact Pair", + meta=(EditCondition="false", EditConditionHides)) FString Name; @@ -133,7 +134,8 @@ class URLAB_API UMjContactPair : public USceneComponent, public IMjSpecElement */ virtual void RegisterToSpec(class FMujocoSpecWrapper& Wrapper, mjsBody* ParentBody = nullptr) override; - virtual void Bind(mjModel* model, mjData* data, const FString& Prefix = TEXT("")) override; + /** No-op: contact pairs are global static data, no per-instance runtime binding. Required by IMjSpecElement. */ + virtual void Bind(mjModel* model, mjData* data, const FString& Prefix = TEXT("")) override {} #if WITH_EDITOR UFUNCTION() diff --git a/Source/URLab/Public/MuJoCo/Components/Physics/MjInertial.h b/Source/URLab/Public/MuJoCo/Components/Physics/MjInertial.h index 095dd27..9f13870 100644 --- a/Source/URLab/Public/MuJoCo/Components/Physics/MjInertial.h +++ b/Source/URLab/Public/MuJoCo/Components/Physics/MjInertial.h @@ -38,34 +38,34 @@ class URLAB_API UMjInertial : public UMjComponent public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjInertial|Spatial Pose", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Inertial|Spatial Pose", meta=(InlineEditConditionToggle)) bool bOverride_Pos = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjInertial|Spatial Pose", meta=(EditCondition="bOverride_Pos")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Inertial|Spatial Pose", meta=(EditCondition="bOverride_Pos")) FVector Pos = FVector::ZeroVector; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjInertial|Orientation", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Inertial|Orientation", meta=(InlineEditConditionToggle)) bool bOverride_Quat = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjInertial|Orientation", meta=(EditCondition="bOverride_Quat")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Inertial|Orientation", meta=(EditCondition="bOverride_Quat")) FQuat Quat = FQuat::Identity; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjInertial", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Inertial", meta=(InlineEditConditionToggle)) bool bOverride_mass = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjInertial", meta=(EditCondition="bOverride_mass")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Inertial", meta=(EditCondition="bOverride_mass")) float mass = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjInertial", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Inertial", meta=(InlineEditConditionToggle)) bool bOverride_diaginertia = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjInertial", meta=(EditCondition="bOverride_diaginertia")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Inertial", meta=(EditCondition="bOverride_diaginertia")) TArray diaginertia = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjInertial", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Inertial", meta=(InlineEditConditionToggle)) bool bOverride_fullinertia = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjInertial", meta=(EditCondition="bOverride_fullinertia")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Inertial", meta=(EditCondition="bOverride_fullinertia")) TArray fullinertia = {}; // --- CODEGEN_PROPERTIES_END --- @@ -87,12 +87,6 @@ class URLAB_API UMjInertial : public UMjComponent // Note: Inertial usually doesn't have a direct 'mjsInertial' struct in mjspec.h same as others, // it's often part of body or explicit inertial element. // mjsBody has 'mass', 'inertia', 'fullinertia'. - - /** - * @brief Binds this component to the live MuJoCo simulation. - */ - virtual void Bind(mjModel* model, mjData* data, const FString& Prefix = TEXT("")) override; - /** * @brief Registers/Applies this inertial to the parent body in the spec. * @param Wrapper The spec wrapper instance. diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjAccelerometer.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjAccelerometer.h index 8844dd5..a37f099 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjAccelerometer.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjAccelerometer.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjAccelerometer - * @brief Specific Accelerometer Sensor component. + * @brief Autogenerated component representing the MuJoCo 'accelerometer' element. + * + * Subclass of UMjSensor. Sets Type = Accelerometer in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjAccelerometer : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjAccelerometer(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjActuatorFrcSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjActuatorFrcSensor.h index 37bdc00..b9bd325 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjActuatorFrcSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjActuatorFrcSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjActuatorFrcSensor - * @brief Specific ActuatorFrc Sensor component. + * @brief Autogenerated component representing the MuJoCo 'actuatorfrc' element. + * + * Subclass of UMjSensor. Sets Type = ActuatorFrc in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjActuatorFrcSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjActuatorFrcSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjActuatorPosSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjActuatorPosSensor.h index e40c6b8..53985a5 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjActuatorPosSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjActuatorPosSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjActuatorPosSensor - * @brief Specific ActuatorPos Sensor component. + * @brief Autogenerated component representing the MuJoCo 'actuatorpos' element. + * + * Subclass of UMjSensor. Sets Type = ActuatorPos in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjActuatorPosSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjActuatorPosSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjActuatorVelSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjActuatorVelSensor.h index af8e89b..e199943 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjActuatorVelSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjActuatorVelSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjActuatorVelSensor - * @brief Specific ActuatorVel Sensor component. + * @brief Autogenerated component representing the MuJoCo 'actuatorvel' element. + * + * Subclass of UMjSensor. Sets Type = ActuatorVel in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjActuatorVelSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjActuatorVelSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjBallAngVelSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjBallAngVelSensor.h index 9951314..9085250 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjBallAngVelSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjBallAngVelSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjBallAngVelSensor - * @brief Specific BallAngVel Sensor component. + * @brief Autogenerated component representing the MuJoCo 'ballangvel' element. + * + * Subclass of UMjSensor. Sets Type = BallAngVel in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjBallAngVelSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjBallAngVelSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjBallQuatSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjBallQuatSensor.h index e116d94..e11918d 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjBallQuatSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjBallQuatSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjBallQuatSensor - * @brief Specific BallQuat Sensor component. + * @brief Autogenerated component representing the MuJoCo 'ballquat' element. + * + * Subclass of UMjSensor. Sets Type = BallQuat in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjBallQuatSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjBallQuatSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjCamProjectionSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjCamProjectionSensor.h index 29c3003..7c41bd5 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjCamProjectionSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjCamProjectionSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjCamProjectionSensor - * @brief Specific CamProjection Sensor component. + * @brief Autogenerated component representing the MuJoCo 'camprojection' element. + * + * Subclass of UMjSensor. Sets Type = CamProjection in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjCamProjectionSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjCamProjectionSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjCamera.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjCamera.h index 6d6830f..3a0801c 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjCamera.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjCamera.h @@ -86,76 +86,76 @@ class URLAB_API UMjCamera : public UMjComponent public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjCamera|Spatial Pose", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Camera|Spatial Pose", meta=(InlineEditConditionToggle)) bool bOverride_Pos = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjCamera|Spatial Pose", meta=(EditCondition="bOverride_Pos")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Camera|Spatial Pose", meta=(EditCondition="bOverride_Pos")) FVector Pos = FVector::ZeroVector; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjCamera|Orientation", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Camera|Orientation", meta=(InlineEditConditionToggle)) bool bOverride_Quat = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjCamera|Orientation", meta=(EditCondition="bOverride_Quat")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Camera|Orientation", meta=(EditCondition="bOverride_Quat")) FQuat Quat = FQuat::Identity; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjCamera", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Camera", meta=(InlineEditConditionToggle)) bool bOverride_fovy = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjCamera", meta=(EditCondition="bOverride_fovy")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Camera", meta=(EditCondition="bOverride_fovy")) float fovy = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjCamera", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Camera", meta=(InlineEditConditionToggle)) bool bOverride_ipd = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjCamera", meta=(EditCondition="bOverride_ipd")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Camera", meta=(EditCondition="bOverride_ipd")) float ipd = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjCamera", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Camera", meta=(InlineEditConditionToggle)) bool bOverride_resolution = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjCamera", meta=(EditCondition="bOverride_resolution")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Camera", meta=(EditCondition="bOverride_resolution")) TArray resolution = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjCamera", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Camera", meta=(InlineEditConditionToggle)) bool bOverride_output = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjCamera", meta=(EditCondition="bOverride_output")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Camera", meta=(EditCondition="bOverride_output")) float output = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjCamera", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Camera", meta=(InlineEditConditionToggle)) bool bOverride_target = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjCamera", meta=(EditCondition="bOverride_target")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Camera", meta=(EditCondition="bOverride_target")) FString target = TEXT(""); - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjCamera", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Camera", meta=(InlineEditConditionToggle)) bool bOverride_focal = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjCamera", meta=(EditCondition="bOverride_focal")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Camera", meta=(EditCondition="bOverride_focal")) TArray focal = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjCamera", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Camera", meta=(InlineEditConditionToggle)) bool bOverride_focalpixel = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjCamera", meta=(EditCondition="bOverride_focalpixel")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Camera", meta=(EditCondition="bOverride_focalpixel")) TArray focalpixel = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjCamera", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Camera", meta=(InlineEditConditionToggle)) bool bOverride_principal = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjCamera", meta=(EditCondition="bOverride_principal")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Camera", meta=(EditCondition="bOverride_principal")) TArray principal = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjCamera", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Camera", meta=(InlineEditConditionToggle)) bool bOverride_principalpixel = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjCamera", meta=(EditCondition="bOverride_principalpixel")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Camera", meta=(EditCondition="bOverride_principalpixel")) TArray principalpixel = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjCamera", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Camera", meta=(InlineEditConditionToggle)) bool bOverride_sensorsize = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjCamera", meta=(EditCondition="bOverride_sensorsize")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Camera", meta=(EditCondition="bOverride_sensorsize")) TArray sensorsize = {}; // --- CODEGEN_PROPERTIES_END --- diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjClockSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjClockSensor.h index b399abc..2c610c6 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjClockSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjClockSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjClockSensor - * @brief Specific Clock Sensor component. + * @brief Autogenerated component representing the MuJoCo 'clock' element. + * + * Subclass of UMjSensor. Sets Type = Clock in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjClockSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjClockSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjContactSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjContactSensor.h index fed4c67..68aa046 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjContactSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjContactSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjContactSensor - * @brief Specific Contact Sensor component. + * @brief Autogenerated component representing the MuJoCo 'contact' element. + * + * Subclass of UMjSensor. Sets Type = Contact in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjContactSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjContactSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjEKineticSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjEKineticSensor.h index 00b4fdd..9854712 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjEKineticSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjEKineticSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjEKineticSensor - * @brief Specific EKinetic Sensor component. + * @brief Autogenerated component representing the MuJoCo 'e_kinetic' element. + * + * Subclass of UMjSensor. Sets Type = EKinetic in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjEKineticSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjEKineticSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjEPotentialSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjEPotentialSensor.h index 7376469..7f244d1 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjEPotentialSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjEPotentialSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjEPotentialSensor - * @brief Specific EPotential Sensor component. + * @brief Autogenerated component representing the MuJoCo 'e_potential' element. + * + * Subclass of UMjSensor. Sets Type = EPotential in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjEPotentialSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjEPotentialSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjForceSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjForceSensor.h index 00d3807..1b106b6 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjForceSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjForceSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjForceSensor - * @brief Specific Force Sensor component. + * @brief Autogenerated component representing the MuJoCo 'force' element. + * + * Subclass of UMjSensor. Sets Type = Force in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjForceSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjForceSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameAngAccSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameAngAccSensor.h index 4ddbe0f..4f4f01f 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameAngAccSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameAngAccSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjFrameAngAccSensor - * @brief Specific FrameAngAcc Sensor component. + * @brief Autogenerated component representing the MuJoCo 'frameangacc' element. + * + * Subclass of UMjSensor. Sets Type = FrameAngAcc in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjFrameAngAccSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjFrameAngAccSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameAngVelSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameAngVelSensor.h index 2047e11..d58259a 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameAngVelSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameAngVelSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjFrameAngVelSensor - * @brief Specific FrameAngVel Sensor component. + * @brief Autogenerated component representing the MuJoCo 'frameangvel' element. + * + * Subclass of UMjSensor. Sets Type = FrameAngVel in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjFrameAngVelSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjFrameAngVelSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameLinAccSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameLinAccSensor.h index 1d969dc..cbf6e4a 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameLinAccSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameLinAccSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjFrameLinAccSensor - * @brief Specific FrameLinAcc Sensor component. + * @brief Autogenerated component representing the MuJoCo 'framelinacc' element. + * + * Subclass of UMjSensor. Sets Type = FrameLinAcc in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjFrameLinAccSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjFrameLinAccSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameLinVelSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameLinVelSensor.h index c8d71ad..1bd0994 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameLinVelSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameLinVelSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjFrameLinVelSensor - * @brief Specific FrameLinVel Sensor component. + * @brief Autogenerated component representing the MuJoCo 'framelinvel' element. + * + * Subclass of UMjSensor. Sets Type = FrameLinVel in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjFrameLinVelSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjFrameLinVelSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjFramePosSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjFramePosSensor.h index 78a21cf..27d8640 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjFramePosSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjFramePosSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjFramePosSensor - * @brief Specific FramePos Sensor component. + * @brief Autogenerated component representing the MuJoCo 'framepos' element. + * + * Subclass of UMjSensor. Sets Type = FramePos in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjFramePosSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjFramePosSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameQuatSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameQuatSensor.h index f80797f..f6d43f6 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameQuatSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameQuatSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjFrameQuatSensor - * @brief Specific FrameQuat Sensor component. + * @brief Autogenerated component representing the MuJoCo 'framequat' element. + * + * Subclass of UMjSensor. Sets Type = FrameQuat in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjFrameQuatSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjFrameQuatSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameXAxisSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameXAxisSensor.h index 0891c29..27caf41 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameXAxisSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameXAxisSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjFrameXAxisSensor - * @brief Specific FrameXAxis Sensor component. + * @brief Autogenerated component representing the MuJoCo 'framexaxis' element. + * + * Subclass of UMjSensor. Sets Type = FrameXAxis in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjFrameXAxisSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjFrameXAxisSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameYAxisSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameYAxisSensor.h index a58d758..1fa5ee4 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameYAxisSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameYAxisSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjFrameYAxisSensor - * @brief Specific FrameYAxis Sensor component. + * @brief Autogenerated component representing the MuJoCo 'frameyaxis' element. + * + * Subclass of UMjSensor. Sets Type = FrameYAxis in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjFrameYAxisSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjFrameYAxisSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameZAxisSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameZAxisSensor.h index 8508c3c..14f797b 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameZAxisSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjFrameZAxisSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjFrameZAxisSensor - * @brief Specific FrameZAxis Sensor component. + * @brief Autogenerated component representing the MuJoCo 'framezaxis' element. + * + * Subclass of UMjSensor. Sets Type = FrameZAxis in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjFrameZAxisSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjFrameZAxisSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjGeomDistSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjGeomDistSensor.h index 58c4457..fb8064d 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjGeomDistSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjGeomDistSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjGeomDistSensor - * @brief Specific GeomDist Sensor component. + * @brief Autogenerated component representing the MuJoCo 'distance' element. + * + * Subclass of UMjSensor. Sets Type = GeomDist in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjGeomDistSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjGeomDistSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjGeomFromToSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjGeomFromToSensor.h index 04046f0..951bfa6 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjGeomFromToSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjGeomFromToSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjGeomFromToSensor - * @brief Specific GeomFromTo Sensor component. + * @brief Autogenerated component representing the MuJoCo 'fromto' element. + * + * Subclass of UMjSensor. Sets Type = GeomFromTo in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjGeomFromToSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjGeomFromToSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjGeomNormalSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjGeomNormalSensor.h index 3c9f132..f55857f 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjGeomNormalSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjGeomNormalSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjGeomNormalSensor - * @brief Specific GeomNormal Sensor component. + * @brief Autogenerated component representing the MuJoCo 'normal' element. + * + * Subclass of UMjSensor. Sets Type = GeomNormal in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjGeomNormalSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjGeomNormalSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjGyro.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjGyro.h index 5481a95..43ccb21 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjGyro.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjGyro.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjGyro - * @brief Specific Gyro Sensor component. + * @brief Autogenerated component representing the MuJoCo 'gyro' element. + * + * Subclass of UMjSensor. Sets Type = Gyro in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjGyro : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjGyro(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjInsideSiteSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjInsideSiteSensor.h index a4a7c0e..ad8b774 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjInsideSiteSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjInsideSiteSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjInsideSiteSensor - * @brief Specific InsideSite Sensor component. + * @brief Autogenerated component representing the MuJoCo 'insidesite' element. + * + * Subclass of UMjSensor. Sets Type = InsideSite in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjInsideSiteSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjInsideSiteSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjJointActFrcSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjJointActFrcSensor.h index bc6cfcd..9e3cab8 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjJointActFrcSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjJointActFrcSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjJointActFrcSensor - * @brief Specific JointActFrc Sensor component. + * @brief Autogenerated component representing the MuJoCo 'jointactuatorfrc' element. + * + * Subclass of UMjSensor. Sets Type = JointActFrc in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjJointActFrcSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjJointActFrcSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjJointLimitFrcSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjJointLimitFrcSensor.h index 885e010..d885cb4 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjJointLimitFrcSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjJointLimitFrcSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjJointLimitFrcSensor - * @brief Specific JointLimitFrc Sensor component. + * @brief Autogenerated component representing the MuJoCo 'jointlimitfrc' element. + * + * Subclass of UMjSensor. Sets Type = JointLimitFrc in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjJointLimitFrcSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjJointLimitFrcSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjJointLimitPosSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjJointLimitPosSensor.h index 873bf63..5bfe8f5 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjJointLimitPosSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjJointLimitPosSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjJointLimitPosSensor - * @brief Specific JointLimitPos Sensor component. + * @brief Autogenerated component representing the MuJoCo 'jointlimitpos' element. + * + * Subclass of UMjSensor. Sets Type = JointLimitPos in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjJointLimitPosSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjJointLimitPosSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjJointLimitVelSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjJointLimitVelSensor.h index 3dafbbc..5091c92 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjJointLimitVelSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjJointLimitVelSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjJointLimitVelSensor - * @brief Specific JointLimitVel Sensor component. + * @brief Autogenerated component representing the MuJoCo 'jointlimitvel' element. + * + * Subclass of UMjSensor. Sets Type = JointLimitVel in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjJointLimitVelSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjJointLimitVelSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjJointVelSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjJointVelSensor.h index 28eedb4..b1f5df1 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjJointVelSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjJointVelSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjJointVelSensor - * @brief Specific JointVel Sensor component. + * @brief Autogenerated component representing the MuJoCo 'jointvel' element. + * + * Subclass of UMjSensor. Sets Type = JointVel in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjJointVelSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjJointVelSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjMagnetometer.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjMagnetometer.h index a571e9b..0af7e9a 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjMagnetometer.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjMagnetometer.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjMagnetometer - * @brief Specific Magnetometer Sensor component. + * @brief Autogenerated component representing the MuJoCo 'magnetometer' element. + * + * Subclass of UMjSensor. Sets Type = Magnetometer in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjMagnetometer : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjMagnetometer(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjPluginSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjPluginSensor.h index 7f06590..7509f0e 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjPluginSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjPluginSensor.h @@ -44,7 +44,7 @@ class URLAB_API UMjPluginSensor : public UMjSensor UMjPluginSensor(); // --- CODEGEN_PROPERTIES_START --- - + // (no type-specific schema attrs) // --- CODEGEN_PROPERTIES_END --- virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjRangeFinderSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjRangeFinderSensor.h index 736fe41..14b333b 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjRangeFinderSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjRangeFinderSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjRangeFinderSensor - * @brief Specific RangeFinder Sensor component. + * @brief Autogenerated component representing the MuJoCo 'rangefinder' element. + * + * Subclass of UMjSensor. Sets Type = RangeFinder in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjRangeFinderSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjRangeFinderSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjSensor.h index f6e1798..bff3bb8 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjSensor.h @@ -159,40 +159,40 @@ class URLAB_API UMjSensor : public UMjComponent public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjSensor", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Sensor", meta=(InlineEditConditionToggle)) bool bOverride_nsample = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjSensor", meta=(EditCondition="bOverride_nsample")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor", meta=(EditCondition="bOverride_nsample")) int32 nsample = 0; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjSensor", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Sensor", meta=(InlineEditConditionToggle)) bool bOverride_interp = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjSensor", meta=(EditCondition="bOverride_interp")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor", meta=(EditCondition="bOverride_interp")) int32 interp = 0; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjSensor", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Sensor", meta=(InlineEditConditionToggle)) bool bOverride_delay = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjSensor", meta=(EditCondition="bOverride_delay")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor", meta=(EditCondition="bOverride_delay")) float delay = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjSensor", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Sensor", meta=(InlineEditConditionToggle)) bool bOverride_interval = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjSensor", meta=(EditCondition="bOverride_interval")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor", meta=(EditCondition="bOverride_interval")) TArray interval = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjSensor", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Sensor", meta=(InlineEditConditionToggle)) bool bOverride_cutoff = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjSensor", meta=(EditCondition="bOverride_cutoff")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor", meta=(EditCondition="bOverride_cutoff")) float cutoff = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjSensor", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Sensor", meta=(InlineEditConditionToggle)) bool bOverride_noise = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjSensor", meta=(EditCondition="bOverride_noise")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor", meta=(EditCondition="bOverride_noise")) float noise = 0.0f; // --- CODEGEN_PROPERTIES_END --- @@ -226,8 +226,10 @@ class URLAB_API UMjSensor : public UMjComponent UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor", meta=(GetOptions="GetDefaultClassOptions")) FString MjClassName; - /** @brief Reference to a UMjDefault component for default class inheritance. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor") + /** @brief Reference to a UMjDefault component for default class inheritance. Hidden from the + * Details panel — synced from MjClassName via the editor dropdown. */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor", + meta=(EditCondition="false", EditConditionHides)) UMjDefault* DefaultClass = nullptr; virtual FString GetMjClassName() const override diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjSubtreeAngMomSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjSubtreeAngMomSensor.h index 10ad220..c76de53 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjSubtreeAngMomSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjSubtreeAngMomSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjSubtreeAngMomSensor - * @brief Specific SubtreeAngMom Sensor component. + * @brief Autogenerated component representing the MuJoCo 'subtreeangmom' element. + * + * Subclass of UMjSensor. Sets Type = SubtreeAngMom in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjSubtreeAngMomSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjSubtreeAngMomSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjSubtreeComSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjSubtreeComSensor.h index 0416196..cdc8ff1 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjSubtreeComSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjSubtreeComSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjSubtreeComSensor - * @brief Specific SubtreeCom Sensor component. + * @brief Autogenerated component representing the MuJoCo 'subtreecom' element. + * + * Subclass of UMjSensor. Sets Type = SubtreeCom in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjSubtreeComSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjSubtreeComSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjSubtreeLinVelSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjSubtreeLinVelSensor.h index 8fff017..d777b61 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjSubtreeLinVelSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjSubtreeLinVelSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjSubtreeLinVelSensor - * @brief Specific SubtreeLinVel Sensor component. + * @brief Autogenerated component representing the MuJoCo 'subtreelinvel' element. + * + * Subclass of UMjSensor. Sets Type = SubtreeLinVel in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjSubtreeLinVelSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjSubtreeLinVelSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonActFrcSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonActFrcSensor.h index 64672ab..be2ea3d 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonActFrcSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonActFrcSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjTendonActFrcSensor - * @brief Specific TendonActFrc Sensor component. + * @brief Autogenerated component representing the MuJoCo 'tendonactuatorfrc' element. + * + * Subclass of UMjSensor. Sets Type = TendonActFrc in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjTendonActFrcSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjTendonActFrcSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonLimitFrcSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonLimitFrcSensor.h index 1e39b2d..7b701ca 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonLimitFrcSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonLimitFrcSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjTendonLimitFrcSensor - * @brief Specific TendonLimitFrc Sensor component. + * @brief Autogenerated component representing the MuJoCo 'tendonlimitfrc' element. + * + * Subclass of UMjSensor. Sets Type = TendonLimitFrc in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjTendonLimitFrcSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjTendonLimitFrcSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonLimitPosSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonLimitPosSensor.h index e9d8ed1..31bebc3 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonLimitPosSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonLimitPosSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjTendonLimitPosSensor - * @brief Specific TendonLimitPos Sensor component. + * @brief Autogenerated component representing the MuJoCo 'tendonlimitpos' element. + * + * Subclass of UMjSensor. Sets Type = TendonLimitPos in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjTendonLimitPosSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjTendonLimitPosSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonLimitVelSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonLimitVelSensor.h index 735495d..6858e73 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonLimitVelSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonLimitVelSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjTendonLimitVelSensor - * @brief Specific TendonLimitVel Sensor component. + * @brief Autogenerated component representing the MuJoCo 'tendonlimitvel' element. + * + * Subclass of UMjSensor. Sets Type = TendonLimitVel in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjTendonLimitVelSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjTendonLimitVelSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonPosSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonPosSensor.h index b26c9c0..9b1bf45 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonPosSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonPosSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjTendonPosSensor - * @brief Specific TendonPos Sensor component. + * @brief Autogenerated component representing the MuJoCo 'tendonpos' element. + * + * Subclass of UMjSensor. Sets Type = TendonPos in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjTendonPosSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjTendonPosSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonVelSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonVelSensor.h index f115862..9587c1c 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonVelSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjTendonVelSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjTendonVelSensor - * @brief Specific TendonVel Sensor component. + * @brief Autogenerated component representing the MuJoCo 'tendonvel' element. + * + * Subclass of UMjSensor. Sets Type = TendonVel in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjTendonVelSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjTendonVelSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjTorqueSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjTorqueSensor.h index 5aa7034..24d3a50 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjTorqueSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjTorqueSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjTorqueSensor - * @brief Specific Torque Sensor component. + * @brief Autogenerated component representing the MuJoCo 'torque' element. + * + * Subclass of UMjSensor. Sets Type = Torque in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjTorqueSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjTorqueSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjTouchSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjTouchSensor.h index dd9a3e8..0ec70cc 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjTouchSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjTouchSensor.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjTouchSensor - * @brief Specific Touch Sensor component. + * @brief Autogenerated component representing the MuJoCo 'touch' element. + * + * Subclass of UMjSensor. Sets Type = Touch in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjTouchSensor : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjTouchSensor(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjUserSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjUserSensor.h index 9984711..0c1a06c 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjUserSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjUserSensor.h @@ -44,7 +44,7 @@ class URLAB_API UMjUserSensor : public UMjSensor UMjUserSensor(); // --- CODEGEN_PROPERTIES_START --- - + // (no type-specific schema attrs) // --- CODEGEN_PROPERTIES_END --- virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjVelocimeter.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjVelocimeter.h index 0db16dc..2c15c44 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjVelocimeter.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjVelocimeter.h @@ -13,12 +13,15 @@ // limitations under the License. // // --- LEGAL DISCLAIMER --- -// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, -// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are +// UnrealRoboticsLab is an independent software plugin. It is NOT affiliated with, +// endorsed by, or sponsored by Epic Games, Inc. "Unreal" and "Unreal Engine" are // trademarks or registered trademarks of Epic Games, Inc. in the US and elsewhere. // -// This plugin incorporates third-party software: MuJoCo (Apache 2.0), +// This plugin incorporates third-party software: MuJoCo (Apache 2.0), // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. +// +// AUTOGENERATED by Scripts/codegen/generate_ue_components.py +// Do not edit by hand. Re-run the generator to regenerate. #pragma once @@ -28,20 +31,22 @@ /** * @class UMjVelocimeter - * @brief Specific Velocimeter Sensor component. + * @brief Autogenerated component representing the MuJoCo 'velocimeter' element. + * + * Subclass of UMjSensor. Sets Type = Velocimeter in the constructor. */ -UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent)) class URLAB_API UMjVelocimeter : public UMjSensor { GENERATED_BODY() -public: - // --- CODEGEN_PROPERTIES_START --- - - // --- CODEGEN_PROPERTIES_END --- +public: UMjVelocimeter(); - virtual void ImportFromXml(const class FXmlNode* Node, const struct FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; + // --- CODEGEN_PROPERTIES_START --- + // (no type-specific schema attrs) + // --- CODEGEN_PROPERTIES_END --- + virtual void ImportFromXml(const class FXmlNode* Node, const FMjCompilerSettings& CompilerSettings = FMjCompilerSettings{}) override; virtual void ExportTo(mjsSensor* Element, mjsDefault* Default = nullptr) override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Tendons/MjTendon.h b/Source/URLab/Public/MuJoCo/Components/Tendons/MjTendon.h index 1b7a4be..6fd5efc 100644 --- a/Source/URLab/Public/MuJoCo/Components/Tendons/MjTendon.h +++ b/Source/URLab/Public/MuJoCo/Components/Tendons/MjTendon.h @@ -112,112 +112,112 @@ class URLAB_API UMjTendon : public UMjComponent public: // --- CODEGEN_PROPERTIES_START --- - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjTendon", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon", meta=(InlineEditConditionToggle)) bool bOverride_group = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjTendon", meta=(EditCondition="bOverride_group")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", meta=(EditCondition="bOverride_group")) int32 group = 0; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjTendon", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon", meta=(InlineEditConditionToggle)) bool bOverride_limited = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjTendon", meta=(EditCondition="bOverride_limited")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", meta=(EditCondition="bOverride_limited")) bool limited = false; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjTendon", meta=(InlineEditConditionToggle)) - bool bOverride_actuatorfrclimited = false; + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon", meta=(InlineEditConditionToggle)) + bool bOverride_ActFrcLimited = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjTendon", meta=(EditCondition="bOverride_actuatorfrclimited")) - bool actuatorfrclimited = false; + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", meta=(EditCondition="bOverride_ActFrcLimited")) + bool ActFrcLimited = false; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjTendon", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon", meta=(InlineEditConditionToggle)) bool bOverride_range = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjTendon", meta=(EditCondition="bOverride_range")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", meta=(EditCondition="bOverride_range")) TArray range = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjTendon", meta=(InlineEditConditionToggle)) - bool bOverride_actuatorfrcrange = false; + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon", meta=(InlineEditConditionToggle)) + bool bOverride_ActFrcRange = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjTendon", meta=(EditCondition="bOverride_actuatorfrcrange")) - TArray actuatorfrcrange = {}; + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", meta=(EditCondition="bOverride_ActFrcRange")) + TArray ActFrcRange = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjTendon", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon", meta=(InlineEditConditionToggle)) bool bOverride_solreflimit = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjTendon", meta=(EditCondition="bOverride_solreflimit")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", meta=(EditCondition="bOverride_solreflimit")) TArray solreflimit = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjTendon", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon", meta=(InlineEditConditionToggle)) bool bOverride_solimplimit = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjTendon", meta=(EditCondition="bOverride_solimplimit")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", meta=(EditCondition="bOverride_solimplimit")) TArray solimplimit = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjTendon", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon", meta=(InlineEditConditionToggle)) bool bOverride_solreffriction = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjTendon", meta=(EditCondition="bOverride_solreffriction")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", meta=(EditCondition="bOverride_solreffriction")) TArray solreffriction = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjTendon", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon", meta=(InlineEditConditionToggle)) bool bOverride_solimpfriction = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjTendon", meta=(EditCondition="bOverride_solimpfriction")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", meta=(EditCondition="bOverride_solimpfriction")) TArray solimpfriction = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjTendon", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon", meta=(InlineEditConditionToggle)) bool bOverride_frictionloss = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjTendon", meta=(EditCondition="bOverride_frictionloss")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", meta=(EditCondition="bOverride_frictionloss")) float frictionloss = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjTendon", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon", meta=(InlineEditConditionToggle)) bool bOverride_springlength = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjTendon", meta=(EditCondition="bOverride_springlength")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", meta=(EditCondition="bOverride_springlength")) TArray springlength = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjTendon", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon", meta=(InlineEditConditionToggle)) bool bOverride_width = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjTendon", meta=(EditCondition="bOverride_width")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", meta=(EditCondition="bOverride_width")) float width = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjTendon", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon", meta=(InlineEditConditionToggle)) bool bOverride_material = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjTendon", meta=(EditCondition="bOverride_material")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", meta=(EditCondition="bOverride_material")) FString material = TEXT(""); - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjTendon", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon", meta=(InlineEditConditionToggle)) bool bOverride_margin = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjTendon", meta=(EditCondition="bOverride_margin")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", meta=(EditCondition="bOverride_margin")) float margin = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjTendon", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon", meta=(InlineEditConditionToggle)) bool bOverride_stiffness = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjTendon", meta=(EditCondition="bOverride_stiffness")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", meta=(EditCondition="bOverride_stiffness")) TArray stiffness = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjTendon", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon", meta=(InlineEditConditionToggle)) bool bOverride_damping = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjTendon", meta=(EditCondition="bOverride_damping")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", meta=(EditCondition="bOverride_damping")) TArray damping = {}; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjTendon", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon", meta=(InlineEditConditionToggle)) bool bOverride_armature = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjTendon", meta=(EditCondition="bOverride_armature")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", meta=(EditCondition="bOverride_armature")) float armature = 0.0f; - UPROPERTY(EditAnywhere, Category = "MuJoCo|MjTendon", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon", meta=(InlineEditConditionToggle)) bool bOverride_rgba = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|MjTendon", meta=(EditCondition="bOverride_rgba")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", meta=(EditCondition="bOverride_rgba")) FLinearColor rgba = FLinearColor::White; // --- CODEGEN_PROPERTIES_END --- @@ -290,8 +290,10 @@ class URLAB_API UMjTendon : public UMjComponent UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", meta=(GetOptions="GetDefaultClassOptions")) FString MjClassName; - /** @brief Reference to a UMjDefault component for default class inheritance. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon") + /** @brief Reference to a UMjDefault component for default class inheritance. Hidden from the + * Details panel — synced from MjClassName via the editor dropdown. */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", + meta=(EditCondition="false", EditConditionHides)) UMjDefault* DefaultClass = nullptr; virtual FString GetMjClassName() const override @@ -328,23 +330,10 @@ class URLAB_API UMjTendon : public UMjComponent - // --- Actuator Limits --- - - /** @brief Override toggle for bActFrcLimited. */ - UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon|Limits", meta=(InlineEditConditionToggle)) - bool bOverride_ActFrcLimited = false; - - /** @brief Whether the tendon has actuator force limits. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Limits", meta=(EditCondition="bOverride_ActFrcLimited")) - bool bActFrcLimited = false; - - /** @brief Override toggle for ActFrcRange. */ - UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon|Limits", meta=(InlineEditConditionToggle)) - bool bOverride_ActFrcRange = false; - - /** @brief Tendon actuator force limits [min, max]. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Limits", meta=(EditCondition="bOverride_ActFrcRange")) - TArray ActFrcRange = {0.0f, 0.0f}; + // ActFrcLimited / ActFrcRange UPROPERTYs are codegen-emitted in the + // CODEGEN_PROPERTIES block above (driven by codegen_rules.json's + // property_renames: actuatorfrclimited -> ActFrcLimited / actuatorfrcrange + // -> ActFrcRange). // --- Solver Parameters --- diff --git a/Source/URLab/Public/MuJoCo/Core/MjArticulation.h b/Source/URLab/Public/MuJoCo/Core/MjArticulation.h index 42a5e3d..cddf57b 100644 --- a/Source/URLab/Public/MuJoCo/Core/MjArticulation.h +++ b/Source/URLab/Public/MuJoCo/Core/MjArticulation.h @@ -25,7 +25,7 @@ #include "CoreMinimal.h" #include #include "MuJoCo/Core/Spec/MjSpecWrapper.h" -#include "MuJoCo/Core/MjSimOptions.h" +#include "MuJoCo/Generated/MjOptionGenerated.h" #include "GameFramework/Pawn.h" #include "MuJoCo/Components/Bodies/MjBody.h" #include "MuJoCo/Components/Joints/MjJoint.h" @@ -207,8 +207,8 @@ class URLAB_API AMjArticulation : public APawn UFUNCTION(BlueprintCallable, Category = "MuJoCo|Discovery") TArray GetRuntimeComponentsOfClass(TSubclassOf ComponentClass) const; - /** - * @brief Templated helper to find all components of type T belonging to this articulation + /** + * @brief Templated helper to find all components of type T belonging to this articulation * that are NOT marked as 'bIsDefault'. This is the standard way to find simulation-active components. */ template @@ -231,6 +231,51 @@ class URLAB_API AMjArticulation : public APawn } } + // ============================================================================ + // Templated map-lookup helpers — collapse the 9 hand-rolled `GetNames` / + // `Gets` / `GetByMjId` methods into 1-line BP wrappers per category. + // Equality and Keyframe getters do NOT use these (name-keyed maps + dedup + + // different name-source) — they stay hand-rolled. See deviation D-future. + // ============================================================================ + + /** Return all values from an id-keyed component map. */ + template + TArray GetComponentsFromMap(const TMap& IdMap) const + { + TArray Out; + IdMap.GenerateValueArray(Out); + return Out; + } + + /** Return MuJoCo names of all components in an id-keyed map (skipping null values). */ + template + TArray GetComponentNamesFromMap(const TMap& IdMap) const + { + TArray Names; + Names.Reserve(IdMap.Num()); + for (const auto& Pair : IdMap) + { + if (Pair.Value) Names.Add(Pair.Value->GetMjName()); + } + return Names; + } + + /** Lookup a component by its compiled mjId in an id-keyed map. Returns nullptr if absent. */ + template + T* GetComponentByIdInMap(int Id, const TMap& IdMap) const + { + if (T* const* Found = IdMap.Find(Id)) return *Found; + return nullptr; + } + + /** Lookup a component by name in a name-keyed map. Returns nullptr if absent. */ + template + T* GetComponentByNameInMap(const FString& Name, const TMap& NameMap) const + { + if (T* const* Found = NameMap.Find(Name)) return *Found; + return nullptr; + } + // ========================================================================= // Blueprint Runtime API — Component Accessors (delegate to the component) // ========================================================================= @@ -370,6 +415,9 @@ class URLAB_API AMjArticulation : public APawn UPROPERTY(BlueprintReadOnly, Category = "MuJoCo|Status") bool bAttachFailed = false; + /** @brief Diagnostic-only accessor for the articulation prefix used by mjs_attach. */ + FString GetPrefixForDiagnostics() const { return m_prefix; } + protected: mjVFS* m_vfs = nullptr; mjSpec* m_spec = nullptr; @@ -417,7 +465,7 @@ class URLAB_API AMjArticulation : public APawn * Parsed from the MJCF