From aa88654e18a6eb9fbaf46e04c8f79ee838bdd290 Mon Sep 17 00:00:00 2001 From: Jonathan Embley-Riches Date: Sun, 12 Apr 2026 18:05:48 +0100 Subject: [PATCH] Articulation Builder QoL & UX improvements (#10) Replace custom detail panel dropdowns with native meta=(GetOptions) on UPROPERTY declarations. This fixes duplicate category sections caused by EditCategory with pipe-separated subcategories and removes the need for FMjComponentRefHelper and the separate MjGeomDetailCustomization. Detail customizations now only hide internal properties (DefaultClass pointers, synced ClassName fields). Geom keeps CoACD decomposition buttons via EditCategory on a dedicated Decomposition subcategory. --- Resources/Icons/MjActuator.png | Bin 0 -> 158 bytes Resources/Icons/MjBallJoint.png | Bin 0 -> 162 bytes Resources/Icons/MjBody.png | Bin 0 -> 163 bytes Resources/Icons/MjBox.png | Bin 0 -> 116 bytes Resources/Icons/MjCamera.png | Bin 0 -> 130 bytes Resources/Icons/MjContactExclude.png | Bin 0 -> 170 bytes Resources/Icons/MjContactPair.png | Bin 0 -> 137 bytes Resources/Icons/MjCylinder.png | Bin 0 -> 145 bytes Resources/Icons/MjDefault.png | Bin 0 -> 128 bytes Resources/Icons/MjEquality.png | Bin 0 -> 98 bytes Resources/Icons/MjFreeJoint.png | Bin 0 -> 141 bytes Resources/Icons/MjGeom.png | Bin 0 -> 117 bytes Resources/Icons/MjHingeJoint.png | Bin 0 -> 528 bytes Resources/Icons/MjInertial.png | Bin 0 -> 130 bytes Resources/Icons/MjJoint.png | Bin 0 -> 129 bytes Resources/Icons/MjKeyframe.png | Bin 0 -> 143 bytes Resources/Icons/MjMeshGeom.png | Bin 0 -> 162 bytes Resources/Icons/MjSensor.png | Bin 0 -> 133 bytes Resources/Icons/MjSite.png | Bin 0 -> 132 bytes Resources/Icons/MjSlideJoint.png | Bin 0 -> 112 bytes Resources/Icons/MjSphere.png | Bin 0 -> 142 bytes Resources/Icons/MjTendon.png | Bin 0 -> 142 bytes Resources/Icons/MjWorldBody.png | Bin 0 -> 144 bytes .../Components/Actuators/MjActuator.cpp | 47 ++ .../MuJoCo/Components/Bodies/MjBody.cpp | 7 + .../Components/Constraints/MjEquality.cpp | 25 + .../MuJoCo/Components/Defaults/MjDefault.cpp | 16 + .../MuJoCo/Components/Geometry/MjGeom.cpp | 32 ++ .../Components/Geometry/MjMeshGeom.cpp} | 19 +- .../MuJoCo/Components/Geometry/MjSite.cpp | 7 + .../Components/Geometry/Primitives/MjBox.cpp | 15 + .../Geometry/Primitives/MjCylinder.cpp | 11 + .../Geometry/Primitives/MjSphere.cpp | 11 + .../MuJoCo/Components/Joints/MjJoint.cpp | 7 + .../Private/MuJoCo/Components/MjComponent.cpp | 51 ++ .../Components/Physics/MjContactExclude.cpp | 9 + .../Components/Physics/MjContactPair.cpp | 9 + .../MuJoCo/Components/Sensors/MjSensor.cpp | 42 ++ .../MuJoCo/Components/Tendons/MjTendon.cpp | 7 + .../Private/MuJoCo/Core/MjArticulation.cpp | 109 +++- .../MuJoCo/Components/Actuators/MjActuator.h | 92 ++-- .../Components/Actuators/MjAdhesionActuator.h | 4 +- .../Components/Actuators/MjCylinderActuator.h | 16 +- .../Components/Actuators/MjDamperActuator.h | 4 +- .../Actuators/MjIntVelocityActuator.h | 20 +- .../Components/Actuators/MjMuscleActuator.h | 40 +- .../Components/Actuators/MjPositionActuator.h | 20 +- .../Components/Actuators/MjVelocityActuator.h | 4 +- .../Public/MuJoCo/Components/Bodies/MjBody.h | 25 +- .../Components/Constraints/MjEquality.h | 37 +- .../MuJoCo/Components/Defaults/MjDefault.h | 8 +- .../MuJoCo/Components/Geometry/MjGeom.h | 38 +- .../MuJoCo/Components/Geometry/MjMeshGeom.h | 40 ++ .../MuJoCo/Components/Geometry/MjSite.h | 20 +- .../Components/Geometry/Primitives/MjBox.h | 1 + .../Geometry/Primitives/MjCylinder.h | 1 + .../Components/Geometry/Primitives/MjSphere.h | 1 + .../Public/MuJoCo/Components/Joints/MjJoint.h | 83 +-- .../MuJoCo/Components/Keyframes/MjKeyframe.h | 26 +- .../Public/MuJoCo/Components/MjComponent.h | 15 +- .../Components/Physics/MjContactExclude.h | 11 +- .../MuJoCo/Components/Physics/MjContactPair.h | 23 +- .../MuJoCo/Components/Sensors/MjSensor.h | 50 +- .../MuJoCo/Components/Tendons/MjTendon.h | 100 ++-- .../MjComponentDetailCustomizations.cpp | 242 +++++++++ Source/URLabEditor/Private/MjEditorStyle.cpp | 115 ++++ .../Private/MjGeomDetailCustomization.cpp | 83 --- .../URLabEditor/Private/MujocoXmlParser.cpp | 139 ++++- .../Private/SMjArticulationOutliner.cpp | 501 ++++++++++++++++++ .../Private/Tests/MjImporterTest.cpp | 35 +- Source/URLabEditor/Private/URLabEditor.cpp | 246 ++++++++- .../Public/MjComponentDetailCustomizations.h | 113 ++++ Source/URLabEditor/Public/MjEditorStyle.h | 43 ++ .../Public/SMjArticulationOutliner.h | 114 ++++ Source/URLabEditor/Public/URLabEditor.h | 5 + Source/URLabEditor/URLabEditor.Build.cs | 3 +- docs/architecture.md | 18 +- docs/getting_started.md | 1 + docs/guides/articulation_builder.md | 182 +++++++ 79 files changed, 2549 insertions(+), 394 deletions(-) create mode 100644 Resources/Icons/MjActuator.png create mode 100644 Resources/Icons/MjBallJoint.png create mode 100644 Resources/Icons/MjBody.png create mode 100644 Resources/Icons/MjBox.png create mode 100644 Resources/Icons/MjCamera.png create mode 100644 Resources/Icons/MjContactExclude.png create mode 100644 Resources/Icons/MjContactPair.png create mode 100644 Resources/Icons/MjCylinder.png create mode 100644 Resources/Icons/MjDefault.png create mode 100644 Resources/Icons/MjEquality.png create mode 100644 Resources/Icons/MjFreeJoint.png create mode 100644 Resources/Icons/MjGeom.png create mode 100644 Resources/Icons/MjHingeJoint.png create mode 100644 Resources/Icons/MjInertial.png create mode 100644 Resources/Icons/MjJoint.png create mode 100644 Resources/Icons/MjKeyframe.png create mode 100644 Resources/Icons/MjMeshGeom.png create mode 100644 Resources/Icons/MjSensor.png create mode 100644 Resources/Icons/MjSite.png create mode 100644 Resources/Icons/MjSlideJoint.png create mode 100644 Resources/Icons/MjSphere.png create mode 100644 Resources/Icons/MjTendon.png create mode 100644 Resources/Icons/MjWorldBody.png rename Source/{URLabEditor/Public/MjGeomDetailCustomization.h => URLab/Private/MuJoCo/Components/Geometry/MjMeshGeom.cpp} (75%) create mode 100644 Source/URLab/Public/MuJoCo/Components/Geometry/MjMeshGeom.h create mode 100644 Source/URLabEditor/Private/MjComponentDetailCustomizations.cpp create mode 100644 Source/URLabEditor/Private/MjEditorStyle.cpp delete mode 100644 Source/URLabEditor/Private/MjGeomDetailCustomization.cpp create mode 100644 Source/URLabEditor/Private/SMjArticulationOutliner.cpp create mode 100644 Source/URLabEditor/Public/MjComponentDetailCustomizations.h create mode 100644 Source/URLabEditor/Public/MjEditorStyle.h create mode 100644 Source/URLabEditor/Public/SMjArticulationOutliner.h create mode 100644 docs/guides/articulation_builder.md diff --git a/Resources/Icons/MjActuator.png b/Resources/Icons/MjActuator.png new file mode 100644 index 0000000000000000000000000000000000000000..ba0300d053f1274c0c440e79a271d45d145ea88b GIT binary patch literal 158 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4#%`sh%#5Ar*6yQw}ixTh8*QeWT>_ zoP;Aw`#Kw)4!DRj|5L7P*I@pae6iuY08i@D>-|@EGaqI zR_w#C$pZ7O8c#GF7RY&YW0HyRMy|rA?2DKtE}Pkz#K0i2#M><1{KN&Ig$$mqelF{r G5}E)NNjWY6 literal 0 HcmV?d00001 diff --git a/Resources/Icons/MjBallJoint.png b/Resources/Icons/MjBallJoint.png new file mode 100644 index 0000000000000000000000000000000000000000..758bd828151a9e943a05182c522d5b65b376919f GIT binary patch literal 162 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4#%`nVv3=Ar*6y6C^SYba*Q*efhsW z<=-4Dw>4RkoS81{FW3wpUg8PnSTxaeVe|o)9^D^%4z%PM>9w9HIX*c#1_Iu{7El)=;0 K&t;ucLK6UR%s4Ut literal 0 HcmV?d00001 diff --git a/Resources/Icons/MjBody.png b/Resources/Icons/MjBody.png new file mode 100644 index 0000000000000000000000000000000000000000..66e51ce8f8c0bc343488f42fdf5187de96344755 GIT binary patch literal 163 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4#%`S)MMAAr*6y6BejdY&-D6o@4T& zcFss+GqXT8o5PD5Bb;Y+Y~@_f7{vKpVxyzJij@qwzD8l{ZfdXozoOQstIzG7My$SlEjk3p=2F(_E&sGdXx0|Sc@*XotqGp7QL OVeoYIb6Mw<&;$Uh>>zLe literal 0 HcmV?d00001 diff --git a/Resources/Icons/MjCamera.png b/Resources/Icons/MjCamera.png new file mode 100644 index 0000000000000000000000000000000000000000..3b7b55dc3fde8b82af85572d6eb1dad66c8a615c GIT binary patch literal 130 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4#%`o}Mm_Ar*6y6C^e%EO>OJUf`@t zXPQ8Qqqu^o!Nk>qM_COvEIiyak&*krb0;-6F2>6j%o|u|I{TFv1-@e1#BgHi6cxK2 diXnx342u}VSl-G{=>{6g;OXk;vd$@?2>}15CrkhU literal 0 HcmV?d00001 diff --git a/Resources/Icons/MjContactExclude.png b/Resources/Icons/MjContactExclude.png new file mode 100644 index 0000000000000000000000000000000000000000..cd86ed447e7c5d9d4154a56136d76c6b2a22c005 GIT binary patch literal 170 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4#%`g`O^sAr*6uPCUqWK!L+~>iS0y zo>zZZALDZ@aoy6}df7=P4)Z&f{#khOR?p^*Ek?)lbQb1)yZ4&)L3)GZgrDD7)CJPw zR;>yxV|=5a?PADPq3rBvdPKxvTjR?68_)EdvpzEACnrnUfh}1{D{qN>y1C~y!-ekw Vr=NWJ8UnPO!PC{xWt~$(697vyNO1rF literal 0 HcmV?d00001 diff --git a/Resources/Icons/MjContactPair.png b/Resources/Icons/MjContactPair.png new file mode 100644 index 0000000000000000000000000000000000000000..f663f84fe4e0c06dcd6d9ac8269e30072a1c386a GIT binary patch literal 137 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4#%`0iG_7Ar*6y6C^%02*y4*Vlw-` z!8X@xf^IQM5@6m5u1?Wpr)ftrtrShwFXT9iA67qq#6dA3X@QtU_+vGG+h( literal 0 HcmV?d00001 diff --git a/Resources/Icons/MjDefault.png b/Resources/Icons/MjDefault.png new file mode 100644 index 0000000000000000000000000000000000000000..5888c70dac138a1c16cbb86244786ada8dcfa338 GIT binary patch literal 128 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4#%`?w&4=Ar*6y6BY;<9Fn-a%=fo{ z*ReHgbauo|;&li+eZ)aA;b5xK$%I=AJ}?=sbL6iTOA>j=?876%G;QH~Ry8l)1#w;~ b;tULaKjbwO0^Z#L8p+`4>gTe~DWM4fKFlam literal 0 HcmV?d00001 diff --git a/Resources/Icons/MjEquality.png b/Resources/Icons/MjEquality.png new file mode 100644 index 0000000000000000000000000000000000000000..363488edc733d05413ee39086b2467fabd989fa3 GIT binary patch literal 98 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4#%`nw~C>Ar*6y6C_wgnB7wRj!x_P veId*JSVaVh{Jj4_9cVs-r>mdKI;Vst0D31b$p8QV literal 0 HcmV?d00001 diff --git a/Resources/Icons/MjGeom.png b/Resources/Icons/MjGeom.png new file mode 100644 index 0000000000000000000000000000000000000000..ef50da8be31dce0b8ce2571d6d7af23611ae882f GIT binary patch literal 117 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4#%`Hl8kyAr*6y6C_xBPRyAitogt5 zqRH_jzAn2RX-PZ>R_U>7IjmtkVIs`j+K_pGcY%d~5^{)z4*}Q$iB}4(%dv literal 0 HcmV?d00001 diff --git a/Resources/Icons/MjHingeJoint.png b/Resources/Icons/MjHingeJoint.png new file mode 100644 index 0000000000000000000000000000000000000000..5024ebe45953c89c1daf849b3a8697c76049853a GIT binary patch literal 528 zcmV+r0`L8aP)!6t%ODW;KKcBK4*a)2!fr|3OsssMhCldJo2?RzcH+o7ZiAAmNjLn5Ki7MJr|WAh7Wx?Wm;GPZUI{sCV)|{$ z&Zr3A3Buxn3wT5Qdz|TJ1me8-vys1R?!F zz!CqTa(UQZiTO^zExNlLOCQz@Y$(jd)#NtB0Fyq>#eYkN-SZ}k(Q@y4g4 S&uiKM0000?T z#GhJX?i*I6D!Cc!8LnZwb8w-+bQ$4|vkF%xCM^&!;MHReDR2?BGxcc^5tx*$6sBmn dPI?go!z6JTkr|F}s)2?wc)I$ztaD0e0ssRqCMo~` literal 0 HcmV?d00001 diff --git a/Resources/Icons/MjJoint.png b/Resources/Icons/MjJoint.png new file mode 100644 index 0000000000000000000000000000000000000000..c1473ae7d398ce1d45b5be66c9b267843783606f GIT binary patch literal 129 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4#%`9-c0aAr*6y6BY;3(oU9h0dx-K4^9| qzR33D!3Cd5+!6&0uT-BhGBdm>kW*c@YC$T{1_n=8KbLh*2~7Z|ATJ33 literal 0 HcmV?d00001 diff --git a/Resources/Icons/MjMeshGeom.png b/Resources/Icons/MjMeshGeom.png new file mode 100644 index 0000000000000000000000000000000000000000..7f28b9a8494d838a8602d629afb0f38412534026 GIT binary patch literal 162 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4#%`nVv3=Ar*6yQw}f&`7Qa=zVUg) znZzSY`#LA2<O<o5cJgP-Ck44$rj JF6*2UngF@2IxqkL literal 0 HcmV?d00001 diff --git a/Resources/Icons/MjSensor.png b/Resources/Icons/MjSensor.png new file mode 100644 index 0000000000000000000000000000000000000000..34ecef4ebfdebb3fd86e876f526257d45cc5162a GIT binary patch literal 133 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4#%`KAtX)Ar*6y6C_xBZm{?-ne(IH z_fAqDYg?6DlF1|E4$j$WIcAF8imOvy#2Pe}p0K8T_2Cg=a*K&`C}-UzamKV~3Y(Jh f(u*eyxFi@vMGUxaT3%lUG?&5C)z4*}Q$iB}ap)() literal 0 HcmV?d00001 diff --git a/Resources/Icons/MjSite.png b/Resources/Icons/MjSite.png new file mode 100644 index 0000000000000000000000000000000000000000..f5917492dfa2aec695d5209c421757c96f1b9f04 GIT binary patch literal 132 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4#%`-kvUwAr*6y6BY;&G&Bt0n87xmQM#bTOwUp+N%WEN4955skGrQjN_8x0 eYBX<1VqmzPETv)1_62Av1B0ilpUXO@geCxPEhr-Z literal 0 HcmV?d00001 diff --git a/Resources/Icons/MjSlideJoint.png b/Resources/Icons/MjSlideJoint.png new file mode 100644 index 0000000000000000000000000000000000000000..e03be88a3e0fb1f328754579b8822705923a629c GIT binary patch literal 112 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4#%`=AJH&Ar*6y6C_xfnS*Bi``^BC zriN)tXV7(nq+&76hEAc|ûl64Sb*f}jmyqVE;mSmee1B1|Ar*6y6BY;qHP?=!ytIn?x|Ar*6y6C~^oq@8a1|KvsT zqAN*iUa<#T)=dm?p0R;*QWA%7hsC4G2RMWqHafN?7<0tVnK*&>M-20(p3Vu33a%&g qmPp)q@Ii`sW!r%pBI-*T*%@Xp(&$(h{r4x(0tQc4KbLh*2~7Z$`7=ZS literal 0 HcmV?d00001 diff --git a/Resources/Icons/MjWorldBody.png b/Resources/Icons/MjWorldBody.png new file mode 100644 index 0000000000000000000000000000000000000000..dbe87616f66e4fb9718e263a76dce725c46b30cd GIT binary patch literal 144 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4#%`;hrvzAr*6y6C^SYba*Fux8A8w z+2?;;c} UMjActuator::GetTargetNameOptions() const +{ + UClass* FilterClass = nullptr; + switch (TransmissionType) + { + case EMjActuatorTrnType::Joint: + case EMjActuatorTrnType::JointInParent: + FilterClass = UMjJoint::StaticClass(); + break; + case EMjActuatorTrnType::Tendon: + FilterClass = UMjTendon::StaticClass(); + break; + case EMjActuatorTrnType::Site: + case EMjActuatorTrnType::SliderCrank: + FilterClass = UMjSite::StaticClass(); + break; + case EMjActuatorTrnType::Body: + FilterClass = UMjBody::StaticClass(); + break; + default: + FilterClass = UMjJoint::StaticClass(); + break; + } + 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); +} +#endif + diff --git a/Source/URLab/Private/MuJoCo/Components/Bodies/MjBody.cpp b/Source/URLab/Private/MuJoCo/Components/Bodies/MjBody.cpp index a6a65f0..db188e9 100644 --- a/Source/URLab/Private/MuJoCo/Components/Bodies/MjBody.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Bodies/MjBody.cpp @@ -448,3 +448,10 @@ void UMjBody::RegisterToSpec(FMujocoSpecWrapper& Wrapper, mjsBody* ParentBody) Setup(GetAttachParent(), ParentBody, &Wrapper); } } + +#if WITH_EDITOR +TArray UMjBody::GetChildClassOptions() const +{ + return UMjComponent::GetSiblingComponentOptions(this, UMjDefault::StaticClass(), true); +} +#endif diff --git a/Source/URLab/Private/MuJoCo/Components/Constraints/MjEquality.cpp b/Source/URLab/Private/MuJoCo/Components/Constraints/MjEquality.cpp index e0324c3..62a180d 100644 --- a/Source/URLab/Private/MuJoCo/Components/Constraints/MjEquality.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Constraints/MjEquality.cpp @@ -25,6 +25,9 @@ #include "MuJoCo/Utils/MjUtils.h" #include "XmlNode.h" #include "MuJoCo/Utils/MjXmlUtils.h" +#include "MuJoCo/Components/Bodies/MjBody.h" +#include "MuJoCo/Components/Joints/MjJoint.h" +#include "MuJoCo/Components/Tendons/MjTendon.h" #include "Utils/URLabLogging.h" UMjEquality::UMjEquality() @@ -212,3 +215,25 @@ void UMjEquality::RegisterToSpec(FMujocoSpecWrapper& Wrapper, mjsBody* ParentBod ExportTo(Eq); } + +#if WITH_EDITOR +TArray UMjEquality::GetObjOptions() const +{ + UClass* FilterClass = nullptr; + switch (EqualityType) + { + case EMjEqualityType::Connect: + case EMjEqualityType::Weld: + FilterClass = UMjBody::StaticClass(); + break; + case EMjEqualityType::Joint: + FilterClass = UMjJoint::StaticClass(); + break; + case EMjEqualityType::Tendon: + FilterClass = UMjTendon::StaticClass(); + break; + } + if (!FilterClass) return {TEXT("")}; + return UMjComponent::GetSiblingComponentOptions(this, FilterClass); +} +#endif diff --git a/Source/URLab/Private/MuJoCo/Components/Defaults/MjDefault.cpp b/Source/URLab/Private/MuJoCo/Components/Defaults/MjDefault.cpp index 8fa313d..8570b66 100644 --- a/Source/URLab/Private/MuJoCo/Components/Defaults/MjDefault.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Defaults/MjDefault.cpp @@ -46,6 +46,22 @@ void UMjDefault::ImportFromXml(const FXmlNode* Node) else ClassName = TEXT("main"); } +#if WITH_EDITOR +void UMjDefault::PostEditChangeProperty(FPropertyChangedEvent& PropertyChangedEvent) +{ + Super::PostEditChangeProperty(PropertyChangedEvent); + + // If ClassName is empty after any edit, auto-populate from component name + if (ClassName.IsEmpty()) + { + ClassName = GetName(); + ClassName.ReplaceInline(TEXT("_GEN_VARIABLE"), TEXT("")); + } +} +#endif + + + void UMjDefault::ExportTo(mjsDefault* def) { if (!def) return; diff --git a/Source/URLab/Private/MuJoCo/Components/Geometry/MjGeom.cpp b/Source/URLab/Private/MuJoCo/Components/Geometry/MjGeom.cpp index c8b05cb..b38c38a 100644 --- a/Source/URLab/Private/MuJoCo/Components/Geometry/MjGeom.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Geometry/MjGeom.cpp @@ -21,6 +21,7 @@ // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. #include "MuJoCo/Components/Geometry/MjGeom.h" +#include "Components/StaticMeshComponent.h" #include "MuJoCo/Utils/MjXmlUtils.h" #include "MuJoCo/Utils/MjUtils.h" #include "MuJoCo/Utils/MjOrientationUtils.h" @@ -508,9 +509,33 @@ void UMjGeom::PostEditChangeProperty(FPropertyChangedEvent& PropertyChangedEvent UE_LOG(LogURLab, Log, TEXT("[MjGeom] User manually changed Scale for '%s'. Marking bOverride_Size = true."), *GetName()); } } + + // Sync MjClassName when DefaultClass changes + if (PropertyName == GET_MEMBER_NAME_CHECKED(UMjGeom, DefaultClass)) + { + if (DefaultClass) + MjClassName = DefaultClass->ClassName; + else + MjClassName.Empty(); + } + + // Apply OverrideMaterial to the visual mesh + if (PropertyName == GET_MEMBER_NAME_CHECKED(UMjGeom, OverrideMaterial) || + MemberPropertyName == GET_MEMBER_NAME_CHECKED(UMjGeom, OverrideMaterial)) + { + ApplyOverrideMaterial(OverrideMaterial); + } } #endif +void UMjGeom::ApplyOverrideMaterial(UMaterialInterface* Material) +{ + // Base implementation is a no-op. Mesh geoms should not have their imported + // materials overwritten — they already have materials from the import pipeline. + // Primitive subclasses (Box, Sphere, Cylinder) override this with direct + // VisualizerMesh access. +} + void UMjGeom::RegisterToSpec(FMujocoSpecWrapper& Wrapper, mjsBody* ParentBody) { if (!ParentBody) return; @@ -1027,3 +1052,10 @@ void UMjGeom::RemoveDecomposition() void UMjGeom::DecomposeMesh() {} void UMjGeom::RemoveDecomposition() {} #endif + +#if WITH_EDITOR +TArray UMjGeom::GetDefaultClassOptions() const +{ + return GetSiblingComponentOptions(this, UMjDefault::StaticClass(), true); +} +#endif diff --git a/Source/URLabEditor/Public/MjGeomDetailCustomization.h b/Source/URLab/Private/MuJoCo/Components/Geometry/MjMeshGeom.cpp similarity index 75% rename from Source/URLabEditor/Public/MjGeomDetailCustomization.h rename to Source/URLab/Private/MuJoCo/Components/Geometry/MjMeshGeom.cpp index 55df442..07f59bf 100644 --- a/Source/URLabEditor/Public/MjGeomDetailCustomization.h +++ b/Source/URLab/Private/MuJoCo/Components/Geometry/MjMeshGeom.cpp @@ -13,20 +13,17 @@ // 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. -#pragma once -#include "CoreMinimal.h" -#include "IDetailCustomization.h" +#include "MuJoCo/Components/Geometry/MjMeshGeom.h" -class FMjGeomDetailCustomization : public IDetailCustomization +UMjMeshGeom::UMjMeshGeom() { -public: - static TSharedRef MakeInstance(); - virtual void CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) override; -}; + Type = EMjGeomType::Mesh; + bOverride_Type = true; +} diff --git a/Source/URLab/Private/MuJoCo/Components/Geometry/MjSite.cpp b/Source/URLab/Private/MuJoCo/Components/Geometry/MjSite.cpp index e51dcd1..8cc8967 100644 --- a/Source/URLab/Private/MuJoCo/Components/Geometry/MjSite.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Geometry/MjSite.cpp @@ -232,3 +232,10 @@ void UMjSite::Bind(mjModel* model, mjData* data, const FString& Prefix) UE_LOG(LogURLabBind, Warning, TEXT("[MjSite] Site '%s' FAILED bind. Prefix: %s, MjName: %s"), *GetName(), *Prefix, *MjName); } } + +#if WITH_EDITOR +TArray UMjSite::GetDefaultClassOptions() const +{ + return GetSiblingComponentOptions(this, UMjDefault::StaticClass(), true); +} +#endif diff --git a/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjBox.cpp b/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjBox.cpp index 3225cfb..3b5ded0 100644 --- a/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjBox.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjBox.cpp @@ -65,6 +65,12 @@ void UMjBox::OnRegister() VisualizerMesh->SetupAttachment(this); VisualizerMesh->RegisterComponent(); } + + // Apply override material after mesh is created and registered + if (VisualizerMesh && OverrideMaterial && IsValid(OverrideMaterial) && GetOwner()) + { + VisualizerMesh->SetMaterial(0, OverrideMaterial); + } } @@ -115,6 +121,15 @@ void UMjBox::ExportTo(mjsGeom* geom, mjsDefault* def) Super::ExportTo(geom, def); } +void UMjBox::ApplyOverrideMaterial(UMaterialInterface* Material) +{ + EnsureVisualizerMesh(); + if (VisualizerMesh && Material && IsValid(Material)) + { + VisualizerMesh->SetMaterial(0, Material); + } +} + void UMjBox::SyncUnrealTransformFromMj() { if (m_GeomView.id == -1) return; diff --git a/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjCylinder.cpp b/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjCylinder.cpp index 636145c..9fbd08f 100644 --- a/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjCylinder.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjCylinder.cpp @@ -65,6 +65,11 @@ void UMjCylinder::OnRegister() VisualizerMesh->SetupAttachment(this); VisualizerMesh->RegisterComponent(); } + + if (VisualizerMesh && OverrideMaterial && IsValid(OverrideMaterial) && GetOwner()) + { + VisualizerMesh->SetMaterial(0, OverrideMaterial); + } } @@ -108,6 +113,12 @@ void UMjCylinder::ExportTo(mjsGeom* geom, mjsDefault* def) Super::ExportTo(geom, def); } +void UMjCylinder::ApplyOverrideMaterial(UMaterialInterface* Material) +{ + EnsureVisualizerMesh(); + if (VisualizerMesh && Material && IsValid(Material)) VisualizerMesh->SetMaterial(0, Material); +} + void UMjCylinder::SyncUnrealTransformFromMj() { if (m_GeomView.id == -1) return; diff --git a/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjSphere.cpp b/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjSphere.cpp index 6e3a2e4..dd7b7d9 100644 --- a/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjSphere.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Geometry/Primitives/MjSphere.cpp @@ -65,6 +65,11 @@ void UMjSphere::OnRegister() VisualizerMesh->SetupAttachment(this); VisualizerMesh->RegisterComponent(); } + + if (VisualizerMesh && OverrideMaterial && IsValid(OverrideMaterial) && GetOwner()) + { + VisualizerMesh->SetMaterial(0, OverrideMaterial); + } } @@ -104,6 +109,12 @@ void UMjSphere::ExportTo(mjsGeom* geom, mjsDefault* def) Super::ExportTo(geom, def); } +void UMjSphere::ApplyOverrideMaterial(UMaterialInterface* Material) +{ + EnsureVisualizerMesh(); + if (VisualizerMesh && Material && IsValid(Material)) VisualizerMesh->SetMaterial(0, Material); +} + void UMjSphere::SyncUnrealTransformFromMj() { if (m_GeomView.id == -1) return; diff --git a/Source/URLab/Private/MuJoCo/Components/Joints/MjJoint.cpp b/Source/URLab/Private/MuJoCo/Components/Joints/MjJoint.cpp index 106b056..bdb69d2 100644 --- a/Source/URLab/Private/MuJoCo/Components/Joints/MjJoint.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Joints/MjJoint.cpp @@ -512,3 +512,10 @@ FString UMjJoint::GetTelemetryTopicName() const { return FString::Printf(TEXT("joint/%s"), *GetName()); } + +#if WITH_EDITOR +TArray UMjJoint::GetDefaultClassOptions() const +{ + return GetSiblingComponentOptions(this, UMjDefault::StaticClass(), true); +} +#endif diff --git a/Source/URLab/Private/MuJoCo/Components/MjComponent.cpp b/Source/URLab/Private/MuJoCo/Components/MjComponent.cpp index b7e7749..4369ad0 100644 --- a/Source/URLab/Private/MuJoCo/Components/MjComponent.cpp +++ b/Source/URLab/Private/MuJoCo/Components/MjComponent.cpp @@ -25,6 +25,13 @@ #include "MuJoCo/Components/Defaults/MjDefault.h" #include "MuJoCo/Components/Bodies/MjBody.h" +#if WITH_EDITOR +#include "Engine/Blueprint.h" +#include "Engine/BlueprintGeneratedClass.h" +#include "Engine/SimpleConstructionScript.h" +#include "Engine/SCS_Node.h" +#endif + UMjComponent::UMjComponent() { PrimaryComponentTick.bCanEverTick = true; @@ -120,3 +127,47 @@ UMjDefault* UMjComponent::FindEditorDefault() const return nullptr; } + +#if WITH_EDITOR +TArray UMjComponent::GetSiblingComponentOptions(const UObject* CallerComponent, UClass* FilterClass, bool bIncludeDefaults) +{ + TArray Options; + Options.Add(TEXT("")); // Empty = no selection + + if (!CallerComponent || !FilterClass) return Options; + + // Walk the outer chain to find the owning Blueprint + UBlueprint* BP = nullptr; + for (UObject* Outer = CallerComponent->GetOuter(); Outer; Outer = Outer->GetOuter()) + { + if (UBlueprintGeneratedClass* BPGC = Cast(Outer)) + { + BP = Cast(BPGC->ClassGeneratedBy); + break; + } + if (UBlueprint* Found = Cast(Outer)) + { + BP = Found; + break; + } + } + + if (!BP || !BP->SimpleConstructionScript) return Options; + + for (USCS_Node* Node : BP->SimpleConstructionScript->GetAllNodes()) + { + UMjComponent* MjComp = Cast(Node->ComponentTemplate); + if (MjComp && MjComp->IsA(FilterClass)) + { + if (MjComp->bIsDefault && !bIncludeDefaults) continue; + + FString DisplayName = MjComp->MjName.IsEmpty() + ? Node->GetVariableName().ToString() + : MjComp->MjName; + Options.Add(DisplayName); + } + } + + return Options; +} +#endif diff --git a/Source/URLab/Private/MuJoCo/Components/Physics/MjContactExclude.cpp b/Source/URLab/Private/MuJoCo/Components/Physics/MjContactExclude.cpp index 8ffc886..4971cf1 100644 --- a/Source/URLab/Private/MuJoCo/Components/Physics/MjContactExclude.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Physics/MjContactExclude.cpp @@ -24,6 +24,8 @@ #include "XmlFile.h" #include "mujoco/mujoco.h" #include "MuJoCo/Core/Spec/MjSpecWrapper.h" +#include "MuJoCo/Components/MjComponent.h" +#include "MuJoCo/Components/Bodies/MjBody.h" #include "Utils/URLabLogging.h" UMjContactExclude::UMjContactExclude() @@ -74,3 +76,10 @@ 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()); +} +#endif diff --git a/Source/URLab/Private/MuJoCo/Components/Physics/MjContactPair.cpp b/Source/URLab/Private/MuJoCo/Components/Physics/MjContactPair.cpp index 2df4c19..9c63973 100644 --- a/Source/URLab/Private/MuJoCo/Components/Physics/MjContactPair.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Physics/MjContactPair.cpp @@ -25,6 +25,8 @@ #include "mujoco/mujoco.h" #include "MuJoCo/Core/Spec/MjSpecWrapper.h" #include "MuJoCo/Utils/MjXmlUtils.h" +#include "MuJoCo/Components/MjComponent.h" +#include "MuJoCo/Components/Geometry/MjGeom.h" #include "Utils/URLabLogging.h" UMjContactPair::UMjContactPair() @@ -132,3 +134,10 @@ 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()); +} +#endif diff --git a/Source/URLab/Private/MuJoCo/Components/Sensors/MjSensor.cpp b/Source/URLab/Private/MuJoCo/Components/Sensors/MjSensor.cpp index a99d63b..d643f51 100644 --- a/Source/URLab/Private/MuJoCo/Components/Sensors/MjSensor.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Sensors/MjSensor.cpp @@ -27,6 +27,12 @@ #include "Utils/URLabLogging.h" #include "MuJoCo/Components/Defaults/MjDefault.h" #include "MuJoCo/Core/Spec/MjSpecWrapper.h" +#include "MuJoCo/Components/Bodies/MjBody.h" +#include "MuJoCo/Components/Joints/MjJoint.h" +#include "MuJoCo/Components/Geometry/MjGeom.h" +#include "MuJoCo/Components/Geometry/MjSite.h" +#include "MuJoCo/Components/Tendons/MjTendon.h" +#include "MuJoCo/Components/Actuators/MjActuator.h" UMjSensor::UMjSensor() { @@ -490,3 +496,39 @@ FString UMjSensor::GetTelemetryTopicName() const { return FString::Printf(TEXT("sensor/%s"), *GetName()); } + +#if WITH_EDITOR +namespace +{ + UClass* GetClassForObjType(EMjObjType ObjType) + { + switch (ObjType) + { + case EMjObjType::Body: return UMjBody::StaticClass(); + case EMjObjType::Joint: return UMjJoint::StaticClass(); + case EMjObjType::Geom: return UMjGeom::StaticClass(); + case EMjObjType::Site: return UMjSite::StaticClass(); + case EMjObjType::Tendon: return UMjTendon::StaticClass(); + case EMjObjType::Actuator:return UMjActuator::StaticClass(); + case EMjObjType::Sensor: return UMjSensor::StaticClass(); + default: return UMjComponent::StaticClass(); + } + } +} + +TArray UMjSensor::GetTargetNameOptions() const +{ + return UMjComponent::GetSiblingComponentOptions(this, GetClassForObjType(ObjType)); +} + +TArray UMjSensor::GetReferenceNameOptions() const +{ + if (RefType == EMjObjType::Unknown) return {TEXT("")}; + return UMjComponent::GetSiblingComponentOptions(this, GetClassForObjType(RefType)); +} + +TArray UMjSensor::GetDefaultClassOptions() const +{ + return UMjComponent::GetSiblingComponentOptions(this, UMjDefault::StaticClass(), true); +} +#endif diff --git a/Source/URLab/Private/MuJoCo/Components/Tendons/MjTendon.cpp b/Source/URLab/Private/MuJoCo/Components/Tendons/MjTendon.cpp index 33a36aa..fb753b1 100644 --- a/Source/URLab/Private/MuJoCo/Components/Tendons/MjTendon.cpp +++ b/Source/URLab/Private/MuJoCo/Components/Tendons/MjTendon.cpp @@ -300,3 +300,10 @@ FString UMjTendon::GetMjName() const if (m_TendonView.id < 0 || !m_TendonView.name) return FString(); return MjUtils::MjToString(m_TendonView.name); } + +#if WITH_EDITOR +TArray UMjTendon::GetDefaultClassOptions() const +{ + return GetSiblingComponentOptions(this, UMjDefault::StaticClass(), true); +} +#endif diff --git a/Source/URLab/Private/MuJoCo/Core/MjArticulation.cpp b/Source/URLab/Private/MuJoCo/Core/MjArticulation.cpp index db3897f..103438c 100644 --- a/Source/URLab/Private/MuJoCo/Core/MjArticulation.cpp +++ b/Source/URLab/Private/MuJoCo/Core/MjArticulation.cpp @@ -26,6 +26,9 @@ #include "MuJoCo/Input/MjTwistController.h" #include "Misc/MessageDialog.h" #include "Engine/Blueprint.h" +#include "Engine/SimpleConstructionScript.h" +#include "Engine/SCS_Node.h" +#include "MuJoCo/Components/Defaults/MjDefault.h" #include "EnhancedInputComponent.h" #include "EnhancedInputSubsystems.h" #include "InputAction.h" @@ -251,12 +254,71 @@ void AMjArticulation::Setup(mjSpec* Spec, mjVFS* VFS) m_wrapper = new FMujocoSpecWrapper(m_ChildSpec, m_vfs); m_wrapper->MeshCacheSubDir = GetClass()->GetName(); - // 2. Process Defaults FIRST so they exist for bodies/geoms to reference - TArray Defaults; - GetComponents(Defaults); - for (UMjDefault* Def : Defaults) + // 1b. Auto-resolve bIsDefault and sync ParentClassName from hierarchy. + // This ensures correctness even if OnBlueprintCompiled hasn't run. { - m_wrapper->AddDefault(Def); + TArray AllDefaults; + GetComponents(AllDefaults); + for (UMjDefault* Def : AllDefaults) + { + Def->bIsDefault = true; + + // Sync ParentClassName from attachment parent if attached to another UMjDefault. + // If not (e.g. attached to root), keep existing ParentClassName as fallback + // for programmatically created defaults that set it explicitly. + if (UMjDefault* ParentDef = Cast(Def->GetAttachParent())) + { + Def->ParentClassName = ParentDef->ClassName; + } + else if (Def->ParentClassName.IsEmpty()) + { + // No parent default in hierarchy and no explicit ParentClassName — root default + } + + TArray DefChildren; + Def->GetChildrenComponents(true, DefChildren); + for (USceneComponent* Child : DefChildren) + { + if (UMjComponent* MjChild = Cast(Child)) + { + MjChild->bIsDefault = true; + } + } + } + } + + // 2. Process Defaults in hierarchy order (parents before children) so that + // mjs_findDefault can resolve parent classes during AddDefault. + { + TArray AllDefaults; + GetComponents(AllDefaults); + + // Find root defaults (those whose parent is NOT a UMjDefault) + // and process them recursively, depth-first + TFunction ProcessDefaultTree = [&](UMjDefault* Def) + { + m_wrapper->AddDefault(Def); + // Find child defaults attached to this one + TArray Children; + Def->GetChildrenComponents(false, Children); + for (USceneComponent* Child : Children) + { + if (UMjDefault* ChildDef = Cast(Child)) + { + ProcessDefaultTree(ChildDef); + } + } + }; + + for (UMjDefault* Def : AllDefaults) + { + // Only start from roots (parent is not a UMjDefault) + UMjDefault* ParentDef = Cast(Def->GetAttachParent()); + if (!ParentDef) + { + ProcessDefaultTree(Def); + } + } } // 3. Find UMjWorldBody and build body hierarchy normally (into child spec) @@ -1177,6 +1239,43 @@ void AMjArticulation::OnConstruction(const FTransform& Transform) void AMjArticulation::OnBlueprintCompiled(UBlueprint* Blueprint) { + // Sync MjDefault ClassName and ParentClassName from SCS hierarchy + if (Blueprint && Blueprint->SimpleConstructionScript) + { + USimpleConstructionScript* SCS = Blueprint->SimpleConstructionScript; + for (USCS_Node* Node : SCS->GetAllNodes()) + { + if (UMjDefault* DefComp = Cast(Node->ComponentTemplate)) + { + // Sync ClassName from variable name + FString VarName = Node->GetVariableName().ToString(); + if (DefComp->ClassName != VarName) + { + DefComp->ClassName = VarName; + } + + // Sync ParentClassName from SCS parent hierarchy + USCS_Node* ParentNode = SCS->FindParentNode(Node); + if (ParentNode) + { + if (UMjDefault* ParentDef = Cast(ParentNode->ComponentTemplate)) + { + FString ParentVarName = ParentNode->GetVariableName().ToString(); + if (DefComp->ParentClassName != ParentVarName) + { + DefComp->ParentClassName = ParentVarName; + } + } + else + { + // Parent is not a UMjDefault (e.g. DefaultsRoot) — no parent class + DefComp->ParentClassName.Empty(); + } + } + } + } + } + if (bValidateOnBlueprintCompile) { ValidateSpec(); diff --git a/Source/URLab/Public/MuJoCo/Components/Actuators/MjActuator.h b/Source/URLab/Public/MuJoCo/Components/Actuators/MjActuator.h index 933e88c..22a0960 100644 --- a/Source/URLab/Public/MuJoCo/Components/Actuators/MjActuator.h +++ b/Source/URLab/Public/MuJoCo/Components/Actuators/MjActuator.h @@ -28,6 +28,7 @@ #include "mujoco/mujoco.h" #include "MuJoCo/Core/Spec/MjSpecElement.h" #include "MuJoCo/Components/MjComponent.h" +#include "MuJoCo/Components/Defaults/MjDefault.h" #include #include "MjActuator.generated.h" @@ -80,17 +81,25 @@ class URLAB_API UMjActuator : public UMjComponent UMjActuator(); /** @brief The type of actuator dynamics (e.g. Motor, Position). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator") EMjActuatorType Type; /** @brief The transmission type connecting the actuator to the system. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator") EMjActuatorTrnType TransmissionType; - /** @brief Optional MuJoCo class name to inherit defaults from. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator") + /** @brief Optional MuJoCo class name to inherit defaults from (string fallback). */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(GetOptions="GetDefaultClassOptions")) FString MjClassName; - virtual FString GetMjClassName() const override { return MjClassName; } + + /** @brief Reference to a UMjDefault component for default class inheritance. */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator") + UMjDefault* DefaultClass = nullptr; + + virtual FString GetMjClassName() const override + { + return MjClassName; + } virtual void ExportTo(mjsActuator* Actuator, mjsDefault* Default = nullptr); void ApplyRawOverrides(mjsActuator* Actuator, mjsDefault* Default = nullptr); @@ -196,129 +205,140 @@ class URLAB_API UMjActuator : public UMjComponent public: /** @brief Name of the target element (Joint, Tendon, Site, etc.) this actuator acts upon. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(GetOptions="GetTargetNameOptions")) FString TargetName; /** @brief Override toggle for Gear. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_Gear = false; /** @brief Gear ratio scaling for the transmission. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator", meta=(EditCondition="bOverride_Gear")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_Gear")) TArray Gear; /** @brief Override toggle for GainPrm. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_GainPrm = false; /** @brief Custom gain parameters (gainprm). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator", meta=(EditCondition="bOverride_GainPrm")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_GainPrm")) TArray GainPrm; /** @brief Override toggle for BiasPrm. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_BiasPrm = false; /** @brief Custom bias parameters (biasprm). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator", meta=(EditCondition="bOverride_BiasPrm")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_BiasPrm")) TArray BiasPrm; /** @brief Override toggle for CtrlRange. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_CtrlRange = false; /** @brief Control range [min, max]. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator", meta=(EditCondition="bOverride_CtrlRange")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_CtrlRange")) TArray CtrlRange = {0.0f, 0.0f}; /** @brief Override toggle for CtrlLimited. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_CtrlLimited = false; /** @brief Whether control limiting is enabled. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator", meta=(EditCondition="bOverride_CtrlLimited")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_CtrlLimited")) bool bCtrlLimited = false; /** @brief Override toggle for ForceRange. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_ForceRange = false; /** @brief Force output range [min, max]. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator", meta=(EditCondition="bOverride_ForceRange")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_ForceRange")) TArray ForceRange = {0.0f, 0.0f}; /** @brief Override toggle for ForceLimited. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_ForceLimited = false; /** @brief Whether force limiting is enabled. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator", meta=(EditCondition="bOverride_ForceLimited")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_ForceLimited")) bool bForceLimited = false; /** @brief Override toggle for ActLimited. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_ActLimited = false; /** @brief Whether internal activation state is limited. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator", meta=(EditCondition="bOverride_ActLimited")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_ActLimited")) bool bActLimited = false; /** @brief Override toggle for ActRange. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_ActRange = false; /** @brief Activation state range [min, max]. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator", meta=(EditCondition="bOverride_ActRange")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_ActRange")) TArray ActRange = {0.0f, 0.0f}; /** @brief Override toggle for LengthRange. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_LengthRange = false; /** @brief Length range for muscle/tendon actuators. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator", meta=(EditCondition="bOverride_LengthRange")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_LengthRange")) TArray LengthRange = {0.0f, 0.0f}; // Transmission specific /** @brief Length of the crank for slider-crank transmission. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator") float CrankLength; /** @brief Name of the slider site for slider-crank transmission. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(GetOptions="GetSliderSiteOptions")) FString SliderSite; /** @brief Reference site name. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(GetOptions="GetRefSiteOptions")) FString RefSite; /** @brief Override toggle for Group. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_Group = false; /** @brief Actuator group ID. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator", meta=(EditCondition="bOverride_Group")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_Group")) int Group = 0; /** @brief Override toggle for ActEarly. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_ActEarly = false; /** @brief Whether to apply actuation early (before other forces). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator", meta=(EditCondition="bOverride_ActEarly")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_ActEarly")) bool bActEarly = false; /** @brief Override toggle for Dynamics. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_Dynamics = false; /** @brief Override toggle for DynPrm. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_DynPrm = false; /** @brief Custom dynamic parameters (dynprm). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator", meta=(EditCondition="bOverride_DynPrm")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator", meta=(EditCondition="bOverride_DynPrm")) TArray DynPrm; +#if WITH_EDITOR + UFUNCTION() + TArray GetTargetNameOptions() const; + UFUNCTION() + TArray GetSliderSiteOptions() const; + UFUNCTION() + TArray GetRefSiteOptions() const; + UFUNCTION() + TArray GetDefaultClassOptions() const; +#endif + virtual void BeginPlay() override; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Actuators/MjAdhesionActuator.h b/Source/URLab/Public/MuJoCo/Components/Actuators/MjAdhesionActuator.h index 9a4a9bd..1c0a0aa 100644 --- a/Source/URLab/Public/MuJoCo/Components/Actuators/MjAdhesionActuator.h +++ b/Source/URLab/Public/MuJoCo/Components/Actuators/MjAdhesionActuator.h @@ -38,11 +38,11 @@ class URLAB_API UMjAdhesionActuator : public UMjActuator UMjAdhesionActuator(); /** @brief Override toggle for Kp. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_Kp = false; /** @brief Proportional gain (Kp) for position servos. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_Kp")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_Kp")) float Kp = 1.0f; virtual void ParseSpecifics(const class FXmlNode* Node) override; diff --git a/Source/URLab/Public/MuJoCo/Components/Actuators/MjCylinderActuator.h b/Source/URLab/Public/MuJoCo/Components/Actuators/MjCylinderActuator.h index 9f2b261..f3bd841 100644 --- a/Source/URLab/Public/MuJoCo/Components/Actuators/MjCylinderActuator.h +++ b/Source/URLab/Public/MuJoCo/Components/Actuators/MjCylinderActuator.h @@ -38,35 +38,35 @@ class URLAB_API UMjCylinderActuator : public UMjActuator UMjCylinderActuator(); /** @brief Override toggle for TimeConst. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_TimeConst = false; /** @brief Time constant for activation dynamics. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_TimeConst")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_TimeConst")) float TimeConst = 0.01f; /** @brief Override toggle for Bias. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_Bias = false; /** @brief Bias force offset. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_Bias")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_Bias")) float Bias = 0.0f; /** @brief Override toggle for Area. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_Area = false; /** @brief Cross-sectional area. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_Area")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_Area")) float Area = 1.0f; /** @brief Override toggle for Diameter. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_Diameter = false; /** @brief Cylinder diameter. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_Diameter")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_Diameter")) float Diameter = 1.0f; virtual void ParseSpecifics(const class FXmlNode* Node) override; diff --git a/Source/URLab/Public/MuJoCo/Components/Actuators/MjDamperActuator.h b/Source/URLab/Public/MuJoCo/Components/Actuators/MjDamperActuator.h index 601d985..8127cc0 100644 --- a/Source/URLab/Public/MuJoCo/Components/Actuators/MjDamperActuator.h +++ b/Source/URLab/Public/MuJoCo/Components/Actuators/MjDamperActuator.h @@ -38,11 +38,11 @@ class URLAB_API UMjDamperActuator : public UMjActuator UMjDamperActuator(); /** @brief Override toggle for Kv. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_Kv = false; /** @brief Derivative gain (Kv) for velocity damping. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_Kv")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_Kv")) double Kv = 0.0f; virtual void ParseSpecifics(const class FXmlNode* Node) override; diff --git a/Source/URLab/Public/MuJoCo/Components/Actuators/MjIntVelocityActuator.h b/Source/URLab/Public/MuJoCo/Components/Actuators/MjIntVelocityActuator.h index 7d8b4b1..8a184ed 100644 --- a/Source/URLab/Public/MuJoCo/Components/Actuators/MjIntVelocityActuator.h +++ b/Source/URLab/Public/MuJoCo/Components/Actuators/MjIntVelocityActuator.h @@ -38,43 +38,43 @@ class URLAB_API UMjIntVelocityActuator : public UMjActuator UMjIntVelocityActuator(); /** @brief Override toggle for Kp. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_Kp = false; /** @brief Proportional gain (Kp) for position servos. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_Kp")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_Kp")) float Kp = 1.0f; /** @brief Override toggle for Kv. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_Kv = false; /** @brief Derivative gain (Kv) for velocity damping. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_Kv")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_Kv")) double Kv = 0.0f; /** @brief Override toggle for DampRatio. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_DampRatio = false; /** @brief Damping ratio. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_DampRatio")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_DampRatio")) float DampRatio = 0.0f; /** @brief Override toggle for TimeConst. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_TimeConst = false; /** @brief Time constant for activation dynamics. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_TimeConst")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_TimeConst")) float TimeConst = 0.0f; /** @brief Override toggle for InheritRange. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_InheritRange = false; /** @brief Inherited range scale factor. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_InheritRange")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_InheritRange")) float InheritRange = 0.0f; virtual void ParseSpecifics(const class FXmlNode* Node) override; diff --git a/Source/URLab/Public/MuJoCo/Components/Actuators/MjMuscleActuator.h b/Source/URLab/Public/MuJoCo/Components/Actuators/MjMuscleActuator.h index 7fb7c1c..3885680 100644 --- a/Source/URLab/Public/MuJoCo/Components/Actuators/MjMuscleActuator.h +++ b/Source/URLab/Public/MuJoCo/Components/Actuators/MjMuscleActuator.h @@ -38,83 +38,83 @@ class URLAB_API UMjMuscleActuator : public UMjActuator UMjMuscleActuator(); /** @brief Override toggle for TimeConst. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_TimeConst = false; /** @brief Time constant for activation dynamics. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_TimeConst")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_TimeConst")) float TimeConst = 0.01f; /** @brief Override toggle for TimeConst2. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_TimeConst2 = false; /** @brief Second time constant (e.g. deactivation time). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_TimeConst2")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_TimeConst2")) float TimeConst2 = 0.04f; /** @brief Override toggle for TauSmooth. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_TauSmooth = false; /** @brief Smoothing time constant. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_TauSmooth")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_TauSmooth")) float TauSmooth = 0.0f; /** @brief Override toggle for Force. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_Force = false; /** @brief Peak active force. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_Force")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_Force")) float Force = -1.0f; // Muscle force /** @brief Override toggle for Scale. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_Scale = false; /** @brief Force scaling factor. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_Scale")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_Scale")) float Scale = 200.0f; // Muscle scale /** @brief Override toggle for LMin. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_LMin = false; /** @brief Minimum fiber length. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_LMin")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_LMin")) float LMin = 0.5f; /** @brief Override toggle for LMax. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_LMax = false; /** @brief Maximum fiber length. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_LMax")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_LMax")) float LMax = 1.6f; /** @brief Override toggle for VMax. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_VMax = false; /** @brief Maximum shortening velocity. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_VMax")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_VMax")) float VMax = 1.5f; /** @brief Override toggle for FPMax. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_FPMax = false; /** @brief Peak passive force. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_FPMax")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_FPMax")) float FPMax = 1.3f; /** @brief Override toggle for FVMax. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_FVMax = false; /** @brief Peak viscous force. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_FVMax")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_FVMax")) float FVMax = 1.2f; virtual void ParseSpecifics(const class FXmlNode* Node) override; diff --git a/Source/URLab/Public/MuJoCo/Components/Actuators/MjPositionActuator.h b/Source/URLab/Public/MuJoCo/Components/Actuators/MjPositionActuator.h index 3aabe9d..daa679d 100644 --- a/Source/URLab/Public/MuJoCo/Components/Actuators/MjPositionActuator.h +++ b/Source/URLab/Public/MuJoCo/Components/Actuators/MjPositionActuator.h @@ -38,43 +38,43 @@ class URLAB_API UMjPositionActuator : public UMjActuator UMjPositionActuator(); /** @brief Override toggle for Kp. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_Kp = false; /** @brief Proportional gain (Kp) for position servos. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_Kp")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_Kp")) float Kp = 1.0f; /** @brief Override toggle for Kv. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_Kv = false; /** @brief Derivative gain (Kv) for velocity damping. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_Kv")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_Kv")) double Kv = 0.0f; /** @brief Override toggle for DampRatio. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_DampRatio = false; /** @brief Damping ratio. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_DampRatio")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_DampRatio")) float DampRatio = 0.0f; /** @brief Override toggle for TimeConst. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_TimeConst = false; /** @brief Time constant for activation dynamics. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_TimeConst")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_TimeConst")) float TimeConst = 0.0f; /** @brief Override toggle for InheritRange. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_InheritRange = false; /** @brief Inherited range scale factor. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_InheritRange")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_InheritRange")) float InheritRange = 0.0f; virtual void ParseSpecifics(const class FXmlNode* Node) override; diff --git a/Source/URLab/Public/MuJoCo/Components/Actuators/MjVelocityActuator.h b/Source/URLab/Public/MuJoCo/Components/Actuators/MjVelocityActuator.h index 59719eb..fa549a3 100644 --- a/Source/URLab/Public/MuJoCo/Components/Actuators/MjVelocityActuator.h +++ b/Source/URLab/Public/MuJoCo/Components/Actuators/MjVelocityActuator.h @@ -38,11 +38,11 @@ class URLAB_API UMjVelocityActuator : public UMjActuator UMjVelocityActuator(); /** @brief Override toggle for Kv. */ - UPROPERTY(EditAnywhere, Category = "Mj Actuator", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Actuator", meta=(InlineEditConditionToggle)) bool bOverride_Kv = false; /** @brief Derivative gain (Kv) for velocity damping. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Actuator|Parameters", meta=(EditCondition="bOverride_Kv")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Actuator|Parameters", meta=(EditCondition="bOverride_Kv")) double Kv = 0.0f; virtual void ParseSpecifics(const class FXmlNode* Node) override; diff --git a/Source/URLab/Public/MuJoCo/Components/Bodies/MjBody.h b/Source/URLab/Public/MuJoCo/Components/Bodies/MjBody.h index 1cd15f5..4f0270e 100644 --- a/Source/URLab/Public/MuJoCo/Components/Bodies/MjBody.h +++ b/Source/URLab/Public/MuJoCo/Components/Bodies/MjBody.h @@ -56,32 +56,37 @@ class URLAB_API UMjBody : public UMjComponent public: UMjBody(); /** @brief If true, this body was created via Quick Convert, enabling specific logic like pivot correction. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo Import") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Body") bool bIsQuickConverted = false; /** @brief If true, this body's transform is driven by the Unreal Actor/Component, enabling One-Way coupling (Unreal -> MuJoCo). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo Physics") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Body") bool bDrivenByUnreal = false; /** @brief Override toggle for Gravcomp. */ - UPROPERTY(EditAnywhere, Category = "MuJoCo Physics", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Body", meta=(InlineEditConditionToggle)) bool bOverride_Gravcomp = false; /** @brief Anti-gravity force applied to the body, in units of body weight. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo Physics", meta=(EditCondition="bOverride_Gravcomp")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Body", meta=(EditCondition="bOverride_Gravcomp")) float Gravcomp = 0.0f; /** @brief If true, overrides the MuJoCo default class name inherited from the parent body's childclass attribute. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo Physics") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Body") bool bOverride_ChildClassName = false; /** @brief Child class name for this body. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo Physics", meta=(EditCondition="bOverride_ChildClassName")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Body", meta=(EditCondition="bOverride_ChildClassName", GetOptions="GetChildClassOptions")) FString ChildClassName; +#if WITH_EDITOR + UFUNCTION() + TArray GetChildClassOptions() const; +#endif + /** @brief Per-body sleep policy (MuJoCo 3.4+). Default lets the global option decide. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo Physics|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; @@ -156,14 +161,14 @@ class URLAB_API UMjBody : public UMjComponent * @brief Returns true if this body is currently awake (not sleeping). * Returns true if sleep is disabled or if the body has not been bound yet. */ - UFUNCTION(BlueprintCallable, BlueprintPure, Category = "MuJoCo|Sleep") + UFUNCTION(BlueprintCallable, BlueprintPure, Category = "MuJoCo|Body|Sleep") bool IsAwake() const; /** * @brief Wakes this body and its kinematic tree, forcing it out of sleep. * No-op if sleep is disabled or if this body has not been bound. */ - UFUNCTION(BlueprintCallable, Category = "MuJoCo|Sleep") + UFUNCTION(BlueprintCallable, Category = "MuJoCo|Body|Sleep") void Wake(); /** @@ -172,7 +177,7 @@ class URLAB_API UMjBody : public UMjComponent * receives an impulse that exceeds the sleep tolerance. * No-op if sleep is disabled or if this body has not been bound. */ - UFUNCTION(BlueprintCallable, Category = "MuJoCo|Sleep") + UFUNCTION(BlueprintCallable, Category = "MuJoCo|Body|Sleep") void Sleep(); protected: diff --git a/Source/URLab/Public/MuJoCo/Components/Constraints/MjEquality.h b/Source/URLab/Public/MuJoCo/Components/Constraints/MjEquality.h index 0372568..51e6251 100644 --- a/Source/URLab/Public/MuJoCo/Components/Constraints/MjEquality.h +++ b/Source/URLab/Public/MuJoCo/Components/Constraints/MjEquality.h @@ -75,70 +75,75 @@ class URLAB_API UMjEquality : public UMjComponent void ImportFromXml(const class FXmlNode* Node); /** @brief The type of equality constraint. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Equality") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Equality") EMjEqualityType EqualityType = EMjEqualityType::Weld; /** @brief Name of the first object (body, joint, or tendon). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Equality") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Equality", meta=(GetOptions="GetObjOptions")) FString Obj1; /** @brief Name of the second object (body, joint, or tendon). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Equality") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Equality", meta=(GetOptions="GetObjOptions")) FString Obj2; +#if WITH_EDITOR + UFUNCTION() + TArray GetObjOptions() const; +#endif + /** @brief Whether the equality constraint is initially active. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Equality") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Equality") bool bActive = true; // --- Solver Parameters --- /** @brief Override toggle for SolRef. */ - UPROPERTY(EditAnywhere, Category = "Mj Equality|Physics", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Equality|Physics", meta=(InlineEditConditionToggle)) bool bOverride_SolRef = false; /** @brief Constraint solver reference (timeconst, dampratio). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Equality|Physics", meta=(EditCondition="bOverride_SolRef")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Equality|Physics", meta=(EditCondition="bOverride_SolRef")) TArray SolRef; /** @brief Override toggle for SolImp. */ - UPROPERTY(EditAnywhere, Category = "Mj Equality|Physics", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Equality|Physics", meta=(InlineEditConditionToggle)) bool bOverride_SolImp = false; /** @brief Constraint solver impedance (dmin, dmax, width). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Equality|Physics", meta=(EditCondition="bOverride_SolImp")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Equality|Physics", meta=(EditCondition="bOverride_SolImp")) TArray SolImp; // --- Type Specific Parameters --- /** @brief Override toggle for Anchor. Used for Connect and Weld. */ - UPROPERTY(EditAnywhere, Category = "Mj Equality|Parameters", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Equality|Parameters", meta=(InlineEditConditionToggle)) bool bOverride_Anchor = false; /** @brief Position of the connection point, in body2 frame. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Equality|Parameters", meta=(EditCondition="bOverride_Anchor")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Equality|Parameters", meta=(EditCondition="bOverride_Anchor")) FVector Anchor = FVector::ZeroVector; /** @brief Override toggle for RelPose. Used for Weld. */ - UPROPERTY(EditAnywhere, Category = "Mj Equality|Parameters", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Equality|Parameters", meta=(InlineEditConditionToggle)) bool bOverride_RelPose = false; /** @brief Relative position and orientation of body1 in body2 frame. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Equality|Parameters", meta=(EditCondition="bOverride_RelPose")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Equality|Parameters", meta=(EditCondition="bOverride_RelPose")) FTransform RelPose = FTransform::Identity; /** @brief Override toggle for PolyCoef. Used for Joint and Tendon. */ - UPROPERTY(EditAnywhere, Category = "Mj Equality|Parameters", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Equality|Parameters", meta=(InlineEditConditionToggle)) bool bOverride_PolyCoef = false; /** @brief Coefficients of the cubic polynomial: y = a + b*x + c*x^2 + d*x^3. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Equality|Parameters", meta=(EditCondition="bOverride_PolyCoef")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Equality|Parameters", meta=(EditCondition="bOverride_PolyCoef")) TArray PolyCoef; /** @brief Override toggle for TorqueScale. Used for Weld only. */ - UPROPERTY(EditAnywhere, Category = "Mj Equality|Parameters", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Equality|Parameters", meta=(InlineEditConditionToggle)) bool bOverride_TorqueScale = false; /** @brief Torque-to-force scaling ratio for weld constraint (mjSpec weld data[7]). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Equality|Parameters", meta=(EditCondition="bOverride_TorqueScale", EditConditionHides)) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Equality|Parameters", meta=(EditCondition="bOverride_TorqueScale", EditConditionHides)) float TorqueScale = 1.0f; }; diff --git a/Source/URLab/Public/MuJoCo/Components/Defaults/MjDefault.h b/Source/URLab/Public/MuJoCo/Components/Defaults/MjDefault.h index 65e5af8..0956192 100644 --- a/Source/URLab/Public/MuJoCo/Components/Defaults/MjDefault.h +++ b/Source/URLab/Public/MuJoCo/Components/Defaults/MjDefault.h @@ -56,11 +56,11 @@ class URLAB_API UMjDefault : public UMjComponent UMjDefault(); /** @brief Name of the default class. If empty, these defaults apply to the global scope. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Default") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Default") FString ClassName; /** @brief Name of the parent default class for inheritance. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Default") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Default") FString ParentClassName; /** @@ -70,6 +70,10 @@ class URLAB_API UMjDefault : public UMjComponent */ void ImportFromXml(const class FXmlNode* Node); +#if WITH_EDITOR + virtual void PostEditChangeProperty(struct FPropertyChangedEvent& PropertyChangedEvent) override; +#endif + /** * @brief Exports default settings to a MuJoCo mjsDefault structure. * @param def Pointer to the mjsDefault structure to populate. diff --git a/Source/URLab/Public/MuJoCo/Components/Geometry/MjGeom.h b/Source/URLab/Public/MuJoCo/Components/Geometry/MjGeom.h index 33293a2..5392c0a 100644 --- a/Source/URLab/Public/MuJoCo/Components/Geometry/MjGeom.h +++ b/Source/URLab/Public/MuJoCo/Components/Geometry/MjGeom.h @@ -90,6 +90,9 @@ class URLAB_API UMjGeom : public UMjComponent /** @brief Returns the built-in visualizer mesh if it exists. */ virtual class UStaticMeshComponent* GetVisualizerMesh() const { return nullptr; } + /** @brief Apply a material to the visual mesh. Override in subclasses with direct member access. */ + virtual void ApplyOverrideMaterial(class UMaterialInterface* Material); + /** @brief The runtime view of the MuJoCo geom. Valid only after Bind() is called. */ GeomView m_GeomView; @@ -145,7 +148,7 @@ class URLAB_API UMjGeom : public UMjComponent * Used by ShouldOverrideSize() to distinguish "inherit-from-default" intent * (imported, bOverride_Size=false) from "use my UE scale" intent (user-authored). */ - UPROPERTY(VisibleAnywhere, Category = "MuJoCo|Geom") + UPROPERTY() bool bWasImported = false; /** @@ -160,8 +163,8 @@ class URLAB_API UMjGeom : public UMjComponent bool ShouldOverrideSize() const { return bOverride_Size || !bWasImported; } /** @brief Name of the mesh asset if Type is Mesh. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom") - FString MeshName; + UPROPERTY(VisibleAnywhere, BlueprintReadOnly, Category = "MuJoCo|Geom") + FString MeshName; /** @brief Legacy: use complex collision mesh. Hidden — use "Decompose Mesh" button instead. * Still used internally by QuickConvert and as import/compile fallback. */ @@ -175,7 +178,7 @@ class URLAB_API UMjGeom : public UMjComponent float CoACDThreshold = 0.05f; /** @brief True if this geom was created by CoACD decomposition of another geom. */ - UPROPERTY(VisibleAnywhere, Category = "MuJoCo|Geom") + UPROPERTY() bool bIsDecomposedHull = false; /** @brief True if this geom's mesh was decomposed into hull sub-geoms. @@ -184,11 +187,11 @@ class URLAB_API UMjGeom : public UMjComponent bool bDisabledByDecomposition = false; /** @brief Runs CoACD decomposition on this geom's mesh and creates persistent hull sub-geom components. */ - UFUNCTION(CallInEditor, Category = "MuJoCo|Geom", meta=(DisplayName="Decompose Mesh")) + UFUNCTION(BlueprintCallable, Category = "MuJoCo|Geom") void DecomposeMesh(); /** @brief Removes all hull sub-geoms created by decomposition and re-enables this geom. */ - UFUNCTION(CallInEditor, Category = "MuJoCo|Geom", meta=(DisplayName="Remove Decomposition")) + UFUNCTION(BlueprintCallable, Category = "MuJoCo|Geom") void RemoveDecomposition(); /** @brief Override toggle for FromTo. */ @@ -211,13 +214,18 @@ class URLAB_API UMjGeom : public UMjComponent UPROPERTY() bool bFromToResolvedHalfLength = false; - /** @brief Optional MuJoCo class name to inherit defaults from. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom") + /** @brief Optional MuJoCo class name to inherit defaults from (string fallback). */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom", meta=(GetOptions="GetDefaultClassOptions")) FString MjClassName; virtual FString GetMjClassName() const override { return MjClassName; } +#if WITH_EDITOR + UFUNCTION() + TArray GetDefaultClassOptions() const; +#endif + /** @brief Optional MuJoCo material name for visual properties. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom") + UPROPERTY(VisibleAnywhere, BlueprintReadOnly, Category = "MuJoCo|Geom") FString MaterialName; /** @brief Resolves MaterialName through the default class chain. Returns empty if none found. */ @@ -328,7 +336,7 @@ class URLAB_API UMjGeom : public UMjComponent * @brief Number of size parameters explicitly provided in XML. * Used to support partial inheritance (e.g. overriding radius but keeping length). */ - UPROPERTY(VisibleAnywhere, Category = "MuJoCo|Geom") + UPROPERTY() int32 SizeParamsCount = 0; // --- Visuals (with override toggle) --- @@ -341,8 +349,14 @@ class URLAB_API UMjGeom : public UMjComponent UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom|Visual", meta=(EditCondition="bOverride_Rgba")) FLinearColor Rgba = FLinearColor(0.5f, 0.5f, 0.5f, 1.0f); - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom") - UMjDefault* m_RefDefault; + /** @brief Optional Unreal material override for primitive visualizer meshes (Box/Sphere/Cylinder). */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Geom|Visual", + 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 Registers this geom to the MuJoCo spec. diff --git a/Source/URLab/Public/MuJoCo/Components/Geometry/MjMeshGeom.h b/Source/URLab/Public/MuJoCo/Components/Geometry/MjMeshGeom.h new file mode 100644 index 0000000..d33b5bc --- /dev/null +++ b/Source/URLab/Public/MuJoCo/Components/Geometry/MjMeshGeom.h @@ -0,0 +1,40 @@ +// 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. + +#pragma once + +#include "CoreMinimal.h" +#include "MuJoCo/Components/Geometry/MjGeom.h" +#include "MjMeshGeom.generated.h" + +/** + * @class UMjMeshGeom + * @brief Mesh geometry component. Thin wrapper around UMjGeom that sets the type to Mesh. + */ +UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent)) +class URLAB_API UMjMeshGeom : public UMjGeom +{ + GENERATED_BODY() + +public: + UMjMeshGeom(); +}; diff --git a/Source/URLab/Public/MuJoCo/Components/Geometry/MjSite.h b/Source/URLab/Public/MuJoCo/Components/Geometry/MjSite.h index 1f43371..712bb2e 100644 --- a/Source/URLab/Public/MuJoCo/Components/Geometry/MjSite.h +++ b/Source/URLab/Public/MuJoCo/Components/Geometry/MjSite.h @@ -26,6 +26,7 @@ #include "Components/SceneComponent.h" #include "mujoco/mujoco.h" #include "MuJoCo/Components/MjComponent.h" +#include "MuJoCo/Components/Defaults/MjDefault.h" #include "MjSite.generated.h" /** @@ -98,10 +99,23 @@ class URLAB_API UMjSite : public UMjComponent UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Site") FVector Size = FVector(0.01f); - /** @brief Optional MuJoCo class name to inherit defaults from. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Site") + /** @brief Optional MuJoCo class name to inherit defaults from (string fallback). */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Site", meta=(GetOptions="GetDefaultClassOptions")) FString MjClassName; - virtual FString GetMjClassName() const override { return MjClassName; } + +#if WITH_EDITOR + UFUNCTION() + TArray GetDefaultClassOptions() const; +#endif + + /** @brief Reference to a UMjDefault component for default class inheritance. */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Site") + UMjDefault* DefaultClass = nullptr; + + virtual FString GetMjClassName() const override + { + return MjClassName; + } // --- Visuals --- /** @brief RGBA Color of the site visualization. */ diff --git a/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjBox.h b/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjBox.h index 25f4d33..8dd4299 100644 --- a/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjBox.h +++ b/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjBox.h @@ -54,5 +54,6 @@ class URLAB_API UMjBox : public UMjGeom virtual void SetGeomVisibility(bool bNewVisibility) override; virtual class UStaticMeshComponent* GetVisualizerMesh() const override { const_cast(this)->EnsureVisualizerMesh(); return VisualizerMesh; } + virtual void ApplyOverrideMaterial(class UMaterialInterface* Material) override; void EnsureVisualizerMesh(); }; diff --git a/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjCylinder.h b/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjCylinder.h index 2c306a7..d2677de 100644 --- a/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjCylinder.h +++ b/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjCylinder.h @@ -62,5 +62,6 @@ class URLAB_API UMjCylinder : public UMjGeom #endif virtual class UStaticMeshComponent* GetVisualizerMesh() const override { const_cast(this)->EnsureVisualizerMesh(); return VisualizerMesh; } + virtual void ApplyOverrideMaterial(class UMaterialInterface* Material) override; void EnsureVisualizerMesh(); }; diff --git a/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjSphere.h b/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjSphere.h index 97a2fe0..326b75e 100644 --- a/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjSphere.h +++ b/Source/URLab/Public/MuJoCo/Components/Geometry/Primitives/MjSphere.h @@ -58,5 +58,6 @@ class URLAB_API UMjSphere : public UMjGeom #endif virtual class UStaticMeshComponent* GetVisualizerMesh() const override { const_cast(this)->EnsureVisualizerMesh(); return VisualizerMesh; } + virtual void ApplyOverrideMaterial(class UMaterialInterface* Material) override; void EnsureVisualizerMesh(); }; diff --git a/Source/URLab/Public/MuJoCo/Components/Joints/MjJoint.h b/Source/URLab/Public/MuJoCo/Components/Joints/MjJoint.h index 1894d17..b5c77cb 100644 --- a/Source/URLab/Public/MuJoCo/Components/Joints/MjJoint.h +++ b/Source/URLab/Public/MuJoCo/Components/Joints/MjJoint.h @@ -26,6 +26,7 @@ #include "MuJoCo/Utils/MjBind.h" #include "MuJoCo/Core/MjTypes.h" #include "MuJoCo/Components/MjComponent.h" +#include "MuJoCo/Components/Defaults/MjDefault.h" #include "MuJoCo/Utils/MjOrientationUtils.h" #include "MjJoint.generated.h" @@ -135,11 +136,23 @@ class URLAB_API UMjJoint : public UMjComponent /** @brief Gets the full prefixed name of this joint as it appears in the compiled MuJoCo model. */ virtual FString GetMjName() const override; - /** @brief Optional MuJoCo class name to inherit defaults from. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Joint") + /** @brief Optional MuJoCo class name to inherit defaults from (string fallback). */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(GetOptions="GetDefaultClassOptions")) FString MjClassName; - virtual FString GetMjClassName() const override { return MjClassName; } +#if WITH_EDITOR + UFUNCTION() + TArray GetDefaultClassOptions() const; +#endif + + /** @brief Reference to a UMjDefault component for default class inheritance. */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint") + class UMjDefault* DefaultClass = nullptr; + + virtual FString GetMjClassName() const override + { + return MjClassName; + } // --- Editor-time resolved accessors --- // Walk the default class chain to resolve effective property values. @@ -159,135 +172,135 @@ class URLAB_API UMjJoint : public UMjComponent bool GetResolvedLimited() const; /** @brief Override toggle for Type. */ - UPROPERTY(EditAnywhere, Category = "Mj Joint", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) bool bOverride_Type = false; /** @brief The type of joint (Hinge, Slide, Ball, Free). Default: Hinge (MuJoCo builtin). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Joint", meta=(EditCondition="bOverride_Type")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_Type")) EMjJointType Type = EMjJointType::Hinge; /** @brief Override toggle for Axis. */ - UPROPERTY(EditAnywhere, Category = "Mj Joint", meta=(InlineEditConditionToggle)) + 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 = "Mj Joint", meta=(EditCondition="bOverride_Axis")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_Axis")) FVector Axis = FVector(0.0f, 0.0f, 1.0f); /** @brief Override toggle for Ref. */ - UPROPERTY(EditAnywhere, Category = "Mj Joint", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint", meta=(InlineEditConditionToggle)) bool bOverride_Ref = false; /** @brief Value at reference configuration (qpos0). Radians for hinge, cm for slide. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Joint", meta=(EditCondition="bOverride_Ref", ToolTip="Reference position (qpos0). Radians for hinge joints, centimeters for slide joints.")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint", meta=(EditCondition="bOverride_Ref", ToolTip="Reference position (qpos0). Radians for hinge joints, centimeters for slide joints.")) float Ref = 0.0f; // --- Physics Properties (with override toggles) --- /** @brief Override toggle for Stiffness. */ - UPROPERTY(EditAnywhere, Category = "Mj Joint|Physics", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint|Physics", meta=(InlineEditConditionToggle)) bool bOverride_Stiffness = false; /** @brief Joint stiffness coefficients [linear, poly0, poly1]. Polynomial spring: F = -x*(linear + poly0*x + poly1*x²). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Joint|Physics", meta=(EditCondition="bOverride_Stiffness")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint|Physics", meta=(EditCondition="bOverride_Stiffness")) TArray Stiffness = {0.0f}; /** @brief Override toggle for SpringRef. */ - UPROPERTY(EditAnywhere, Category = "Mj Joint|Physics", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint|Physics", meta=(InlineEditConditionToggle)) bool bOverride_SpringRef = false; /** @brief Reference position for the spring. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Joint|Physics", meta=(EditCondition="bOverride_SpringRef")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint|Physics", meta=(EditCondition="bOverride_SpringRef")) float SpringRef = 0.0f; /** @brief Override toggle for Damping. */ - UPROPERTY(EditAnywhere, Category = "Mj Joint|Physics", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint|Physics", meta=(InlineEditConditionToggle)) bool bOverride_Damping = false; /** @brief Damping coefficients [linear, poly0, poly1]. Polynomial damper: F = -v*(linear + poly0*|v| + poly1*v²). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Joint|Physics", meta=(EditCondition="bOverride_Damping")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint|Physics", meta=(EditCondition="bOverride_Damping")) TArray Damping = {0.0f}; /** @brief Override toggle for Armature. */ - UPROPERTY(EditAnywhere, Category = "Mj Joint|Physics", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint|Physics", meta=(InlineEditConditionToggle)) bool bOverride_Armature = false; /** @brief Armature inertia/mass added to the joint. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Joint|Physics", meta=(EditCondition="bOverride_Armature")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint|Physics", meta=(EditCondition="bOverride_Armature")) float Armature = 0.0f; /** @brief Override toggle for FrictionLoss. */ - UPROPERTY(EditAnywhere, Category = "Mj Joint|Physics", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint|Physics", meta=(InlineEditConditionToggle)) bool bOverride_FrictionLoss = false; /** @brief Friction loss (dry friction). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Joint|Physics", meta=(EditCondition="bOverride_FrictionLoss")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint|Physics", meta=(EditCondition="bOverride_FrictionLoss")) float FrictionLoss = 0.0f; // --- Limits (with override toggles) --- /** @brief Override toggle for bLimited. */ - UPROPERTY(EditAnywhere, Category = "Mj Joint|Limits", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint|Limits", meta=(InlineEditConditionToggle)) bool bOverride_Limited = false; /** @brief Whether the joint limits are enabled. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Joint|Limits", meta=(EditCondition="bOverride_Limited")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint|Limits", meta=(EditCondition="bOverride_Limited")) bool bLimited = false; /** @brief Override toggle for Range. */ - UPROPERTY(EditAnywhere, Category = "Mj Joint|Limits", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint|Limits", meta=(InlineEditConditionToggle)) bool bOverride_Range = false; /** @brief Joint limits (min, max). Only active if bLimited is true. Radians for hinge, cm for slide. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Joint|Limits", meta=(EditCondition="bOverride_Range", ToolTip="Joint range limits [min, max]. Radians for hinge joints, centimeters for slide joints.")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint|Limits", meta=(EditCondition="bOverride_Range", ToolTip="Joint range limits [min, max]. Radians for hinge joints, centimeters for slide joints.")) TArray Range = {0.0f, 0.0f}; - UPROPERTY(EditAnywhere, Category = "Mj Joint|Limits", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint|Limits", meta=(InlineEditConditionToggle)) bool bOverride_ActuatorFrcRange = false; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Joint|ActuatorFrcRange", meta=(EditCondition="bOverride_ActuatorFrcRange")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint|ActuatorFrcRange", meta=(EditCondition="bOverride_ActuatorFrcRange")) TArray ActuatorFrcRange = {0.0f, 0.0f}; /** @brief Override toggle for Margin. */ - UPROPERTY(EditAnywhere, Category = "Mj Joint|Limits", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint|Limits", meta=(InlineEditConditionToggle)) bool bOverride_Margin = false; /** @brief Constraint margin. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Joint|Limits", meta=(EditCondition="bOverride_Margin")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint|Limits", meta=(EditCondition="bOverride_Margin")) float Margin = 0.0f; // --- Solver Parameters (with override toggles) --- /** @brief Override toggle for SolRefLimit. */ - UPROPERTY(EditAnywhere, Category = "Mj Joint|Solving", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint|Solving", meta=(InlineEditConditionToggle)) bool bOverride_SolRefLimit = false; /** @brief Constraint solver reference parameter for limits (timeconst, dampratio). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Joint|Solving", meta=(EditCondition="bOverride_SolRefLimit")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint|Solving", meta=(EditCondition="bOverride_SolRefLimit")) TArray SolRefLimit = {0.02f, 1.0f}; /** @brief Override toggle for SolImpLimit. */ - UPROPERTY(EditAnywhere, Category = "Mj Joint|Solving", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint|Solving", meta=(InlineEditConditionToggle)) bool bOverride_SolImpLimit = false; /** @brief Constraint solver impedance parameter for limits (dmin, dmax, width). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Joint|Solving", meta=(EditCondition="bOverride_SolImpLimit")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint|Solving", meta=(EditCondition="bOverride_SolImpLimit")) TArray SolImpLimit = {0.9f, 0.95f, 0.001f}; /** @brief Override toggle for SolRefFriction. */ - UPROPERTY(EditAnywhere, Category = "Mj Joint|Solving", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint|Solving", meta=(InlineEditConditionToggle)) bool bOverride_SolRefFriction = false; /** @brief Constraint solver reference parameter for friction (timeconst, dampratio). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Joint|Solving", meta=(EditCondition="bOverride_SolRefFriction")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint|Solving", meta=(EditCondition="bOverride_SolRefFriction")) TArray SolRefFriction = {0.02f, 1.0f}; /** @brief Override toggle for SolImpFriction. */ - UPROPERTY(EditAnywhere, Category = "Mj Joint|Solving", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Joint|Solving", meta=(InlineEditConditionToggle)) bool bOverride_SolImpFriction = false; /** @brief Constraint solver impedance parameter for friction. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Joint|Solving", meta=(EditCondition="bOverride_SolImpFriction")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Joint|Solving", meta=(EditCondition="bOverride_SolImpFriction")) TArray SolImpFriction = {0.9f, 0.95f, 0.001f}; // --- Group --- diff --git a/Source/URLab/Public/MuJoCo/Components/Keyframes/MjKeyframe.h b/Source/URLab/Public/MuJoCo/Components/Keyframes/MjKeyframe.h index 2126358..00148f3 100644 --- a/Source/URLab/Public/MuJoCo/Components/Keyframes/MjKeyframe.h +++ b/Source/URLab/Public/MuJoCo/Components/Keyframes/MjKeyframe.h @@ -61,56 +61,56 @@ class URLAB_API UMjKeyframe : public UMjComponent void ImportFromXml(const class FXmlNode* Node); /** @brief Simulation time for this keyframe. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Keyframe") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Keyframe") float Time = 0.0f; // --- State Vectors --- /** @brief Override toggle for Qpos. */ - UPROPERTY(EditAnywhere, Category = "Mj Keyframe", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Keyframe", meta=(InlineEditConditionToggle)) bool bOverride_Qpos = false; /** @brief Joint positions. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Keyframe", meta=(EditCondition="bOverride_Qpos")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Keyframe", meta=(EditCondition="bOverride_Qpos")) TArray Qpos; /** @brief Override toggle for Qvel. */ - UPROPERTY(EditAnywhere, Category = "Mj Keyframe", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Keyframe", meta=(InlineEditConditionToggle)) bool bOverride_Qvel = false; /** @brief Joint velocities. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Keyframe", meta=(EditCondition="bOverride_Qvel")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Keyframe", meta=(EditCondition="bOverride_Qvel")) TArray Qvel; /** @brief Override toggle for Act. */ - UPROPERTY(EditAnywhere, Category = "Mj Keyframe", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Keyframe", meta=(InlineEditConditionToggle)) bool bOverride_Act = false; /** @brief Actuator activations. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Keyframe", meta=(EditCondition="bOverride_Act")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Keyframe", meta=(EditCondition="bOverride_Act")) TArray Act; /** @brief Override toggle for Ctrl. */ - UPROPERTY(EditAnywhere, Category = "Mj Keyframe", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Keyframe", meta=(InlineEditConditionToggle)) bool bOverride_Ctrl = false; /** @brief Actuator controls. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Keyframe", meta=(EditCondition="bOverride_Ctrl")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Keyframe", meta=(EditCondition="bOverride_Ctrl")) TArray Ctrl; /** @brief Override toggle for Mpos. */ - UPROPERTY(EditAnywhere, Category = "Mj Keyframe", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Keyframe", meta=(InlineEditConditionToggle)) bool bOverride_Mpos = false; /** @brief Mocap body positions. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Keyframe", meta=(EditCondition="bOverride_Mpos")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Keyframe", meta=(EditCondition="bOverride_Mpos")) TArray Mpos; /** @brief Override toggle for Mquat. */ - UPROPERTY(EditAnywhere, Category = "Mj Keyframe", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Keyframe", meta=(InlineEditConditionToggle)) bool bOverride_Mquat = false; /** @brief Mocap body quaternions. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Keyframe", meta=(EditCondition="bOverride_Mquat")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Keyframe", meta=(EditCondition="bOverride_Mquat")) TArray Mquat; }; diff --git a/Source/URLab/Public/MuJoCo/Components/MjComponent.h b/Source/URLab/Public/MuJoCo/Components/MjComponent.h index 822d631..9c2ef78 100644 --- a/Source/URLab/Public/MuJoCo/Components/MjComponent.h +++ b/Source/URLab/Public/MuJoCo/Components/MjComponent.h @@ -158,19 +158,24 @@ class URLAB_API UMjComponent : public USceneComponent, public IMjSpecElement UFUNCTION(BlueprintCallable, Category = "MuJoCo|Base") int GetMjID() const { return m_ID; } - /** @brief If true, this component is used as a template in a block and should be ignored by runtime discovery. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo") + /** @brief If true, this component is a template in a block. Auto-resolved in Setup(). */ + UPROPERTY() bool bIsDefault = false; /** @brief Gets the full prefixed name of this component as it appears in the compiled MuJoCo model. */ UFUNCTION(BlueprintCallable, Category = "MuJoCo|Base") virtual FString GetMjName() const; - /** @brief The original name of this element in the MuJoCo Spec (from XML). - * Stable for cross-referencing, unlike Unreal's GetName() which can vary. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo") + /** @brief The original name of this element in the MuJoCo Spec (from XML). */ + UPROPERTY() FString MjName; +#if WITH_EDITOR + /** Returns names of sibling components of the given class in the same Blueprint SCS tree. + * Static so non-UMjComponent classes (ContactPair, etc.) can also use it. */ + static TArray GetSiblingComponentOptions(const UObject* CallerComponent, UClass* FilterClass, bool bIncludeDefaults = false); +#endif + protected: /** Resolves the MuJoCo default class for a given class name. * Looks up ClassName; falls back to the spec's global default. */ diff --git a/Source/URLab/Public/MuJoCo/Components/Physics/MjContactExclude.h b/Source/URLab/Public/MuJoCo/Components/Physics/MjContactExclude.h index d0dfc65..3d6cf86 100644 --- a/Source/URLab/Public/MuJoCo/Components/Physics/MjContactExclude.h +++ b/Source/URLab/Public/MuJoCo/Components/Physics/MjContactExclude.h @@ -46,15 +46,15 @@ class URLAB_API UMjContactExclude : public USceneComponent, public IMjSpecElemen UMjContactExclude(); /** @brief Name of the contact exclusion (optional). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Contact Exclude") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Contact Exclude") FString Name; /** @brief Name of the first body in the exclusion pair (required). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Contact Exclude") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Contact Exclude", meta=(GetOptions="GetBodyOptions")) FString Body1; /** @brief Name of the second body in the exclusion pair (required). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Contact Exclude") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Contact Exclude", meta=(GetOptions="GetBodyOptions")) FString Body2; /** @@ -78,6 +78,11 @@ class URLAB_API UMjContactExclude : public USceneComponent, public IMjSpecElemen virtual void Bind(mjModel* model, mjData* data, const FString& Prefix = TEXT("")) override; +#if WITH_EDITOR + UFUNCTION() + TArray GetBodyOptions() const; +#endif + protected: /** @brief Called when the game starts. */ virtual void BeginPlay() override; diff --git a/Source/URLab/Public/MuJoCo/Components/Physics/MjContactPair.h b/Source/URLab/Public/MuJoCo/Components/Physics/MjContactPair.h index af57b0f..3420499 100644 --- a/Source/URLab/Public/MuJoCo/Components/Physics/MjContactPair.h +++ b/Source/URLab/Public/MuJoCo/Components/Physics/MjContactPair.h @@ -46,39 +46,39 @@ class URLAB_API UMjContactPair : public USceneComponent, public IMjSpecElement UMjContactPair(); /** @brief Name of the contact pair (optional). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Contact Pair") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Contact Pair") FString Name; /** @brief Name of the first geom in the contact pair (required). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Contact Pair") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Contact Pair", meta=(GetOptions="GetGeomOptions")) FString Geom1; /** @brief Name of the second geom in the contact pair (required). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Contact Pair") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Contact Pair", meta=(GetOptions="GetGeomOptions")) FString Geom2; /** @brief Contact dimensionality (1-6). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Contact Pair") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Contact Pair") int Condim = 3; /** @brief Friction coefficients (sliding, torsional, rolling). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Contact Pair") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Contact Pair") TArray Friction; /** @brief Solver reference time/damping for contact. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Contact Pair") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Contact Pair") TArray Solref; /** @brief Solver impedance for contact. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Contact Pair") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Contact Pair") TArray Solimp; /** @brief Distance threshold below which contacts are detected. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Contact Pair") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Contact Pair") float Gap = 0.0f; /** @brief Safety margin for collision detection. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Contact Pair") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Contact Pair") float Margin = 0.0f; /** @@ -102,6 +102,11 @@ class URLAB_API UMjContactPair : public USceneComponent, public IMjSpecElement virtual void Bind(mjModel* model, mjData* data, const FString& Prefix = TEXT("")) override; +#if WITH_EDITOR + UFUNCTION() + TArray GetGeomOptions() const; +#endif + protected: /** @brief Called when the game starts. */ virtual void BeginPlay() override; diff --git a/Source/URLab/Public/MuJoCo/Components/Sensors/MjSensor.h b/Source/URLab/Public/MuJoCo/Components/Sensors/MjSensor.h index dfe6f2c..6521a7c 100644 --- a/Source/URLab/Public/MuJoCo/Components/Sensors/MjSensor.h +++ b/Source/URLab/Public/MuJoCo/Components/Sensors/MjSensor.h @@ -28,6 +28,7 @@ #include "mujoco/mujoco.h" #include "MuJoCo/Core/Spec/MjSpecElement.h" #include "MuJoCo/Components/MjComponent.h" +#include "MuJoCo/Components/Defaults/MjDefault.h" #include "MuJoCo/Utils/MjBind.h" #include "MjSensor.generated.h" @@ -159,60 +160,68 @@ class URLAB_API UMjSensor : public UMjComponent UMjSensor(); /** @brief The type of sensor (Touch, Accelerometer, JointPos, etc.). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Sensor") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor") EMjSensorType Type; /** @brief Name of the object this sensor is attached to or referencing (e.g. site name, joint name). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Sensor") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor", meta=(GetOptions="GetTargetNameOptions")) FString TargetName; /** @brief Optional: Referenced object name (e.g. for reftype/refname pairs in MuJoCo). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Sensor") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor", meta=(GetOptions="GetReferenceNameOptions")) FString ReferenceName; /** @brief Dimension of the sensor output. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Sensor") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor") int Dim; /** @brief Override toggle for Noise. */ - UPROPERTY(EditAnywhere, Category = "Mj Sensor", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Sensor", meta=(InlineEditConditionToggle)) bool bOverride_Noise = false; /** @brief Noise standard deviation added to the sensor reading. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Sensor", meta=(EditCondition="bOverride_Noise")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor", meta=(EditCondition="bOverride_Noise")) float Noise = 0.0f; /** @brief Override toggle for Cutoff. */ - UPROPERTY(EditAnywhere, Category = "Mj Sensor", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Sensor", meta=(InlineEditConditionToggle)) bool bOverride_Cutoff = false; /** @brief Cutoff frequency for the sensor filter. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Sensor", meta=(EditCondition="bOverride_Cutoff")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor", meta=(EditCondition="bOverride_Cutoff")) float Cutoff = 0.0f; /** @brief Output address override for user sensors (mjsSensor::adr). -1 = let MuJoCo assign. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Sensor") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor") int32 UserAdr = -1; - /** @brief Optional MuJoCo class name to inherit defaults from. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Sensor") + /** @brief Optional MuJoCo class name to inherit defaults from (string fallback). */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor", meta=(GetOptions="GetDefaultClassOptions")) FString MjClassName; - virtual FString GetMjClassName() const override { return MjClassName; } + + /** @brief Reference to a UMjDefault component for default class inheritance. */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor") + UMjDefault* DefaultClass = nullptr; + + virtual FString GetMjClassName() const override + { + return MjClassName; + } /** @brief Type of object this sensor is attached to (e.g. Site, Joint, Body). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Sensor") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor") EMjObjType ObjType; /** @brief Type of reference object (e.g. Camera for camprojection, Body/Geom for distance). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Sensor") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor") EMjObjType RefType; /** @brief Integer parameters for sensor configuration (e.g. rangefinder flags, contact flags). Maps to sensor->intprm. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Sensor") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor") TArray IntParams; /** @brief User data for custom sensors. Maps to sensor->userdata. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Sensor") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Sensor") TArray UserParams; public: @@ -252,6 +261,15 @@ class URLAB_API UMjSensor : public UMjComponent /** @brief Gets the full prefixed name of this sensor as it appears in the compiled MuJoCo model. */ virtual FString GetMjName() const override; +#if WITH_EDITOR + UFUNCTION() + TArray GetTargetNameOptions() const; + UFUNCTION() + TArray GetReferenceNameOptions() const; + UFUNCTION() + TArray GetDefaultClassOptions() const; +#endif + /** @brief The runtime view of the MuJoCo sensor. */ SensorView m_SensorView; diff --git a/Source/URLab/Public/MuJoCo/Components/Tendons/MjTendon.h b/Source/URLab/Public/MuJoCo/Components/Tendons/MjTendon.h index 80cfc39..bb55625 100644 --- a/Source/URLab/Public/MuJoCo/Components/Tendons/MjTendon.h +++ b/Source/URLab/Public/MuJoCo/Components/Tendons/MjTendon.h @@ -27,6 +27,7 @@ #include "mujoco/mjspec.h" #include "MuJoCo/Utils/MjBind.h" #include "MuJoCo/Components/MjComponent.h" +#include "MuJoCo/Components/Defaults/MjDefault.h" #include "MjTendon.generated.h" @@ -57,21 +58,21 @@ struct FMjTendonWrap GENERATED_BODY() /** @brief Type of this wrap entry. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon Wrap") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Wrap") EMjTendonWrapType Type = EMjTendonWrapType::Joint; /** * @brief Name of the target joint, site, or geom. * Ignored for Pulley wraps. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon Wrap") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Wrap") FString TargetName; /** * @brief Gear coefficient for Joint wraps (how much of joint movement maps to tendon length). * Ignored for Site, Geom, Pulley wraps. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon Wrap") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Wrap") float Coef = 1.0f; /** @@ -79,7 +80,7 @@ struct FMjTendonWrap * The side-site disambiguates which side of the cylinder to wrap around. * Ignored for Joint, Site, Pulley wraps. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon Wrap") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Wrap") FString SideSite; /** @@ -87,7 +88,7 @@ struct FMjTendonWrap * Divides the tendon's effective length change; use for compound pulleys. * Ignored for Joint, Site, Geom wraps. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon Wrap") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Wrap") float Divisor = 1.0f; }; @@ -171,161 +172,174 @@ class URLAB_API UMjTendon : public UMjComponent * For fixed tendons: add Joint wraps. * For spatial tendons: add Site, Geom, and/or Pulley wraps. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon") + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon") TArray Wraps; - /** @brief Optional MuJoCo default class name to inherit from. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon") + /** @brief Optional MuJoCo default class name to inherit from (string fallback). */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon", meta=(GetOptions="GetDefaultClassOptions")) FString MjClassName; - virtual FString GetMjClassName() const override { return MjClassName; } + + /** @brief Reference to a UMjDefault component for default class inheritance. */ + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon") + UMjDefault* DefaultClass = nullptr; + + virtual FString GetMjClassName() const override + { + return MjClassName; + } + +#if WITH_EDITOR + UFUNCTION() + TArray GetDefaultClassOptions() const; +#endif // --- Physics Properties --- /** @brief Override toggle for Stiffness. */ - UPROPERTY(EditAnywhere, Category = "Mj Tendon|Physics", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon|Physics", meta=(InlineEditConditionToggle)) bool bOverride_Stiffness = false; /** @brief Tendon stiffness coefficients [linear, poly0, poly1]. Polynomial spring: F = -x*(linear + poly0*x + poly1*x²). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon|Physics", meta=(EditCondition="bOverride_Stiffness")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Physics", meta=(EditCondition="bOverride_Stiffness")) TArray Stiffness = {0.0f}; /** @brief Override toggle for SpringLength. */ - UPROPERTY(EditAnywhere, Category = "Mj Tendon|Physics", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon|Physics", meta=(InlineEditConditionToggle)) bool bOverride_SpringLength = false; /** * @brief Spring resting length [min, max]. Use (-1, -1) to compute from qpos_spring. * For fixed tendons this is usually a single value; store in X, leave Y as -1. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon|Physics", meta=(EditCondition="bOverride_SpringLength")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Physics", meta=(EditCondition="bOverride_SpringLength")) TArray SpringLength; /** @brief Override toggle for Damping. */ - UPROPERTY(EditAnywhere, Category = "Mj Tendon|Physics", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon|Physics", meta=(InlineEditConditionToggle)) bool bOverride_Damping = false; /** @brief Damping coefficients [linear, poly0, poly1]. Polynomial damper: F = -v*(linear + poly0*|v| + poly1*v²). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon|Physics", meta=(EditCondition="bOverride_Damping")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Physics", meta=(EditCondition="bOverride_Damping")) TArray Damping = {0.0f}; /** @brief Override toggle for FrictionLoss. */ - UPROPERTY(EditAnywhere, Category = "Mj Tendon|Physics", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon|Physics", meta=(InlineEditConditionToggle)) bool bOverride_FrictionLoss = false; /** @brief Friction loss (dry friction applied along the tendon). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon|Physics", meta=(EditCondition="bOverride_FrictionLoss")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Physics", meta=(EditCondition="bOverride_FrictionLoss")) float FrictionLoss = 0.0f; /** @brief Override toggle for Armature. */ - UPROPERTY(EditAnywhere, Category = "Mj Tendon|Physics", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon|Physics", meta=(InlineEditConditionToggle)) bool bOverride_Armature = false; /** @brief Inertia associated with the tendon velocity. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon|Physics", meta=(EditCondition="bOverride_Armature")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Physics", meta=(EditCondition="bOverride_Armature")) float Armature = 0.0f; // --- Limits --- /** @brief Override toggle for bLimited. */ - UPROPERTY(EditAnywhere, Category = "Mj Tendon|Limits", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon|Limits", meta=(InlineEditConditionToggle)) bool bOverride_Limited = false; /** @brief Whether the tendon has length limits. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon|Limits", meta=(EditCondition="bOverride_Limited")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Limits", meta=(EditCondition="bOverride_Limited")) bool bLimited = false; /** @brief Override toggle for Range. */ - UPROPERTY(EditAnywhere, Category = "Mj Tendon|Limits", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon|Limits", meta=(InlineEditConditionToggle)) bool bOverride_Range = false; /** @brief Tendon length limits [min, max]. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon|Limits", meta=(EditCondition="bOverride_Range")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Limits", meta=(EditCondition="bOverride_Range")) TArray Range = {0.0f, 0.0f}; /** @brief Override toggle for Margin. */ - UPROPERTY(EditAnywhere, Category = "Mj Tendon|Limits", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon|Limits", meta=(InlineEditConditionToggle)) bool bOverride_Margin = false; /** @brief Margin for limit detection. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon|Limits", meta=(EditCondition="bOverride_Margin")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Limits", meta=(EditCondition="bOverride_Margin")) float Margin = 0.0f; // --- Actuator Limits --- /** @brief Override toggle for bActFrcLimited. */ - UPROPERTY(EditAnywhere, Category = "Mj Tendon|Limits", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon|Limits", meta=(InlineEditConditionToggle)) bool bOverride_ActFrcLimited = false; /** @brief Whether the tendon has actuator force limits. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon|Limits", meta=(EditCondition="bOverride_ActFrcLimited")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Limits", meta=(EditCondition="bOverride_ActFrcLimited")) bool bActFrcLimited = false; /** @brief Override toggle for ActFrcRange. */ - UPROPERTY(EditAnywhere, Category = "Mj Tendon|Limits", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon|Limits", meta=(InlineEditConditionToggle)) bool bOverride_ActFrcRange = false; /** @brief Tendon actuator force limits [min, max]. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon|Limits", meta=(EditCondition="bOverride_ActFrcRange")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Limits", meta=(EditCondition="bOverride_ActFrcRange")) TArray ActFrcRange = {0.0f, 0.0f}; // --- Solver Parameters --- /** @brief Override toggle for SolRefLimit. */ - UPROPERTY(EditAnywhere, Category = "Mj Tendon|Solving", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon|Solving", meta=(InlineEditConditionToggle)) bool bOverride_SolRefLimit = false; /** @brief Constraint solver reference for limits (timeconst, dampratio). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon|Solving", meta=(EditCondition="bOverride_SolRefLimit")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Solving", meta=(EditCondition="bOverride_SolRefLimit")) TArray SolRefLimit = {0.02f, 1.0f}; /** @brief Override toggle for SolImpLimit. */ - UPROPERTY(EditAnywhere, Category = "Mj Tendon|Solving", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon|Solving", meta=(InlineEditConditionToggle)) bool bOverride_SolImpLimit = false; /** @brief Constraint solver impedance for limits (dmin, dmax, width). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon|Solving", meta=(EditCondition="bOverride_SolImpLimit")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Solving", meta=(EditCondition="bOverride_SolImpLimit")) TArray SolImpLimit = {0.9f, 0.95f, 0.001f}; /** @brief Override toggle for SolRefFriction. */ - UPROPERTY(EditAnywhere, Category = "Mj Tendon|Solving", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon|Solving", meta=(InlineEditConditionToggle)) bool bOverride_SolRefFriction = false; /** @brief Constraint solver reference for friction (timeconst, dampratio). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon|Solving", meta=(EditCondition="bOverride_SolRefFriction")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Solving", meta=(EditCondition="bOverride_SolRefFriction")) TArray SolRefFriction = {0.02f, 1.0f}; /** @brief Override toggle for SolImpFriction. */ - UPROPERTY(EditAnywhere, Category = "Mj Tendon|Solving", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon|Solving", meta=(InlineEditConditionToggle)) bool bOverride_SolImpFriction = false; /** @brief Constraint solver impedance for friction. */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon|Solving", meta=(EditCondition="bOverride_SolImpFriction")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Solving", meta=(EditCondition="bOverride_SolImpFriction")) TArray SolImpFriction = {0.9f, 0.95f, 0.001f}; // --- Visuals --- /** @brief Override toggle for Width. */ - UPROPERTY(EditAnywhere, Category = "Mj Tendon|Visual", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon|Visual", meta=(InlineEditConditionToggle)) bool bOverride_Width = false; /** @brief Width for rendering the tendon (meters). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon|Visual", meta=(EditCondition="bOverride_Width")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Visual", meta=(EditCondition="bOverride_Width")) float Width = 0.003f; /** @brief Override toggle for Rgba. */ - UPROPERTY(EditAnywhere, Category = "Mj Tendon|Visual", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon|Visual", meta=(InlineEditConditionToggle)) bool bOverride_Rgba = false; /** @brief Tendon color (RGBA). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon|Visual", meta=(EditCondition="bOverride_Rgba")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Visual", meta=(EditCondition="bOverride_Rgba")) FLinearColor Rgba = FLinearColor(0.5f, 0.5f, 0.5f, 1.0f); /** @brief Override toggle for Group. */ - UPROPERTY(EditAnywhere, Category = "Mj Tendon|Visual", meta=(InlineEditConditionToggle)) + UPROPERTY(EditAnywhere, Category = "MuJoCo|Tendon|Visual", meta=(InlineEditConditionToggle)) bool bOverride_Group = false; /** @brief Visualization group (0 = always visible). */ - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mj Tendon|Visual", meta=(EditCondition="bOverride_Group")) + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "MuJoCo|Tendon|Visual", meta=(EditCondition="bOverride_Group")) int Group = 0; protected: diff --git a/Source/URLabEditor/Private/MjComponentDetailCustomizations.cpp b/Source/URLabEditor/Private/MjComponentDetailCustomizations.cpp new file mode 100644 index 0000000..318ebfd --- /dev/null +++ b/Source/URLabEditor/Private/MjComponentDetailCustomizations.cpp @@ -0,0 +1,242 @@ +// 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 "MjComponentDetailCustomizations.h" +#include "DetailLayoutBuilder.h" +#include "DetailCategoryBuilder.h" +#include "DetailWidgetRow.h" +#include "Widgets/Input/SButton.h" +#include "Widgets/Text/STextBlock.h" + +#include "MuJoCo/Components/Actuators/MjActuator.h" +#include "MuJoCo/Components/Sensors/MjSensor.h" +#include "MuJoCo/Components/Physics/MjContactPair.h" +#include "MuJoCo/Components/Physics/MjContactExclude.h" +#include "MuJoCo/Components/Constraints/MjEquality.h" +#include "MuJoCo/Components/Bodies/MjBody.h" +#include "MuJoCo/Components/Defaults/MjDefault.h" +#include "MuJoCo/Components/Joints/MjJoint.h" +#include "MuJoCo/Components/Geometry/MjGeom.h" +#include "MuJoCo/Components/Geometry/MjSite.h" +#include "MuJoCo/Components/Tendons/MjTendon.h" + +// Detail customizations that hide internal properties from the editor UI. + +// ============================================================================ +// Actuator — hide DefaultClass pointer +// ============================================================================ + +TSharedRef FMjActuatorDetailCustomization::MakeInstance() +{ + return MakeShareable(new FMjActuatorDetailCustomization); +} + +void FMjActuatorDetailCustomization::CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) +{ + DetailBuilder.HideProperty(DetailBuilder.GetProperty(GET_MEMBER_NAME_CHECKED(UMjActuator, DefaultClass))); +} + +// ============================================================================ +// Sensor — hide DefaultClass pointer +// ============================================================================ + +TSharedRef FMjSensorDetailCustomization::MakeInstance() +{ + return MakeShareable(new FMjSensorDetailCustomization); +} + +void FMjSensorDetailCustomization::CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) +{ + DetailBuilder.HideProperty(DetailBuilder.GetProperty(GET_MEMBER_NAME_CHECKED(UMjSensor, DefaultClass))); +} + +// ============================================================================ +// Contact Pair — hide Name +// ============================================================================ + +TSharedRef FMjContactPairDetailCustomization::MakeInstance() +{ + return MakeShareable(new FMjContactPairDetailCustomization); +} + +void FMjContactPairDetailCustomization::CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) +{ + DetailBuilder.HideProperty(DetailBuilder.GetProperty(GET_MEMBER_NAME_CHECKED(UMjContactPair, Name))); +} + +// ============================================================================ +// Contact Exclude — hide Name +// ============================================================================ + +TSharedRef FMjContactExcludeDetailCustomization::MakeInstance() +{ + return MakeShareable(new FMjContactExcludeDetailCustomization); +} + +void FMjContactExcludeDetailCustomization::CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) +{ + DetailBuilder.HideProperty(DetailBuilder.GetProperty(GET_MEMBER_NAME_CHECKED(UMjContactExclude, Name))); +} + +// ============================================================================ +// Equality +// ============================================================================ + +TSharedRef FMjEqualityDetailCustomization::MakeInstance() +{ + return MakeShareable(new FMjEqualityDetailCustomization); +} + +void FMjEqualityDetailCustomization::CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) +{ +} + +// ============================================================================ +// Joint — hide DefaultClass pointer +// ============================================================================ + +TSharedRef FMjJointDetailCustomization::MakeInstance() +{ + return MakeShareable(new FMjJointDetailCustomization); +} + +void FMjJointDetailCustomization::CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) +{ + DetailBuilder.HideProperty(DetailBuilder.GetProperty(GET_MEMBER_NAME_CHECKED(UMjJoint, DefaultClass))); +} + +// ============================================================================ +// Body +// ============================================================================ + +TSharedRef FMjBodyDetailCustomization::MakeInstance() +{ + return MakeShareable(new FMjBodyDetailCustomization); +} + +void FMjBodyDetailCustomization::CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) +{ +} + +// ============================================================================ +// Default — hide ClassName and ParentClassName (synced from SCS hierarchy) +// ============================================================================ + +TSharedRef FMjDefaultDetailCustomization::MakeInstance() +{ + return MakeShareable(new FMjDefaultDetailCustomization); +} + +void FMjDefaultDetailCustomization::CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) +{ + DetailBuilder.HideProperty(DetailBuilder.GetProperty(GET_MEMBER_NAME_CHECKED(UMjDefault, ClassName))); + DetailBuilder.HideProperty(DetailBuilder.GetProperty(GET_MEMBER_NAME_CHECKED(UMjDefault, ParentClassName))); +} + +// ============================================================================ +// Site — hide DefaultClass pointer +// ============================================================================ + +TSharedRef FMjSiteDetailCustomization::MakeInstance() +{ + return MakeShareable(new FMjSiteDetailCustomization); +} + +void FMjSiteDetailCustomization::CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) +{ + DetailBuilder.HideProperty(DetailBuilder.GetProperty(GET_MEMBER_NAME_CHECKED(UMjSite, DefaultClass))); +} + +// ============================================================================ +// Tendon — hide DefaultClass pointer +// ============================================================================ + +TSharedRef FMjTendonDetailCustomization::MakeInstance() +{ + return MakeShareable(new FMjTendonDetailCustomization); +} + +void FMjTendonDetailCustomization::CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) +{ + DetailBuilder.HideProperty(DetailBuilder.GetProperty(GET_MEMBER_NAME_CHECKED(UMjTendon, DefaultClass))); +} + +// ============================================================================ +// Geom — hide DefaultClass pointer + CoACD decomposition buttons +// ============================================================================ + +TSharedRef FMjGeomDetailCustomization::MakeInstance() +{ + return MakeShareable(new FMjGeomDetailCustomization); +} + +void FMjGeomDetailCustomization::CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) +{ + TArray> Objects; + DetailBuilder.GetObjectsBeingCustomized(Objects); + + if (Objects.Num() != 1) return; + TWeakObjectPtr WeakGeom = Cast(Objects[0].Get()); + if (!WeakGeom.IsValid()) return; + + DetailBuilder.HideProperty(DetailBuilder.GetProperty(GET_MEMBER_NAME_CHECKED(UMjGeom, DefaultClass))); + + // Decomposition buttons (only for mesh geoms) + if (WeakGeom->Type != EMjGeomType::Mesh) return; + + IDetailCategoryBuilder& DecompCategory = DetailBuilder.EditCategory("MuJoCo|Geom|Decomposition"); + + DecompCategory.AddCustomRow(FText::FromString("Decompose")) + .NameContent() + [ + SNew(STextBlock).Text(FText::FromString("CoACD Decomposition")) + ] + .ValueContent() + .MaxDesiredWidth(300.f) + [ + SNew(SHorizontalBox) + + SHorizontalBox::Slot() + .AutoWidth() + .Padding(2.f) + [ + SNew(SButton) + .Text(FText::FromString("Decompose Mesh")) + .OnClicked_Lambda([WeakGeom]() -> FReply + { + if (WeakGeom.IsValid()) WeakGeom->DecomposeMesh(); + return FReply::Handled(); + }) + ] + + SHorizontalBox::Slot() + .AutoWidth() + .Padding(2.f) + [ + SNew(SButton) + .Text(FText::FromString("Remove Decomposition")) + .OnClicked_Lambda([WeakGeom]() -> FReply + { + if (WeakGeom.IsValid()) WeakGeom->RemoveDecomposition(); + return FReply::Handled(); + }) + ] + ]; +} diff --git a/Source/URLabEditor/Private/MjEditorStyle.cpp b/Source/URLabEditor/Private/MjEditorStyle.cpp new file mode 100644 index 0000000..5d77417 --- /dev/null +++ b/Source/URLabEditor/Private/MjEditorStyle.cpp @@ -0,0 +1,115 @@ +// 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 "MjEditorStyle.h" +#include "Styling/SlateStyleRegistry.h" +#include "Styling/AppStyle.h" +#include "Interfaces/IPluginManager.h" + +TSharedPtr FMjEditorStyle::StyleInstance = nullptr; + +FName FMjEditorStyle::GetStyleSetName() +{ + static FName StyleSetName(TEXT("MjEditorStyle")); + return StyleSetName; +} + +void FMjEditorStyle::Initialize() +{ + if (StyleInstance.IsValid()) return; + + StyleInstance = MakeShareable(new FSlateStyleSet(GetStyleSetName())); + + // Resolve the plugin's Resources directory for custom icon PNGs + FString PluginBaseDir = FPaths::Combine( + FPaths::ProjectPluginsDir(), TEXT("UnrealRoboticsLab")); + FString IconsDir = PluginBaseDir / TEXT("Resources") / TEXT("Icons"); + + StyleInstance->SetContentRoot(IconsDir); + + // Icon size for component tree + const FVector2D IconSize(16.0f, 16.0f); + + // Helper lambda: register icon if PNG exists, otherwise use an existing engine brush + auto RegisterIcon = [&](const FName& PropertyName, const FString& PngName, const FName& FallbackBrush) + { + FString PngPath = IconsDir / PngName; + if (FPaths::FileExists(PngPath)) + { + StyleInstance->Set(PropertyName, new FSlateImageBrush(PngPath, IconSize)); + } + else + { + // Copy the existing brush from the engine's style set + const FSlateBrush* Existing = FAppStyle::Get().GetBrush(FallbackBrush); + if (Existing && Existing != FAppStyle::GetNoBrush()) + { + StyleInstance->Set(PropertyName, new FSlateBrush(*Existing)); + } + } + }; + + // Register class icons for each MuJoCo component type. + // UE looks for "ClassIcon." in registered style sets. + // If custom PNGs are placed in Resources/Icons/, they will be used. + // Otherwise, built-in editor icons serve as placeholders. + RegisterIcon("ClassIcon.MjBody", TEXT("MjBody.png"), "ClassIcon.SceneComponent"); + RegisterIcon("ClassIcon.MjWorldBody", TEXT("MjWorldBody.png"), "ClassIcon.SceneComponent"); + RegisterIcon("ClassIcon.MjGeom", TEXT("MjGeom.png"), "ClassIcon.StaticMeshComponent"); + RegisterIcon("ClassIcon.MjBox", TEXT("MjBox.png"), "ClassIcon.StaticMeshComponent"); + RegisterIcon("ClassIcon.MjSphere", TEXT("MjSphere.png"), "ClassIcon.StaticMeshComponent"); + RegisterIcon("ClassIcon.MjCylinder", TEXT("MjCylinder.png"), "ClassIcon.StaticMeshComponent"); + RegisterIcon("ClassIcon.MjMeshGeom", TEXT("MjMeshGeom.png"), "ClassIcon.StaticMeshComponent"); + RegisterIcon("ClassIcon.MjHingeJoint", TEXT("MjHingeJoint.png"), "ClassIcon.PhysicsConstraintComponent"); + RegisterIcon("ClassIcon.MjSlideJoint", TEXT("MjSlideJoint.png"), "ClassIcon.PhysicsConstraintComponent"); + RegisterIcon("ClassIcon.MjBallJoint", TEXT("MjBallJoint.png"), "ClassIcon.PhysicsConstraintComponent"); + RegisterIcon("ClassIcon.MjFreeJoint", TEXT("MjFreeJoint.png"), "ClassIcon.PhysicsConstraintComponent"); + RegisterIcon("ClassIcon.MjJoint", TEXT("MjJoint.png"), "ClassIcon.PhysicsConstraintComponent"); + RegisterIcon("ClassIcon.MjSensor", TEXT("MjSensor.png"), "ClassIcon.SphereComponent"); + RegisterIcon("ClassIcon.MjActuator", TEXT("MjActuator.png"), "ClassIcon.MovementComponent"); + RegisterIcon("ClassIcon.MjDefault", TEXT("MjDefault.png"), "ClassIcon.BlueprintCore"); + RegisterIcon("ClassIcon.MjSite", TEXT("MjSite.png"), "ClassIcon.TargetPoint"); + RegisterIcon("ClassIcon.MjTendon", TEXT("MjTendon.png"), "ClassIcon.CableComponent"); + RegisterIcon("ClassIcon.MjCamera", TEXT("MjCamera.png"), "ClassIcon.CameraComponent"); + RegisterIcon("ClassIcon.MjInertial", TEXT("MjInertial.png"), "ClassIcon.SphereComponent"); + RegisterIcon("ClassIcon.MjContactPair", TEXT("MjContactPair.png"), "ClassIcon.SphereComponent"); + RegisterIcon("ClassIcon.MjContactExclude", TEXT("MjContactExclude.png"), "ClassIcon.SphereComponent"); + RegisterIcon("ClassIcon.MjEquality", TEXT("MjEquality.png"), "ClassIcon.SphereComponent"); + RegisterIcon("ClassIcon.MjKeyframe", TEXT("MjKeyframe.png"), "ClassIcon.SphereComponent"); + + FSlateStyleRegistry::RegisterSlateStyle(*StyleInstance); +} + +void FMjEditorStyle::Shutdown() +{ + if (StyleInstance.IsValid()) + { + FSlateStyleRegistry::UnRegisterSlateStyle(*StyleInstance); + StyleInstance.Reset(); + } +} + +const ISlateStyle& FMjEditorStyle::Get() +{ + check(StyleInstance.IsValid()); + return *StyleInstance; +} diff --git a/Source/URLabEditor/Private/MjGeomDetailCustomization.cpp b/Source/URLabEditor/Private/MjGeomDetailCustomization.cpp deleted file mode 100644 index 3ea7b75..0000000 --- a/Source/URLabEditor/Private/MjGeomDetailCustomization.cpp +++ /dev/null @@ -1,83 +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 "MjGeomDetailCustomization.h" -#include "MuJoCo/Components/Geometry/MjGeom.h" -#include "DetailLayoutBuilder.h" -#include "DetailCategoryBuilder.h" -#include "DetailWidgetRow.h" -#include "Widgets/Input/SButton.h" -#include "Widgets/Text/STextBlock.h" - -TSharedRef FMjGeomDetailCustomization::MakeInstance() -{ - return MakeShareable(new FMjGeomDetailCustomization); -} - -void FMjGeomDetailCustomization::CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) -{ - TArray> Objects; - DetailBuilder.GetObjectsBeingCustomized(Objects); - - if (Objects.Num() != 1) return; - TWeakObjectPtr WeakGeom = Cast(Objects[0].Get()); - if (!WeakGeom.IsValid()) return; - - if (WeakGeom->Type != EMjGeomType::Mesh) return; - - IDetailCategoryBuilder& Category = DetailBuilder.EditCategory("MuJoCo|Geom|Decomposition", - FText::FromString("Mesh Decomposition"), ECategoryPriority::Important); - - Category.AddCustomRow(FText::FromString("Decompose")) - .NameContent() - [ - SNew(STextBlock).Text(FText::FromString("CoACD Decomposition")) - ] - .ValueContent() - .MaxDesiredWidth(300.f) - [ - SNew(SHorizontalBox) - + SHorizontalBox::Slot() - .AutoWidth() - .Padding(2.f) - [ - SNew(SButton) - .Text(FText::FromString("Decompose Mesh")) - .OnClicked_Lambda([WeakGeom]() -> FReply - { - if (WeakGeom.IsValid()) WeakGeom->DecomposeMesh(); - return FReply::Handled(); - }) - ] - + SHorizontalBox::Slot() - .AutoWidth() - .Padding(2.f) - [ - SNew(SButton) - .Text(FText::FromString("Remove Decomposition")) - .OnClicked_Lambda([WeakGeom]() -> FReply - { - if (WeakGeom.IsValid()) WeakGeom->RemoveDecomposition(); - return FReply::Handled(); - }) - ] - ]; -} diff --git a/Source/URLabEditor/Private/MujocoXmlParser.cpp b/Source/URLabEditor/Private/MujocoXmlParser.cpp index 7050afb..45e1351 100644 --- a/Source/URLabEditor/Private/MujocoXmlParser.cpp +++ b/Source/URLabEditor/Private/MujocoXmlParser.cpp @@ -106,6 +106,7 @@ #include "MuJoCo/Components/Geometry/Primitives/MjBox.h" #include "MuJoCo/Components/Geometry/Primitives/MjSphere.h" #include "MuJoCo/Components/Geometry/Primitives/MjCylinder.h" +#include "MuJoCo/Components/Geometry/MjMeshGeom.h" #include "MuJoCo/Components/Physics/MjInertial.h" #include "MuJoCo/Components/Constraints/MjEquality.h" #include "MuJoCo/Components/Keyframes/MjKeyframe.h" @@ -259,7 +260,11 @@ void UMujocoGenerationAction::ImportNodeRecursive(const FXmlNode* Node, USCS_Nod // Regular Body FString Name = Node->GetAttribute(TEXT("name")); - if (Name.IsEmpty()) Name = TEXT("AUTONAME_Body"); + if (Name.IsEmpty()) + { + FString ParentName = ParentNode ? ParentNode->GetVariableName().ToString() : TEXT("Body"); + Name = ParentName + TEXT("_Body"); + } if (ReuseNode) { @@ -286,7 +291,11 @@ void UMujocoGenerationAction::ImportNodeRecursive(const FXmlNode* Node, USCS_Nod else if (Tag.Equals(TEXT("frame"))) { FString Name = Node->GetAttribute(TEXT("name")); - if (Name.IsEmpty()) Name = TEXT("AUTONAME_Frame"); + if (Name.IsEmpty()) + { + FString ParentName = ParentNode ? ParentNode->GetVariableName().ToString() : TEXT("Frame"); + Name = ParentName + TEXT("_Frame"); + } CreatedNode = BP->SimpleConstructionScript->CreateNode(UMjFrame::StaticClass(), *Name); UMjFrame* FrameComp = Cast(CreatedNode->ComponentTemplate); @@ -312,13 +321,26 @@ void UMujocoGenerationAction::ImportNodeRecursive(const FXmlNode* Node, USCS_Nod else if (Tag.Equals(TEXT("geom"))) { FString Name = Node->GetAttribute(TEXT("name")); - if (Name.IsEmpty()) Name = TEXT("AUTONAME_Geom"); - FString TypeStr = Node->GetAttribute(TEXT("type")); + FString MeshAttr = Node->GetAttribute(TEXT("mesh")); + + // If no explicit type but has a mesh attribute, it's a mesh geom + if (TypeStr.IsEmpty() && !MeshAttr.IsEmpty()) + { + TypeStr = TEXT("mesh"); + } + + if (Name.IsEmpty()) + { + FString GeomTypeName = TypeStr.IsEmpty() ? TEXT("Sphere") : TypeStr; + GeomTypeName[0] = FChar::ToUpper(GeomTypeName[0]); + Name = TEXT("Geom_") + GeomTypeName; + } UClass* Class = UMjGeom::StaticClass(); if (TypeStr == "box") Class = UMjBox::StaticClass(); else if (TypeStr == "sphere") Class = UMjSphere::StaticClass(); else if (TypeStr == "cylinder") Class = UMjCylinder::StaticClass(); + else if (TypeStr == "mesh") Class = UMjMeshGeom::StaticClass(); CreatedNode = BP->SimpleConstructionScript->CreateNode(Class, *Name); UMjGeom* GeomComp = Cast(CreatedNode->ComponentTemplate); @@ -327,6 +349,20 @@ void UMujocoGenerationAction::ImportNodeRecursive(const FXmlNode* Node, USCS_Nod GeomComp->ImportFromXml(Node, CompilerSettings); GeomComp->bIsDefault = bIsDefaultContext; + // Resolve DefaultClass from the class attribute + { + FString ClassAttr = Node->GetAttribute(TEXT("class")); + if (ClassAttr.IsEmpty()) ClassAttr = TEXT("main"); + if (CreatedDefaultNodes.Contains(ClassAttr)) + { + UMjDefault* DefComp = Cast(CreatedDefaultNodes[ClassAttr]->ComponentTemplate); + if (DefComp) + { + GeomComp->DefaultClass = DefComp; + } + } + } + // Resolve default class transform for visual mesh placement. // Walk the default class hierarchy (child -> parent -> ... -> main) to find // the first default geom with a transform override. @@ -535,9 +571,13 @@ void UMujocoGenerationAction::ImportNodeRecursive(const FXmlNode* Node, USCS_Nod else if (Tag.Equals(TEXT("joint"))) { FString Name = Node->GetAttribute(TEXT("name")); - if (Name.IsEmpty()) Name = TEXT("AUTONAME_Joint"); - FString TypeStr = Node->GetAttribute(TEXT("type")); + if (Name.IsEmpty()) + { + FString JointTypeName = TypeStr.IsEmpty() ? TEXT("Hinge") : TypeStr; + JointTypeName[0] = FChar::ToUpper(JointTypeName[0]); + Name = JointTypeName + TEXT("Joint"); + } UClass* Class = UMjHingeJoint::StaticClass(); if (TypeStr == "hinge") Class = UMjHingeJoint::StaticClass(); else if (TypeStr == "slide") Class = UMjSlideJoint::StaticClass(); @@ -550,13 +590,20 @@ void UMujocoGenerationAction::ImportNodeRecursive(const FXmlNode* Node, USCS_Nod { JointComp->ImportFromXml(Node, CompilerSettings); JointComp->bIsDefault = bIsDefaultContext; + + FString ClassAttr = Node->GetAttribute(TEXT("class")); + if (!ClassAttr.IsEmpty() && CreatedDefaultNodes.Contains(ClassAttr)) + { + UMjDefault* DefComp = Cast(CreatedDefaultNodes[ClassAttr]->ComponentTemplate); + if (DefComp) JointComp->DefaultClass = DefComp; + } } } // --- FREEJOINT (Standalone) --- else if (Tag.Equals(TEXT("freejoint"))) { FString Name = Node->GetAttribute(TEXT("name")); - if (Name.IsEmpty()) Name = TEXT("AUTONAME_FreeJoint"); + if (Name.IsEmpty()) Name = TEXT("FreeJoint"); CreatedNode = BP->SimpleConstructionScript->CreateNode(UMjFreeJoint::StaticClass(), *Name); UMjJoint* JointComp = Cast(CreatedNode->ComponentTemplate); @@ -573,7 +620,7 @@ void UMujocoGenerationAction::ImportNodeRecursive(const FXmlNode* Node, USCS_Nod else if (Tag.Equals(TEXT("site"))) { FString Name = Node->GetAttribute(TEXT("name")); - if (Name.IsEmpty()) Name = TEXT("AUTONAME_Site"); + if (Name.IsEmpty()) Name = TEXT("Site"); CreatedNode = BP->SimpleConstructionScript->CreateNode(UMjSite::StaticClass(), *Name); UMjSite* SiteComp = Cast(CreatedNode->ComponentTemplate); if (SiteComp) @@ -582,12 +629,19 @@ void UMujocoGenerationAction::ImportNodeRecursive(const FXmlNode* Node, USCS_Nod SiteComp->bIsDefault = bIsDefaultContext; FString NameAttr = Node->GetAttribute(TEXT("name")); if (!NameAttr.IsEmpty()) SiteComp->MjName = NameAttr; + + FString ClassAttr = Node->GetAttribute(TEXT("class")); + if (!ClassAttr.IsEmpty() && CreatedDefaultNodes.Contains(ClassAttr)) + { + UMjDefault* DefComp = Cast(CreatedDefaultNodes[ClassAttr]->ComponentTemplate); + if (DefComp) SiteComp->DefaultClass = DefComp; + } } } // --- INERTIAL --- else if (Tag.Equals(TEXT("inertial"))) { - CreatedNode = BP->SimpleConstructionScript->CreateNode(UMjInertial::StaticClass(), TEXT("AUTONAME_Inertial")); + CreatedNode = BP->SimpleConstructionScript->CreateNode(UMjInertial::StaticClass(), TEXT("Inertial")); UMjInertial* InertialComp = Cast(CreatedNode->ComponentTemplate); if (InertialComp) { @@ -617,7 +671,12 @@ void UMujocoGenerationAction::ImportNodeRecursive(const FXmlNode* Node, USCS_Nod Tag == "clock" || Tag == "tactile" || Tag == "user" || Tag == "plugin") { FString Name = Node->GetAttribute(TEXT("name")); - if (Name.IsEmpty()) Name = TEXT("AUTONAME_") + Tag; + if (Name.IsEmpty()) + { + FString SensorTag = Tag; + SensorTag[0] = FChar::ToUpper(SensorTag[0]); + Name = SensorTag + TEXT("Sensor"); + } UClass* Class = UMjSensor::StaticClass(); if (Tag == "touch") Class = UMjTouchSensor::StaticClass(); @@ -676,13 +735,20 @@ void UMujocoGenerationAction::ImportNodeRecursive(const FXmlNode* Node, USCS_Nod SensComp->bIsDefault = bIsDefaultContext; FString NameAttr = Node->GetAttribute(TEXT("name")); if (!NameAttr.IsEmpty()) SensComp->MjName = NameAttr; + + FString ClassAttr = Node->GetAttribute(TEXT("class")); + if (!ClassAttr.IsEmpty() && CreatedDefaultNodes.Contains(ClassAttr)) + { + UMjDefault* DefComp = Cast(CreatedDefaultNodes[ClassAttr]->ComponentTemplate); + if (DefComp) SensComp->DefaultClass = DefComp; + } } } // --- CAMERA --- else if (Tag.Equals(TEXT("camera"))) { FString Name = Node->GetAttribute(TEXT("name")); - if (Name.IsEmpty()) Name = TEXT("AUTONAME_Camera"); + if (Name.IsEmpty()) Name = TEXT("Camera"); CreatedNode = BP->SimpleConstructionScript->CreateNode(UMjCamera::StaticClass(), *Name); UMjCamera* CamComp = Cast(CreatedNode->ComponentTemplate); @@ -699,7 +765,12 @@ void UMujocoGenerationAction::ImportNodeRecursive(const FXmlNode* Node, USCS_Nod Tag == "motor" || Tag == "position" || Tag == "velocity" || Tag == "cylinder" || Tag == "muscle" || Tag == "general" || Tag == "damper" || Tag == "intvelocity" || Tag == "adhesion") { FString Name = Node->GetAttribute(TEXT("name")); - if (Name.IsEmpty()) Name = TEXT("AUTONAME_") + Tag; + if (Name.IsEmpty()) + { + FString ActTag = Tag; + ActTag[0] = FChar::ToUpper(ActTag[0]); + Name = ActTag + TEXT("Actuator"); + } UClass* Class = UMjActuator::StaticClass(); if (Tag == "motor") Class = UMjMotorActuator::StaticClass(); @@ -720,6 +791,13 @@ void UMujocoGenerationAction::ImportNodeRecursive(const FXmlNode* Node, USCS_Nod ActComp->bIsDefault = bIsDefaultContext; FString NameAttr = Node->GetAttribute(TEXT("name")); if (!NameAttr.IsEmpty()) ActComp->MjName = NameAttr; + + FString ClassAttr = Node->GetAttribute(TEXT("class")); + if (!ClassAttr.IsEmpty() && CreatedDefaultNodes.Contains(ClassAttr)) + { + UMjDefault* DefComp = Cast(CreatedDefaultNodes[ClassAttr]->ComponentTemplate); + if (DefComp) ActComp->DefaultClass = DefComp; + } } } // --- TENDON --- @@ -735,7 +813,12 @@ void UMujocoGenerationAction::ImportNodeRecursive(const FXmlNode* Node, USCS_Nod } FString Name = Node->GetAttribute(TEXT("name")); - if (Name.IsEmpty()) Name = TEXT("AUTONAME_") + Tag; + if (Name.IsEmpty()) + { + FString TendonTag = Tag; + TendonTag[0] = FChar::ToUpper(TendonTag[0]); + Name = TendonTag + TEXT("Tendon"); + } CreatedNode = BP->SimpleConstructionScript->CreateNode(UMjTendon::StaticClass(), *Name); UMjTendon* TendonComp = Cast(CreatedNode->ComponentTemplate); @@ -1049,7 +1132,7 @@ void UMujocoGenerationAction::ParseDefaultsRecursive(const FXmlNode* Node, UBlue if (ClassName.IsEmpty()) ClassName = TEXT("main"); - FString NodeName = FString::Printf(TEXT("Default_%s"), *ClassName); + FString NodeName = ClassName; UE_LOG(LogURLabEditor, Log, TEXT("Creating Default Component: %s (Parent: %s)"), *NodeName, *ParentClassName); USCS_Node* DefNode = BP->SimpleConstructionScript->CreateNode(UMjDefault::StaticClass(), *NodeName); @@ -1082,7 +1165,7 @@ void UMujocoGenerationAction::ParseDefaultsRecursive(const FXmlNode* Node, UBlue else if (ChildTag.Equals(TEXT("geom"))) { FString GeomName = Child->GetAttribute(TEXT("name")); - if (GeomName.IsEmpty()) GeomName = TEXT("AUTONAME_DefaultGeom"); + if (GeomName.IsEmpty()) GeomName = TEXT("DefaultGeom"); USCS_Node* GeomNode = BP->SimpleConstructionScript->CreateNode(UMjGeom::StaticClass(), *GeomName); DefNode->AddChildNode(GeomNode); @@ -1097,7 +1180,7 @@ void UMujocoGenerationAction::ParseDefaultsRecursive(const FXmlNode* Node, UBlue else if (ChildTag.Equals(TEXT("joint"))) { FString JointName = Child->GetAttribute(TEXT("name")); - if (JointName.IsEmpty()) JointName = TEXT("AUTONAME_DefaultJoint"); + if (JointName.IsEmpty()) JointName = TEXT("DefaultJoint"); USCS_Node* JointNode = BP->SimpleConstructionScript->CreateNode(UMjJoint::StaticClass(), *JointName); DefNode->AddChildNode(JointNode); @@ -1113,7 +1196,7 @@ void UMujocoGenerationAction::ParseDefaultsRecursive(const FXmlNode* Node, UBlue else if (ChildTag.Equals(TEXT("site"))) { FString SiteName = Child->GetAttribute(TEXT("name")); - if (SiteName.IsEmpty()) SiteName = TEXT("AUTONAME_DefaultSite"); + if (SiteName.IsEmpty()) SiteName = TEXT("DefaultSite"); USCS_Node* SiteNode = BP->SimpleConstructionScript->CreateNode(UMjSite::StaticClass(), *SiteName); DefNode->AddChildNode(SiteNode); @@ -1128,7 +1211,7 @@ void UMujocoGenerationAction::ParseDefaultsRecursive(const FXmlNode* Node, UBlue else if (ChildTag.Equals(TEXT("camera"))) { FString CamName = Child->GetAttribute(TEXT("name")); - if (CamName.IsEmpty()) CamName = TEXT("AUTONAME_DefaultCamera"); + if (CamName.IsEmpty()) CamName = TEXT("DefaultCamera"); USCS_Node* CamNode = BP->SimpleConstructionScript->CreateNode(UMjCamera::StaticClass(), *CamName); DefNode->AddChildNode(CamNode); @@ -1148,7 +1231,12 @@ void UMujocoGenerationAction::ParseDefaultsRecursive(const FXmlNode* Node, UBlue ChildTag.Equals(TEXT("adhesion")) || ChildTag.Equals(TEXT("intvelocity"))) { FString ActName = Child->GetAttribute(TEXT("name")); - if (ActName.IsEmpty()) ActName = TEXT("AUTONAME_Default") + ChildTag; + if (ActName.IsEmpty()) + { + FString DefaultActTag = ChildTag; + DefaultActTag[0] = FChar::ToUpper(DefaultActTag[0]); + ActName = TEXT("Default") + DefaultActTag; + } UClass* ActClass = UMjActuator::StaticClass(); if (ChildTag == "motor") ActClass = UMjMotorActuator::StaticClass(); @@ -1219,7 +1307,7 @@ void UMujocoGenerationAction::ParseContactSection(const FXmlNode* Node, UBluepri if (PairName.IsEmpty()) { - PairName = FString::Printf(TEXT("AUTONAME_ContactPair_%s_%s"), *Geom1, *Geom2); + PairName = FString::Printf(TEXT("ContactPair_%s_%s"), *Geom1, *Geom2); } UE_LOG(LogURLabEditor, Log, TEXT("Creating Contact Pair: %s (geom1=%s, geom2=%s)"), *PairName, *Geom1, *Geom2); @@ -1242,7 +1330,7 @@ void UMujocoGenerationAction::ParseContactSection(const FXmlNode* Node, UBluepri if (ExcludeName.IsEmpty()) { - ExcludeName = FString::Printf(TEXT("AUTONAME_ContactExclude_%s_%s"), *Body1, *Body2); + ExcludeName = FString::Printf(TEXT("ContactExclude_%s_%s"), *Body1, *Body2); } UE_LOG(LogURLabEditor, Log, TEXT("Creating Contact Exclude: %s (body1=%s, body2=%s)"), *ExcludeName, *Body1, *Body2); @@ -1296,7 +1384,12 @@ void UMujocoGenerationAction::ParseEqualitySection(const FXmlNode* Node, UBluepr if (ChildTag.Equals(TEXT("connect")) || ChildTag.Equals(TEXT("weld")) || ChildTag.Equals(TEXT("joint")) || ChildTag.Equals(TEXT("tendon"))) { FString EqName = Child->GetAttribute(TEXT("name")); - if (EqName.IsEmpty()) EqName = FString::Printf(TEXT("AUTONAME_Eq_%s"), *ChildTag); + if (EqName.IsEmpty()) + { + FString EqTag = ChildTag; + EqTag[0] = FChar::ToUpper(EqTag[0]); + EqName = TEXT("Eq_") + EqTag; + } USCS_Node* EqNode = BP->SimpleConstructionScript->CreateNode(UMjEquality::StaticClass(), *EqName); RootNode->AddChildNode(EqNode); @@ -1344,7 +1437,7 @@ void UMujocoGenerationAction::ParseKeyframeSection(const FXmlNode* Node, UBluepr if (Child->GetTag().Equals(TEXT("key"))) { FString KeyName = Child->GetAttribute(TEXT("name")); - if (KeyName.IsEmpty()) KeyName = TEXT("AUTONAME_Keyframe"); + if (KeyName.IsEmpty()) KeyName = TEXT("Keyframe"); USCS_Node* KeyNode = BP->SimpleConstructionScript->CreateNode(UMjKeyframe::StaticClass(), *KeyName); RootNode->AddChildNode(KeyNode); diff --git a/Source/URLabEditor/Private/SMjArticulationOutliner.cpp b/Source/URLabEditor/Private/SMjArticulationOutliner.cpp new file mode 100644 index 0000000..3d8f730 --- /dev/null +++ b/Source/URLabEditor/Private/SMjArticulationOutliner.cpp @@ -0,0 +1,501 @@ +// 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 "SMjArticulationOutliner.h" +#include "Widgets/Input/SSearchBox.h" +#include "Widgets/Input/SCheckBox.h" +#include "Widgets/Layout/SScrollBox.h" +#include "Widgets/Layout/SWrapBox.h" +#include "Widgets/Text/STextBlock.h" +#include "Engine/SimpleConstructionScript.h" +#include "Engine/SCS_Node.h" +#include "Engine/Blueprint.h" +#include "Editor.h" +#include "Subsystems/AssetEditorSubsystem.h" +#include "Kismet2/BlueprintEditorUtils.h" +#include "BlueprintEditor.h" + +#include "MuJoCo/Core/MjArticulation.h" +#include "MuJoCo/Components/Bodies/MjBody.h" +#include "MuJoCo/Components/Geometry/MjGeom.h" +#include "MuJoCo/Components/Geometry/MjSite.h" +#include "MuJoCo/Components/Joints/MjJoint.h" +#include "MuJoCo/Components/Sensors/MjSensor.h" +#include "MuJoCo/Components/Actuators/MjActuator.h" +#include "MuJoCo/Components/Defaults/MjDefault.h" + +void SMjArticulationOutliner::Construct(const FArguments& InArgs) +{ + auto MakeFilterToggle = [this](const FString& Label, bool& bFilterVar) -> TSharedRef + { + return SNew(SCheckBox) + .IsChecked_Lambda([&bFilterVar]() { return bFilterVar ? ECheckBoxState::Checked : ECheckBoxState::Unchecked; }) + .OnCheckStateChanged_Lambda([this, &bFilterVar](ECheckBoxState NewState) + { + bFilterVar = (NewState == ECheckBoxState::Checked); + ApplyFilters(); + }) + [ + SNew(STextBlock).Text(FText::FromString(Label)) + ]; + }; + + ChildSlot + [ + SNew(SVerticalBox) + + // Header: BP selector dropdown + + SVerticalBox::Slot() + .AutoHeight() + .Padding(4.f) + [ + SNew(SHorizontalBox) + + SHorizontalBox::Slot() + .AutoWidth() + .VAlign(VAlign_Center) + .Padding(0.f, 0.f, 4.f, 0.f) + [ + SNew(STextBlock) + .Text(FText::FromString(TEXT("Articulation:"))) + .Font(FCoreStyle::GetDefaultFontStyle("Bold", 10)) + ] + + SHorizontalBox::Slot() + .FillWidth(1.0f) + [ + SAssignNew(BPComboBox, SComboBox>) + .OptionsSource(&AvailableBPNames) + .OnSelectionChanged(this, &SMjArticulationOutliner::OnBPSelected) + .OnGenerateWidget_Lambda([](TSharedPtr Item) -> TSharedRef + { + return SNew(STextBlock).Text(FText::FromString(*Item)); + }) + .Content() + [ + SNew(STextBlock) + .Text_Lambda([this]() -> FText + { + if (SelectedBPName.IsValid()) return FText::FromString(*SelectedBPName); + return FText::FromString(TEXT("No articulation BPs open")); + }) + ] + ] + ] + + // Search bar + + SVerticalBox::Slot() + .AutoHeight() + .Padding(4.f) + [ + SNew(SSearchBox) + .HintText(FText::FromString(TEXT("Search components..."))) + .OnTextChanged_Lambda([this](const FText& NewText) + { + SearchText = NewText.ToString(); + ApplyFilters(); + }) + ] + + // Filter toggles + + SVerticalBox::Slot() + .AutoHeight() + .Padding(4.f) + [ + SNew(SWrapBox) + .UseAllottedSize(true) + + SWrapBox::Slot().Padding(2.f) [ MakeFilterToggle(TEXT("Bodies"), bShowBodies) ] + + SWrapBox::Slot().Padding(2.f) [ MakeFilterToggle(TEXT("Geoms"), bShowGeoms) ] + + SWrapBox::Slot().Padding(2.f) [ MakeFilterToggle(TEXT("Joints"), bShowJoints) ] + + SWrapBox::Slot().Padding(2.f) [ MakeFilterToggle(TEXT("Sensors"), bShowSensors) ] + + SWrapBox::Slot().Padding(2.f) [ MakeFilterToggle(TEXT("Actuators"), bShowActuators) ] + + SWrapBox::Slot().Padding(2.f) [ MakeFilterToggle(TEXT("Defaults"), bShowDefaults) ] + + SWrapBox::Slot().Padding(2.f) [ MakeFilterToggle(TEXT("Sites"), bShowSites) ] + + SWrapBox::Slot().Padding(2.f) [ MakeFilterToggle(TEXT("Other"), bShowOther) ] + ] + + // Tree view + + SVerticalBox::Slot() + .FillHeight(1.0f) + [ + SAssignNew(TreeView, STreeView>) + .TreeItemsSource(&FilteredRootEntries) + .OnGenerateRow(this, &SMjArticulationOutliner::OnGenerateRow) + .OnGetChildren(this, &SMjArticulationOutliner::OnGetChildren) + .OnSelectionChanged(this, &SMjArticulationOutliner::OnSelectionChanged) + ] + + // Summary bar + + SVerticalBox::Slot() + .AutoHeight() + .Padding(4.f) + [ + SNew(STextBlock) + .Text(this, &SMjArticulationOutliner::GetSummaryText) + .ColorAndOpacity(FSlateColor(FLinearColor(0.6f, 0.6f, 0.6f))) + ] + ]; +} + +void SMjArticulationOutliner::Tick(const FGeometry& AllottedGeometry, const double InCurrentTime, const float InDeltaTime) +{ + SCompoundWidget::Tick(AllottedGeometry, InCurrentTime, InDeltaTime); + + TimeSinceLastRefresh += InDeltaTime; + if (TimeSinceLastRefresh < 1.0f) return; + TimeSinceLastRefresh = 0.f; + + RefreshAvailableBPs(); + + // Auto-select first BP if none selected + if (!CurrentBP.IsValid() && AvailableBPs.Num() > 0) + { + RefreshFromBlueprint(AvailableBPs[0].Get()); + SelectedBPName = AvailableBPNames[0]; + if (BPComboBox.IsValid()) BPComboBox->SetSelectedItem(SelectedBPName); + } +} + +void SMjArticulationOutliner::RefreshAvailableBPs() +{ + TArray> NewBPs; + + if (GEditor) + { + UAssetEditorSubsystem* Sub = GEditor->GetEditorSubsystem(); + if (Sub) + { + for (UObject* Asset : Sub->GetAllEditedAssets()) + { + UBlueprint* BP = Cast(Asset); + if (BP && BP->GeneratedClass && BP->GeneratedClass->IsChildOf(AMjArticulation::StaticClass())) + { + NewBPs.Add(BP); + } + } + } + } + + // Only rebuild if changed + bool bChanged = (NewBPs.Num() != AvailableBPs.Num()); + if (!bChanged) + { + for (int32 i = 0; i < NewBPs.Num(); i++) + { + if (NewBPs[i] != AvailableBPs[i]) { bChanged = true; break; } + } + } + + if (bChanged) + { + AvailableBPs = NewBPs; + AvailableBPNames.Empty(); + for (const auto& WBP : AvailableBPs) + { + if (UBlueprint* BP = WBP.Get()) + AvailableBPNames.Add(MakeShared(BP->GetName())); + } + if (BPComboBox.IsValid()) BPComboBox->RefreshOptions(); + } +} + +void SMjArticulationOutliner::OnBPSelected(TSharedPtr Selected, ESelectInfo::Type SelectInfo) +{ + SelectedBPName = Selected; + if (!Selected.IsValid()) return; + + for (const auto& WBP : AvailableBPs) + { + UBlueprint* BP = WBP.Get(); + if (BP && BP->GetName() == *Selected) + { + RefreshFromBlueprint(BP); + return; + } + } +} + +void SMjArticulationOutliner::RefreshFromBlueprint(UBlueprint* BP) +{ + CurrentBP = BP; + RebuildTree(); +} + +void SMjArticulationOutliner::RebuildTree() +{ + RootEntries.Empty(); + + UBlueprint* BP = CurrentBP.Get(); + if (!BP || !BP->SimpleConstructionScript) return; + + for (USCS_Node* RootNode : BP->SimpleConstructionScript->GetRootNodes()) + { + TSharedPtr RootEntry = MakeShared(); + RootEntry->Name = RootNode->GetVariableName().ToString(); + RootEntry->TypeLabel = GetTypeLabel(RootNode->ComponentTemplate); + RootEntry->ComponentTemplate = RootNode->ComponentTemplate; + RootEntry->SCSNode = RootNode; + + CollectNodes(RootNode, RootEntry); + RootEntries.Add(RootEntry); + } + + ApplyFilters(); +} + +void SMjArticulationOutliner::CollectNodes(USCS_Node* Node, TSharedPtr ParentEntry) +{ + for (USCS_Node* Child : Node->GetChildNodes()) + { + TSharedPtr Entry = MakeShared(); + Entry->Name = Child->GetVariableName().ToString(); + Entry->TypeLabel = GetTypeLabel(Child->ComponentTemplate); + Entry->ComponentTemplate = Child->ComponentTemplate; + Entry->SCSNode = Child; + + CollectNodes(Child, Entry); + ParentEntry->Children.Add(Entry); + } +} + +void SMjArticulationOutliner::ApplyFilters() +{ + FilteredRootEntries.Empty(); + + for (const auto& RootEntry : RootEntries) + { + TSharedPtr Filtered = FilterTree(RootEntry); + if (Filtered.IsValid()) + { + FilteredRootEntries.Add(Filtered); + } + } + + if (TreeView.IsValid()) + { + TreeView->RequestTreeRefresh(); + + // Auto-expand the first two levels for visibility + for (const auto& Entry : FilteredRootEntries) + { + TreeView->SetItemExpansion(Entry, true); + for (const auto& Child : Entry->Children) + { + TreeView->SetItemExpansion(Child, true); + } + } + } +} + +bool SMjArticulationOutliner::PassesFilter(const TSharedPtr& Entry) const +{ + UObject* Comp = Entry->ComponentTemplate.Get(); + if (!Comp) return false; + + // Type filter + bool bPassType = false; + if (IsBody(Comp)) bPassType = bShowBodies; + else if (IsGeom(Comp)) bPassType = bShowGeoms; + else if (IsJoint(Comp)) bPassType = bShowJoints; + else if (IsSensor(Comp)) bPassType = bShowSensors; + else if (IsActuator(Comp)) bPassType = bShowActuators; + else if (IsDefault(Comp)) bPassType = bShowDefaults; + else if (IsSite(Comp)) bPassType = bShowSites; + else bPassType = bShowOther; + + if (!bPassType) return false; + + // Text search + if (!SearchText.IsEmpty()) + { + if (!Entry->Name.Contains(SearchText, ESearchCase::IgnoreCase) && + !Entry->TypeLabel.Contains(SearchText, ESearchCase::IgnoreCase)) + { + return false; + } + } + + return true; +} + +TSharedPtr SMjArticulationOutliner::FilterTree(const TSharedPtr& Entry) const +{ + // Recursively filter: keep a node if it passes OR if any descendant passes + TArray> FilteredChildren; + for (const auto& Child : Entry->Children) + { + TSharedPtr FilteredChild = FilterTree(Child); + if (FilteredChild.IsValid()) + { + FilteredChildren.Add(FilteredChild); + } + } + + bool bSelfPasses = PassesFilter(Entry); + + if (!bSelfPasses && FilteredChildren.IsEmpty()) + return nullptr; + + // Create a shallow copy with filtered children + TSharedPtr Result = MakeShared(); + Result->Name = Entry->Name; + Result->TypeLabel = Entry->TypeLabel; + Result->ComponentTemplate = Entry->ComponentTemplate; + Result->SCSNode = Entry->SCSNode; + Result->Children = FilteredChildren; + return Result; +} + +TSharedRef SMjArticulationOutliner::OnGenerateRow( + TSharedPtr Entry, + const TSharedRef& OwnerTable) +{ + // Color code by type + FLinearColor TypeColor(0.5f, 0.7f, 1.0f); + UObject* Comp = Entry->ComponentTemplate.Get(); + if (Comp) + { + if (IsBody(Comp)) TypeColor = FLinearColor(0.9f, 0.7f, 0.3f); + else if (IsGeom(Comp)) TypeColor = FLinearColor(0.5f, 0.8f, 0.5f); + else if (IsJoint(Comp)) TypeColor = FLinearColor(0.5f, 0.6f, 1.0f); + else if (IsSensor(Comp)) TypeColor = FLinearColor(0.8f, 0.5f, 0.8f); + else if (IsActuator(Comp)) TypeColor = FLinearColor(1.0f, 0.5f, 0.4f); + else if (IsDefault(Comp)) TypeColor = FLinearColor(0.6f, 0.6f, 0.6f); + else if (IsSite(Comp)) TypeColor = FLinearColor(0.4f, 0.9f, 0.9f); + } + + return SNew(STableRow>, OwnerTable) + [ + SNew(SHorizontalBox) + + SHorizontalBox::Slot() + .AutoWidth() + .Padding(2.f, 1.f) + [ + SNew(STextBlock) + .Text(FText::FromString(FString::Printf(TEXT("[%s]"), *Entry->TypeLabel))) + .ColorAndOpacity(FSlateColor(TypeColor)) + .Font(FCoreStyle::GetDefaultFontStyle("Regular", 8)) + ] + + SHorizontalBox::Slot() + .FillWidth(1.0f) + .Padding(4.f, 1.f) + [ + SNew(STextBlock) + .Text(FText::FromString(Entry->Name)) + ] + ]; +} + +void SMjArticulationOutliner::OnGetChildren( + TSharedPtr Entry, + TArray>& OutChildren) +{ + OutChildren = Entry->Children; +} + +void SMjArticulationOutliner::OnSelectionChanged( + TSharedPtr Entry, ESelectInfo::Type SelectInfo) +{ + if (!Entry.IsValid() || !Entry->SCSNode || !GEditor) return; + + UBlueprint* BP = CurrentBP.Get(); + if (!BP) return; + + // Open/focus the BP editor and select the SCS node + UAssetEditorSubsystem* Sub = GEditor->GetEditorSubsystem(); + if (!Sub) return; + + IAssetEditorInstance* EditorInstance = Sub->FindEditorForAsset(BP, /*bFocusIfOpen=*/true); + if (!EditorInstance) + { + Sub->OpenEditorForAsset(BP); + EditorInstance = Sub->FindEditorForAsset(BP, true); + } + + if (FBlueprintEditor* BPEditor = static_cast(EditorInstance)) + { + BPEditor->FindAndSelectSubobjectEditorTreeNode( + Cast(Entry->SCSNode->ComponentTemplate), /*IsCntrlDown=*/false); + } +} + +FString SMjArticulationOutliner::GetTypeLabel(UObject* Comp) +{ + if (!Comp) return TEXT("Unknown"); + + // Use the specific class name for joints/geoms + if (IsJoint(Comp)) + { + FString ClassName = Comp->GetClass()->GetName(); + ClassName.RemoveFromStart(TEXT("Mj")); + return ClassName; + } + if (IsGeom(Comp)) + { + FString ClassName = Comp->GetClass()->GetName(); + ClassName.RemoveFromStart(TEXT("Mj")); + if (ClassName == TEXT("Geom")) return TEXT("Geom"); + return ClassName; + } + + if (IsBody(Comp)) return TEXT("Body"); + if (IsSensor(Comp)) return TEXT("Sensor"); + if (IsActuator(Comp)) return TEXT("Actuator"); + if (IsDefault(Comp)) return TEXT("Default"); + if (IsSite(Comp)) return TEXT("Site"); + return Comp->GetClass()->GetName(); +} + +bool SMjArticulationOutliner::IsBody(UObject* Comp) { return Comp && Comp->IsA(); } +bool SMjArticulationOutliner::IsGeom(UObject* Comp) { return Comp && Comp->IsA(); } +bool SMjArticulationOutliner::IsJoint(UObject* Comp) { return Comp && Comp->IsA(); } +bool SMjArticulationOutliner::IsSensor(UObject* Comp) { return Comp && Comp->IsA(); } +bool SMjArticulationOutliner::IsActuator(UObject* Comp) { return Comp && Comp->IsA(); } +bool SMjArticulationOutliner::IsDefault(UObject* Comp) { return Comp && Comp->IsA(); } +bool SMjArticulationOutliner::IsSite(UObject* Comp) { return Comp && Comp->IsA(); } + +FText SMjArticulationOutliner::GetSummaryText() const +{ + int32 Bodies = 0, Geoms = 0, Joints = 0, Sensors = 0, Actuators = 0; + + // Count from the unfiltered tree + TFunction>&)> CountAll = + [&](const TArray>& Entries) + { + for (const auto& Entry : Entries) + { + UObject* Comp = Entry->ComponentTemplate.Get(); + if (Comp) + { + if (IsBody(Comp)) Bodies++; + else if (IsGeom(Comp)) Geoms++; + else if (IsJoint(Comp)) Joints++; + else if (IsSensor(Comp)) Sensors++; + else if (IsActuator(Comp)) Actuators++; + } + CountAll(Entry->Children); + } + }; + CountAll(RootEntries); + + return FText::FromString(FString::Printf( + TEXT("%d Bodies | %d Geoms | %d Joints | %d Sensors | %d Actuators"), + Bodies, Geoms, Joints, Sensors, Actuators)); +} diff --git a/Source/URLabEditor/Private/Tests/MjImporterTest.cpp b/Source/URLabEditor/Private/Tests/MjImporterTest.cpp index 7bc0c68..63309dd 100644 --- a/Source/URLabEditor/Private/Tests/MjImporterTest.cpp +++ b/Source/URLabEditor/Private/Tests/MjImporterTest.cpp @@ -45,14 +45,35 @@ FString SanitizeXmlForComparison(const FString& InXml, const FString& PrefixToSt OutXml = OutXml.Replace(*PrefixToStrip, TEXT("")); } - // 2. Strip auto-generated names (e.g. name="AUTONAME_Geom", name="AUTONAME_Geom_0", etc.) - // We target anything starting with AUTONAME_ inside a name attribute. - const FRegexPattern AutoNamePattern(TEXT(" name=\"AUTONAME_[^\"]*\"")); - FRegexMatcher AutoNameMatcher(AutoNamePattern, OutXml); - while (AutoNameMatcher.FindNext()) + // 2. Strip auto-generated names produced by the importer for unnamed XML elements. + // Covers new contextual names (Geom_Box, HingeJoint, etc.) and legacy AUTONAME_*. + TArray AutoNamePatterns; + AutoNamePatterns.Emplace(TEXT(" name=\"AUTONAME_[^\"]*\"")); + AutoNamePatterns.Emplace(TEXT(" name=\"Geom_[^\"]*\"")); + AutoNamePatterns.Emplace(TEXT(" name=\"[A-Z][a-z]*Joint[^\"]*\"")); + AutoNamePatterns.Emplace(TEXT(" name=\"FreeJoint[^\"]*\"")); + AutoNamePatterns.Emplace(TEXT(" name=\"Site[^\"]*\"")); + AutoNamePatterns.Emplace(TEXT(" name=\"Inertial[^\"]*\"")); + AutoNamePatterns.Emplace(TEXT(" name=\"Camera[^\"]*\"")); + AutoNamePatterns.Emplace(TEXT(" name=\"[A-Z][a-z]*Sensor[^\"]*\"")); + AutoNamePatterns.Emplace(TEXT(" name=\"[A-Z][a-z]*Actuator[^\"]*\"")); + AutoNamePatterns.Emplace(TEXT(" name=\"[A-Z][a-z]*Tendon[^\"]*\"")); + AutoNamePatterns.Emplace(TEXT(" name=\"[a-zA-Z_]*_Body[^\"]*\"")); + AutoNamePatterns.Emplace(TEXT(" name=\"[a-zA-Z_]*_Frame[^\"]*\"")); + AutoNamePatterns.Emplace(TEXT(" name=\"ContactPair_[^\"]*\"")); + AutoNamePatterns.Emplace(TEXT(" name=\"ContactExclude_[^\"]*\"")); + AutoNamePatterns.Emplace(TEXT(" name=\"Eq_[^\"]*\"")); + AutoNamePatterns.Emplace(TEXT(" name=\"Keyframe[^\"]*\"")); + AutoNamePatterns.Emplace(TEXT(" name=\"Default[A-Z][^\"]*\"")); + + for (const FRegexPattern& Pattern : AutoNamePatterns) { - OutXml = OutXml.Replace(*AutoNameMatcher.GetCaptureGroup(0), TEXT("")); - AutoNameMatcher = FRegexMatcher(AutoNamePattern, OutXml); + FRegexMatcher Matcher(Pattern, OutXml); + while (Matcher.FindNext()) + { + OutXml = OutXml.Replace(*Matcher.GetCaptureGroup(0), TEXT("")); + Matcher = FRegexMatcher(Pattern, OutXml); + } } // 3. Collapse whitespace and newlines for robust comparison diff --git a/Source/URLabEditor/Private/URLabEditor.cpp b/Source/URLabEditor/Private/URLabEditor.cpp index c6c1d70..f435b5c 100644 --- a/Source/URLabEditor/Private/URLabEditor.cpp +++ b/Source/URLabEditor/Private/URLabEditor.cpp @@ -21,23 +21,112 @@ // CoACD (MIT), and libzmq (MPL 2.0). See ThirdPartyNotices.txt for details. #include "URLabEditor.h" #include "URLabEditorLogging.h" +#include "MjEditorStyle.h" DEFINE_LOG_CATEGORY(LogURLabEditor); #include "PropertyEditorModule.h" #include "MuJoCo/Components/Geometry/MjGeom.h" -#include "MjGeomDetailCustomization.h" +#include "MjComponentDetailCustomizations.h" +#include "MuJoCo/Components/Physics/MjContactPair.h" +#include "MuJoCo/Components/Physics/MjContactExclude.h" +#include "MuJoCo/Components/Constraints/MjEquality.h" #include "LevelEditor.h" #include "Framework/MultiBox/MultiBoxBuilder.h" #include "MuJoCo/Components/QuickConvert/MjQuickConvertComponent.h" #include "ScopedTransaction.h" +#include "Engine/SimpleConstructionScript.h" +#include "Engine/SCS_Node.h" +#include "MuJoCo/Components/Sensors/MjSensor.h" +#include "MuJoCo/Components/Actuators/MjActuator.h" +#include "MuJoCo/Components/Joints/MjJoint.h" +#include "MuJoCo/Components/Geometry/MjSite.h" +#include "MuJoCo/Components/Tendons/MjTendon.h" +#include "MuJoCo/Components/Bodies/MjBody.h" +#include "MuJoCo/Components/Defaults/MjDefault.h" +#include "MuJoCo/Components/Tendons/MjTendon.h" +#include "MuJoCo/Core/MjArticulation.h" +#include "MuJoCo/Components/Physics/MjContactPair.h" +#include "MuJoCo/Components/Physics/MjContactExclude.h" +#include "MuJoCo/Components/Constraints/MjEquality.h" +#include "SMjArticulationOutliner.h" +#include "Kismet2/BlueprintEditorUtils.h" +#include "Framework/Docking/WorkspaceItem.h" void FURLabEditorModule::StartupModule() { + FMjEditorStyle::Initialize(); + FPropertyEditorModule& PropertyModule = FModuleManager::LoadModuleChecked("PropertyEditor"); + // Register geom customization on all subclasses + { + TArray GeomClasses; + GetDerivedClasses(UMjGeom::StaticClass(), GeomClasses, true); + GeomClasses.Add(UMjGeom::StaticClass()); + for (UClass* Class : GeomClasses) + { + PropertyModule.RegisterCustomClassLayout( + Class->GetFName(), + FOnGetDetailCustomizationInstance::CreateStatic(&FMjGeomDetailCustomization::MakeInstance)); + } + } + // Register actuator customization on all subclasses + { + TArray ActuatorClasses; + GetDerivedClasses(UMjActuator::StaticClass(), ActuatorClasses, true); + ActuatorClasses.Add(UMjActuator::StaticClass()); + for (UClass* Class : ActuatorClasses) + { + PropertyModule.RegisterCustomClassLayout( + Class->GetFName(), + FOnGetDetailCustomizationInstance::CreateStatic(&FMjActuatorDetailCustomization::MakeInstance)); + } + } + // Register sensor customization on all subclasses + { + TArray SensorClasses; + GetDerivedClasses(UMjSensor::StaticClass(), SensorClasses, true); + SensorClasses.Add(UMjSensor::StaticClass()); + for (UClass* Class : SensorClasses) + { + PropertyModule.RegisterCustomClassLayout( + Class->GetFName(), + FOnGetDetailCustomizationInstance::CreateStatic(&FMjSensorDetailCustomization::MakeInstance)); + } + } + PropertyModule.RegisterCustomClassLayout( + UMjContactPair::StaticClass()->GetFName(), + FOnGetDetailCustomizationInstance::CreateStatic(&FMjContactPairDetailCustomization::MakeInstance)); PropertyModule.RegisterCustomClassLayout( - UMjGeom::StaticClass()->GetFName(), - FOnGetDetailCustomizationInstance::CreateStatic(&FMjGeomDetailCustomization::MakeInstance)); + UMjContactExclude::StaticClass()->GetFName(), + FOnGetDetailCustomizationInstance::CreateStatic(&FMjContactExcludeDetailCustomization::MakeInstance)); + PropertyModule.RegisterCustomClassLayout( + UMjEquality::StaticClass()->GetFName(), + FOnGetDetailCustomizationInstance::CreateStatic(&FMjEqualityDetailCustomization::MakeInstance)); + // Register joint customization on all subclasses + { + TArray JointClasses; + GetDerivedClasses(UMjJoint::StaticClass(), JointClasses, true); + JointClasses.Add(UMjJoint::StaticClass()); + for (UClass* Class : JointClasses) + { + PropertyModule.RegisterCustomClassLayout( + Class->GetFName(), + FOnGetDetailCustomizationInstance::CreateStatic(&FMjJointDetailCustomization::MakeInstance)); + } + } + PropertyModule.RegisterCustomClassLayout( + UMjBody::StaticClass()->GetFName(), + FOnGetDetailCustomizationInstance::CreateStatic(&FMjBodyDetailCustomization::MakeInstance)); + PropertyModule.RegisterCustomClassLayout( + UMjDefault::StaticClass()->GetFName(), + FOnGetDetailCustomizationInstance::CreateStatic(&FMjDefaultDetailCustomization::MakeInstance)); + PropertyModule.RegisterCustomClassLayout( + UMjSite::StaticClass()->GetFName(), + FOnGetDetailCustomizationInstance::CreateStatic(&FMjSiteDetailCustomization::MakeInstance)); + PropertyModule.RegisterCustomClassLayout( + UMjTendon::StaticClass()->GetFName(), + FOnGetDetailCustomizationInstance::CreateStatic(&FMjTendonDetailCustomization::MakeInstance)); PropertyModule.NotifyCustomizationModuleChanged(); // Register viewport actor context menu extender @@ -48,14 +137,63 @@ void FURLabEditorModule::StartupModule() auto& Extenders = LevelEditorModule.GetAllLevelViewportContextMenuExtenders(); Extenders.Add(MenuExtender); ViewportContextMenuExtenderHandle = Extenders.Last().GetHandle(); + + // Register auto-parenting hook for MuJoCo components + OnObjectModifiedHandle = FCoreUObjectDelegates::OnObjectModified.AddRaw(this, &FURLabEditorModule::OnObjectModified); + + // Register MuJoCo Outliner tab (guard against double registration on hot-reload) + FGlobalTabmanager::Get()->UnregisterNomadTabSpawner(TEXT("MjArticulationOutliner")); + FGlobalTabmanager::Get()->RegisterNomadTabSpawner( + TEXT("MjArticulationOutliner"), + FOnSpawnTab::CreateLambda([](const FSpawnTabArgs& Args) -> TSharedRef + { + TSharedRef Outliner = SNew(SMjArticulationOutliner); + + return SNew(SDockTab) + .TabRole(ETabRole::NomadTab) + .Label(FText::FromString(TEXT("MuJoCo Outliner"))) + [ + Outliner + ]; + })) + .SetDisplayName(FText::FromString(TEXT("MuJoCo Outliner"))) + .SetTooltipText(FText::FromString(TEXT("Filtered view of MuJoCo articulation components"))); + } void FURLabEditorModule::ShutdownModule() { + FMjEditorStyle::Shutdown(); + + FCoreUObjectDelegates::OnObjectModified.Remove(OnObjectModifiedHandle); + + FGlobalTabmanager::Get()->UnregisterNomadTabSpawner(TEXT("MjArticulationOutliner")); + if (FModuleManager::Get().IsModuleLoaded("PropertyEditor")) { FPropertyEditorModule& PropertyModule = FModuleManager::GetModuleChecked("PropertyEditor"); - PropertyModule.UnregisterCustomClassLayout(UMjGeom::StaticClass()->GetFName()); + // Unregister all subclass customizations + auto UnregisterWithSubclasses = [&](UClass* BaseClass) + { + TArray Classes; + GetDerivedClasses(BaseClass, Classes, true); + Classes.Add(BaseClass); + for (UClass* Class : Classes) + { + PropertyModule.UnregisterCustomClassLayout(Class->GetFName()); + } + }; + UnregisterWithSubclasses(UMjGeom::StaticClass()); + UnregisterWithSubclasses(UMjActuator::StaticClass()); + UnregisterWithSubclasses(UMjSensor::StaticClass()); + UnregisterWithSubclasses(UMjJoint::StaticClass()); + PropertyModule.UnregisterCustomClassLayout(UMjContactPair::StaticClass()->GetFName()); + PropertyModule.UnregisterCustomClassLayout(UMjContactExclude::StaticClass()->GetFName()); + PropertyModule.UnregisterCustomClassLayout(UMjEquality::StaticClass()->GetFName()); + PropertyModule.UnregisterCustomClassLayout(UMjBody::StaticClass()->GetFName()); + PropertyModule.UnregisterCustomClassLayout(UMjDefault::StaticClass()->GetFName()); + PropertyModule.UnregisterCustomClassLayout(UMjSite::StaticClass()->GetFName()); + PropertyModule.UnregisterCustomClassLayout(UMjTendon::StaticClass()->GetFName()); } if (FModuleManager::Get().IsModuleLoaded("LevelEditor")) @@ -167,4 +305,104 @@ void FURLabEditorModule::ApplyQuickConvert(TArray> Actors Applied, bStatic, bComplex); } +void FURLabEditorModule::OnObjectModified(UObject* Object) +{ + if (bIsAutoParenting) return; + + USimpleConstructionScript* SCS = Cast(Object); + if (!SCS) return; + + UBlueprint* BP = SCS->GetBlueprint(); + if (!BP || !BP->GeneratedClass || !BP->GeneratedClass->IsChildOf(AMjArticulation::StaticClass())) + return; + + // Defer to next tick so the SCS tree is fully updated before we scan + TWeakObjectPtr WeakSCS = SCS; + TWeakObjectPtr WeakBP = BP; + GEditor->GetTimerManager()->SetTimerForNextTick([this, WeakSCS, WeakBP]() + { + if (bIsAutoParenting) return; + USimpleConstructionScript* SCSPtr = WeakSCS.Get(); + UBlueprint* BPPtr = WeakBP.Get(); + if (!SCSPtr || !BPPtr) return; + + TArray AllNodes = SCSPtr->GetAllNodes(); + bIsAutoParenting = true; + bool bMoved = false; + + for (USCS_Node* Node : AllNodes) + { + bMoved |= AutoParentSCSNode(Node, SCSPtr); + + } + bIsAutoParenting = false; + + if (bMoved) + { + FBlueprintEditorUtils::MarkBlueprintAsStructurallyModified(BPPtr); + } + }); +} + +bool FURLabEditorModule::AutoParentSCSNode(USCS_Node* Node, USimpleConstructionScript* SCS) +{ + if (!Node || !Node->ComponentTemplate) return false; + + // Determine the correct parent folder name for this component type + FString TargetParentName; + if (Node->ComponentTemplate->IsA()) TargetParentName = TEXT("SensorsRoot"); + else if (Node->ComponentTemplate->IsA()) TargetParentName = TEXT("ActuatorsRoot"); + else if (Node->ComponentTemplate->IsA()) TargetParentName = TEXT("DefaultsRoot"); + else if (Node->ComponentTemplate->IsA()) TargetParentName = TEXT("TendonsRoot"); + else if (Node->ComponentTemplate->IsA() || Node->ComponentTemplate->IsA()) + TargetParentName = TEXT("ContactsRoot"); + else if (Node->ComponentTemplate->IsA()) TargetParentName = TEXT("EqualitiesRoot"); + else return false; + + // Check if already correctly parented + USCS_Node* CurrentParent = SCS->FindParentNode(Node); + if (CurrentParent && CurrentParent->GetVariableName().ToString() == TargetParentName) + return false; + + // Skip components that are under DefaultsRoot — they are default templates + // and must not be moved to organizational folders + { + USCS_Node* Ancestor = CurrentParent; + while (Ancestor) + { + if (Ancestor->GetVariableName().ToString() == TEXT("DefaultsRoot")) + return false; + Ancestor = SCS->FindParentNode(Ancestor); + } + } + + // Find the target parent node + USCS_Node* TargetParent = nullptr; + for (USCS_Node* SearchNode : SCS->GetAllNodes()) + { + if (SearchNode->GetVariableName().ToString() == TargetParentName) + { + TargetParent = SearchNode; + break; + } + } + + if (!TargetParent) return false; + + // Reparent + if (CurrentParent) + { + CurrentParent->RemoveChildNode(Node); + } + else + { + SCS->RemoveNode(Node, /*bNotify=*/false); + } + TargetParent->AddChildNode(Node); + + FString CompName = Node->GetVariableName().ToString(); + UE_LOG(LogURLabEditor, Log, TEXT("[Auto-Parent] Moved '%s' to '%s'"), *CompName, *TargetParentName); + return true; +} + IMPLEMENT_MODULE(FURLabEditorModule, URLabEditor) diff --git a/Source/URLabEditor/Public/MjComponentDetailCustomizations.h b/Source/URLabEditor/Public/MjComponentDetailCustomizations.h new file mode 100644 index 0000000..03e8684 --- /dev/null +++ b/Source/URLabEditor/Public/MjComponentDetailCustomizations.h @@ -0,0 +1,113 @@ +// 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. + +#pragma once + +#include "IDetailCustomization.h" + +/** Detail customization for UMjActuator — hides internal properties. */ +class FMjActuatorDetailCustomization : public IDetailCustomization +{ +public: + static TSharedRef MakeInstance(); + virtual void CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) override; +}; + +/** Detail customization for UMjSensor — hides internal properties. */ +class FMjSensorDetailCustomization : public IDetailCustomization +{ +public: + static TSharedRef MakeInstance(); + virtual void CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) override; +}; + +/** Detail customization for UMjContactPair — hides internal properties. */ +class FMjContactPairDetailCustomization : public IDetailCustomization +{ +public: + static TSharedRef MakeInstance(); + virtual void CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) override; +}; + +/** Detail customization for UMjContactExclude — hides internal properties. */ +class FMjContactExcludeDetailCustomization : public IDetailCustomization +{ +public: + static TSharedRef MakeInstance(); + virtual void CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) override; +}; + +/** Detail customization for UMjEquality. */ +class FMjEqualityDetailCustomization : public IDetailCustomization +{ +public: + static TSharedRef MakeInstance(); + virtual void CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) override; +}; + +/** Detail customization for UMjJoint — hides string properties. */ +class FMjJointDetailCustomization : public IDetailCustomization +{ +public: + static TSharedRef MakeInstance(); + virtual void CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) override; +}; + +/** Detail customization for UMjBody. */ +class FMjBodyDetailCustomization : public IDetailCustomization +{ +public: + static TSharedRef MakeInstance(); + virtual void CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) override; +}; + +/** Detail customization for UMjDefault — hides string properties synced at compile time. */ +class FMjDefaultDetailCustomization : public IDetailCustomization +{ +public: + static TSharedRef MakeInstance(); + virtual void CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) override; +}; + +/** Detail customization for UMjSite — hides string properties. */ +class FMjSiteDetailCustomization : public IDetailCustomization +{ +public: + static TSharedRef MakeInstance(); + virtual void CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) override; +}; + +/** Detail customization for UMjTendon — hides string properties. */ +class FMjTendonDetailCustomization : public IDetailCustomization +{ +public: + static TSharedRef MakeInstance(); + virtual void CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) override; +}; + +/** Detail customization for UMjGeom — hides internal properties and adds CoACD decomposition buttons. */ +class FMjGeomDetailCustomization : public IDetailCustomization +{ +public: + static TSharedRef MakeInstance(); + virtual void CustomizeDetails(IDetailLayoutBuilder& DetailBuilder) override; +}; diff --git a/Source/URLabEditor/Public/MjEditorStyle.h b/Source/URLabEditor/Public/MjEditorStyle.h new file mode 100644 index 0000000..1f42cc7 --- /dev/null +++ b/Source/URLabEditor/Public/MjEditorStyle.h @@ -0,0 +1,43 @@ +// 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. + +#pragma once + +#include "Styling/SlateStyle.h" + +/** + * @class FMjEditorStyle + * @brief Registers custom Slate icons for MuJoCo component types + * so they appear in the Blueprint component tree. + */ +class FMjEditorStyle +{ +public: + static void Initialize(); + static void Shutdown(); + + static const ISlateStyle& Get(); + static FName GetStyleSetName(); + +private: + static TSharedPtr StyleInstance; +}; diff --git a/Source/URLabEditor/Public/SMjArticulationOutliner.h b/Source/URLabEditor/Public/SMjArticulationOutliner.h new file mode 100644 index 0000000..b001638 --- /dev/null +++ b/Source/URLabEditor/Public/SMjArticulationOutliner.h @@ -0,0 +1,114 @@ +// 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. + +#pragma once + +#include "CoreMinimal.h" +#include "Widgets/SCompoundWidget.h" +#include "Widgets/Views/STreeView.h" +#include "Widgets/Input/SComboBox.h" + +class UBlueprint; +class USCS_Node; + +/** + * @brief A single entry in the MuJoCo Outliner tree. + */ +struct FMjOutlinerEntry +{ + FString Name; + FString TypeLabel; // e.g. "Body", "HingeJoint", "Sensor" + TWeakObjectPtr ComponentTemplate; + USCS_Node* SCSNode = nullptr; + TArray> Children; +}; + +/** + * @class SMjArticulationOutliner + * @brief Dockable editor panel that shows a filtered, searchable tree view + * of AMjArticulation Blueprints. Auto-detects the currently open + * articulation BP and refreshes when it changes. + */ +class SMjArticulationOutliner : public SCompoundWidget +{ +public: + SLATE_BEGIN_ARGS(SMjArticulationOutliner) {} + SLATE_END_ARGS() + + void Construct(const FArguments& InArgs); + virtual void Tick(const FGeometry& AllottedGeometry, const double InCurrentTime, const float InDeltaTime) override; + +private: + /** Rebuild tree from the active BP. */ + void RefreshFromBlueprint(UBlueprint* BP); + void RebuildTree(); + void CollectNodes(USCS_Node* Node, TSharedPtr ParentEntry); + + /** Filter toggles */ + bool bShowBodies = true; + bool bShowGeoms = true; + bool bShowJoints = true; + bool bShowSensors = true; + bool bShowActuators = true; + bool bShowDefaults = false; // Off by default — usually not what you're navigating + bool bShowSites = true; + bool bShowOther = false; + + FString SearchText; + float TimeSinceLastRefresh = 0.f; + + TWeakObjectPtr CurrentBP; + TArray> RootEntries; + TArray> FilteredRootEntries; + + TSharedPtr>> TreeView; + + /** BP selector */ + TArray> AvailableBPs; + TArray> AvailableBPNames; + TSharedPtr SelectedBPName; + TSharedPtr>> BPComboBox; + void RefreshAvailableBPs(); + void OnBPSelected(TSharedPtr Selected, ESelectInfo::Type SelectInfo); + + /** Tree view callbacks */ + TSharedRef OnGenerateRow(TSharedPtr Entry, const TSharedRef& OwnerTable); + void OnGetChildren(TSharedPtr Entry, TArray>& OutChildren); + void OnSelectionChanged(TSharedPtr Entry, ESelectInfo::Type SelectInfo); + + /** Apply search and type filters, producing FilteredRootEntries */ + void ApplyFilters(); + bool PassesFilter(const TSharedPtr& Entry) const; + TSharedPtr FilterTree(const TSharedPtr& Entry) const; + + /** Type classification */ + static FString GetTypeLabel(UObject* ComponentTemplate); + static bool IsBody(UObject* Comp); + static bool IsGeom(UObject* Comp); + static bool IsJoint(UObject* Comp); + static bool IsSensor(UObject* Comp); + static bool IsActuator(UObject* Comp); + static bool IsDefault(UObject* Comp); + static bool IsSite(UObject* Comp); + + FText GetSummaryText() const; +}; diff --git a/Source/URLabEditor/Public/URLabEditor.h b/Source/URLabEditor/Public/URLabEditor.h index c5a8263..70f02b0 100644 --- a/Source/URLabEditor/Public/URLabEditor.h +++ b/Source/URLabEditor/Public/URLabEditor.h @@ -32,8 +32,13 @@ class FURLabEditorModule : public IModuleInterface private: FDelegateHandle ViewportContextMenuExtenderHandle; + FDelegateHandle OnObjectModifiedHandle; + bool bIsAutoParenting = false; static TSharedRef OnExtendActorContextMenu(const TSharedRef CommandList, const TArray SelectedActors); static void BuildQuickConvertSubMenu(FMenuBuilder& MenuBuilder, TArray SelectedActors); static void ApplyQuickConvert(TArray> Actors, bool bStatic, bool bComplex); + + void OnObjectModified(UObject* Object); + static bool AutoParentSCSNode(class USCS_Node* Node, class USimpleConstructionScript* SCS); }; diff --git a/Source/URLabEditor/URLabEditor.Build.cs b/Source/URLabEditor/URLabEditor.Build.cs index 517678a..022a29f 100644 --- a/Source/URLabEditor/URLabEditor.Build.cs +++ b/Source/URLabEditor/URLabEditor.Build.cs @@ -30,7 +30,8 @@ public URLabEditor(ReadOnlyTargetRules Target) : base(Target) { "InputCore", "RenderCore", - "DesktopPlatform" + "DesktopPlatform", + "Kismet" }); } } diff --git a/docs/architecture.md b/docs/architecture.md index 7ebdb7e..80a53fa 100644 --- a/docs/architecture.md +++ b/docs/architecture.md @@ -561,7 +561,19 @@ Registered to the spec during Setup (after bodies/joints). At runtime, `AMjArtic - **MjSimulate widget** (`WBP_MjSimulate`): Physics options, per-actuator sliders, debug visualization toggles, replay controls, possess button. Auto-created at BeginPlay. - **ValidateSpec:** Blueprint compile hook on `AMjArticulation`. Creates a temporary spec, runs `mj_compile()`, and reports errors without affecting the running simulation. -- **MjGeomDetailCustomization** (`Source/URLabEditor/`): Custom Details panel for geom properties in the editor. +- **MjComponentDetailCustomizations** (`Source/URLabEditor/`): Detail customizations for all MuJoCo component types — hides internal properties (DefaultClass pointers, synced names) and adds CoACD decomposition buttons for mesh geoms. Component-reference dropdowns (Target, Default Class, etc.) use `meta=(GetOptions)` on UPROPERTY declarations. +- **MjEditorStyle** (`Source/URLabEditor/`): Custom Slate icons for all MuJoCo component types in the Blueprint component tree. Icons are loaded from `Resources/Icons/` PNGs. +- **MuJoCo Outliner** (`SMjArticulationOutliner`): Dockable editor tab (Window menu) that shows a filtered, searchable tree of an articulation Blueprint's component hierarchy. Auto-detects open articulation BPs, provides type filter toggles and summary counts. + +### Editor Module Hooks (`FURLabEditorModule`) + +The editor module (`Source/URLabEditor/`) registers several hooks that improve the Blueprint editing workflow: + +| Hook | Trigger | What It Does | +|------|---------|--------------| +| `OnObjectModified` (SCS) | Any SCS modification | **Auto-parenting:** defers to next tick, then scans all nodes and moves sensors/actuators/defaults/tendons/contacts/equalities under their organizational root folders. | +| `OnObjectModified` (USCS_Node) | Variable name rename | **Default ClassName sync:** keeps `UMjDefault::ClassName` in sync with the SCS variable name for user-created defaults. | +| `OnBlueprintPreCompile` | Blueprint Compile button | **FixupDefaultFlags:** walks everything under `DefaultsRoot` and marks all `UMjComponent` descendants as `bIsDefault = true`. Ensures user-added defaults are properly flagged before the spec is built. | --- @@ -582,9 +594,9 @@ Auto-created from `WBP_MjSimulate` Blueprint asset at BeginPlay. Provides: - Record/Replay/Snapshot controls - Possess button (attaches spring arm camera) -### MjGeomDetailCustomization +### Detail Panel Customizations -Custom Details panel for `UMjGeom` components. Adds "Decompose Mesh" and "Remove Decomposition" buttons for CoACD operations directly in the editor. +All MuJoCo component types have registered `IDetailCustomization` classes (in `MjComponentDetailCustomizations.h/.cpp`) that hide internal properties like `DefaultClass` pointers and auto-synced string fields. Component-reference properties (e.g. `TargetName`, `MjClassName`, `Geom1`) use UE's native `meta=(GetOptions="FunctionName")` UPROPERTY specifier to render as dropdown combo boxes — the option lists are populated by `UMjComponent::GetSiblingComponentOptions()`, which scans the Blueprint's SCS tree. Mesh geom components additionally show "Decompose Mesh" and "Remove Decomposition" buttons for CoACD operations. --- diff --git a/docs/getting_started.md b/docs/getting_started.md index aaae737..c201671 100644 --- a/docs/getting_started.md +++ b/docs/getting_started.md @@ -42,6 +42,7 @@ This is **not required** if you only use the plugin through the editor, Blueprin 1. Get a robot XML (e.g., from [MuJoCo Menagerie](https://github.com/google-deepmind/mujoco_menagerie)). 2. Drag the XML into the Unreal Content Browser. On first import, the editor will prompt to install the required Python packages (`trimesh`, `numpy`, `scipy`) — by default these are installed to UE's bundled Python, so no external setup is needed. You can also choose your own Python interpreter if preferred. 3. A Blueprint is auto-generated with all joints, bodies, actuators, and sensors as components. +4. See the [Articulation Builder Guide](guides/articulation_builder.md) for editing and building articulations. ### Quick Convert (Static Meshes) diff --git a/docs/guides/articulation_builder.md b/docs/guides/articulation_builder.md new file mode 100644 index 0000000..a2210fc --- /dev/null +++ b/docs/guides/articulation_builder.md @@ -0,0 +1,182 @@ +# Articulation Builder Guide + +This guide covers how to build and edit MuJoCo articulations in the Unreal Blueprint editor — both imported from MJCF XML and built from scratch. + +--- + +## Overview + +An `AMjArticulation` Blueprint contains a hierarchy of MuJoCo components that mirror the MJCF XML structure. When placed in a level and simulated, the plugin converts this hierarchy into a MuJoCo spec, compiles it, and runs physics. + +The component hierarchy is organized into folders: + +``` +ArticulationRoot +├── worldbody (MjWorldBody) +│ └── body1 (MjBody) +│ ├── Geom_Box (MjBox) +│ ├── HingeJoint (MjHingeJoint) +│ └── body2 (MjBody) +│ └── ... +├── DefinitionsRoot +│ ├── DefaultsRoot +│ │ └── main (MjDefault) +│ │ └── robot (MjDefault) +│ ├── ActuatorsRoot +│ │ └── MotorActuator (MjMotorActuator) +│ ├── SensorsRoot +│ │ └── JointposSensor (MjJointPosSensor) +│ ├── TendonsRoot +│ ├── ContactsRoot +│ ├── EqualitiesRoot +│ └── KeyframesRoot +``` + +--- + +## Importing from MJCF XML + +1. Drag an `.xml` file into the Content Browser +2. The plugin auto-converts meshes and generates the Blueprint +3. See [MJCF Import Guide](mujoco_import.md) for details + +--- + +## Building from Scratch + +### Creating the Blueprint + +1. Right-click in Content Browser → Blueprint Class → select `MjArticulation` +2. Open the Blueprint editor + +### Adding Bodies + +1. In the Components panel, click **Add** → search for `MjBody` +2. Attach it as a child of `worldbody` +3. Set the body's transform (location/rotation) +4. Nest bodies to create kinematic chains (e.g. upper arm → forearm → hand) + +### Adding Geoms (Collision/Visual Shapes) + +1. Select a body → **Add** → choose a geom type: + - `MjBox`, `MjSphere`, `MjCylinder` — primitive shapes with built-in visualizers + - `MjMeshGeom` — for custom static mesh assets (auto-sets type to Mesh) +2. Geoms attach as children of bodies +3. Set size via the UE scale gizmo (primitives) or assign a mesh asset (mesh geoms) +4. **Material Override**: primitives support an `OverrideMaterial` property for visual customization + +### Adding Joints + +1. Select a body → **Add** → choose a joint type: + - `MjHingeJoint` — 1-DOF rotation + - `MjSlideJoint` — 1-DOF translation + - `MjBallJoint` — 3-DOF spherical + - `MjFreeJoint` — 6-DOF (root bodies) +2. Joints attach as children of the body they actuate +3. Configure axis, limits, stiffness, damping in the detail panel + +### Adding Actuators + +1. **Add** → search for actuator type (e.g. `MjMotorActuator`, `MjPositionActuator`) +2. Actuators are **auto-parented** to `ActuatorsRoot` when added +3. Use the **Target** dropdown in the detail panel to select which joint/tendon/site the actuator controls + +### Adding Sensors + +1. **Add** → search for sensor type (e.g. `MjJointPosSensor`, `MjTouchSensor`) +2. Sensors are **auto-parented** to `SensorsRoot` +3. Use the **Target** dropdown to select what the sensor monitors + +### Setting Up Default Classes + +Default classes define shared properties (friction, damping, etc.) that multiple components can inherit from. + +1. **Add** → `MjDefault` — auto-parented to `DefaultsRoot` +2. The component's **variable name** in the SCS tree becomes the MuJoCo class name (synced at compile time) +3. Add child components under the default to define template values (e.g. add an `MjGeom` child to set default friction) +4. **Nest defaults** to create inheritance: drag one default under another in the SCS tree. The parent-child relationship is inferred from the hierarchy. +5. On bodies, use the **Child Class** dropdown to assign a default class to all children +6. On individual geoms/joints, use the **Default Class** dropdown to reference a specific default + +--- + +## Component Reference Dropdowns + +Most cross-references between components use dropdown pickers instead of string names: + +| Component | Dropdown | Shows | +|-----------|----------|-------| +| Actuator | Target | Joints, Tendons, Sites, or Bodies (filtered by Transmission Type) | +| Sensor | Target | Bodies, Joints, Geoms, Sites, etc. (filtered by Object Type) | +| Sensor | Reference | Bodies, Geoms (for relative sensors) | +| Contact Pair | Geom 1/2 | All geom components | +| Contact Exclude | Body 1/2 | All body components | +| Equality | Object 1/2 | Bodies, Joints, or Tendons (filtered by Equality Type) | +| Body | Child Class | All default class components | +| Geom/Joint/etc. | Default Class | All default class components | + +The dropdowns read and write the underlying string properties used by MuJoCo spec construction. + +--- + +## Auto-Parenting + +When you add certain component types, they are automatically moved to the correct organizational folder: + +| Component Type | Auto-Parented To | +|---------------|------------------| +| Sensor | SensorsRoot | +| Actuator | ActuatorsRoot | +| Default | DefaultsRoot | +| Tendon | TendonsRoot | +| Contact Pair/Exclude | ContactsRoot | +| Equality | EqualitiesRoot | + +Components under `DefaultsRoot` (default templates) are excluded from auto-parenting — they stay where you put them. + +--- + +## Compiling and Validating + +Press **Compile** in the Blueprint editor to: +- Sync default class names from the SCS variable names +- Sync parent-child default relationships from the SCS hierarchy +- Run `ValidateSpec` which creates a temporary MuJoCo spec and checks for errors + +Compilation errors appear in the Output Log (e.g. missing joint references, invalid ranges). + +--- + +## MuJoCo Outliner + +Open **Window → MuJoCo Outliner** for a filtered view of the articulation: + +- **BP selector** — choose which open articulation to inspect +- **Type filters** — toggle Bodies, Geoms, Joints, Sensors, Actuators, etc. +- **Search** — filter by component name +- **Click to select** — clicking an entry selects it in the Blueprint editor's component tree +- **Summary bar** — shows component counts + +--- + +## Custom Icons + +Each MuJoCo component type has a distinct icon in the component tree: + +- **Orange** — Bodies (bone shape) +- **Green** — Geoms (box, sphere, cylinder, capsule, mesh, triangle wireframe) +- **Blue** — Joints (angle arc, arrow, starburst) +- **Purple** — Sensors (eye shape) +- **Red** — Actuators (gear) +- **Grey** — Defaults (document) +- **Cyan** — Sites (pin marker) +- **Teal** — Tendons (taut line) + +--- + +## Tips + +- **Name your components** — the SCS variable name is used as the MuJoCo element name. Clear names make debugging easier. +- **Use defaults for shared properties** — instead of setting friction on every geom, create a default class and reference it. +- **Check the Output Log** after compile for validation warnings. +- **Defaults are hierarchical** — nest defaults in the SCS tree to create inheritance chains (child inherits from parent).