-
Notifications
You must be signed in to change notification settings - Fork 1.5k
Expand file tree
/
Copy pathusd_decoder.cc
More file actions
2657 lines (2346 loc) · 93 KB
/
usd_decoder.cc
File metadata and controls
2657 lines (2346 loc) · 93 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
// Copyright 2025 DeepMind Technologies Limited
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <algorithm>
#include <cmath>
#include <cstddef>
#include <map>
#include <memory>
#include <numbers>
#include <optional>
#include <string>
#include <string_view>
#include <vector>
#include <mujoco/experimental/usd/mjcPhysics/actuator.h>
#include <mujoco/experimental/usd/mjcPhysics/collisionAPI.h>
#include <mujoco/experimental/usd/mjcPhysics/equalityAPI.h>
#include <mujoco/experimental/usd/mjcPhysics/equalityConnectAPI.h>
#include <mujoco/experimental/usd/mjcPhysics/equalityJointAPI.h>
#include <mujoco/experimental/usd/mjcPhysics/equalityWeldAPI.h>
#include <mujoco/experimental/usd/mjcPhysics/imageableAPI.h>
#include <mujoco/experimental/usd/mjcPhysics/jointAPI.h>
#include <mujoco/experimental/usd/mjcPhysics/keyframe.h>
#include <mujoco/experimental/usd/mjcPhysics/materialAPI.h>
#include <mujoco/experimental/usd/mjcPhysics/meshCollisionAPI.h>
#include <mujoco/experimental/usd/mjcPhysics/sceneAPI.h>
#include <mujoco/experimental/usd/mjcPhysics/siteAPI.h>
#include <mujoco/experimental/usd/mjcPhysics/tendon.h>
#include <mujoco/experimental/usd/mjcPhysics/tokens.h>
#include <mujoco/mujoco.h>
#include "kinematic_tree.h"
#include "material_parsing.h"
#include <pxr/base/gf/declare.h>
#include <pxr/base/gf/matrix4d.h>
#include <pxr/base/gf/matrix4f.h>
#include <pxr/base/gf/rotation.h>
#include <pxr/base/gf/vec3d.h>
#include <pxr/base/tf/staticTokens.h>
#include <pxr/base/tf/token.h>
#include <pxr/base/vt/types.h>
#include <pxr/usd/sdf/path.h>
#include <pxr/usd/usd/common.h>
#include <pxr/usd/usd/prim.h>
#include <pxr/usd/usd/primFlags.h>
#include <pxr/usd/usd/primRange.h>
#include <pxr/usd/usd/stage.h>
#include <pxr/usd/usdGeom/capsule.h>
#include <pxr/usd/usdGeom/cube.h>
#include <pxr/usd/usdGeom/cylinder.h>
#include <pxr/usd/usdGeom/gprim.h>
#include <pxr/usd/usdGeom/mesh.h>
#include <pxr/usd/usdGeom/metrics.h>
#include <pxr/usd/usdGeom/plane.h>
#include <pxr/usd/usdGeom/primvar.h>
#include <pxr/usd/usdGeom/primvarsAPI.h>
#include <pxr/usd/usdGeom/sphere.h>
#include <pxr/usd/usdGeom/tokens.h>
#include <pxr/usd/usdGeom/xformCache.h>
#include <pxr/usd/usdPhysics/collisionAPI.h>
#include <pxr/usd/usdPhysics/filteredPairsAPI.h>
#include <pxr/usd/usdPhysics/fixedJoint.h>
#include <pxr/usd/usdPhysics/joint.h>
#include <pxr/usd/usdPhysics/massAPI.h>
#include <pxr/usd/usdPhysics/materialAPI.h>
#include <pxr/usd/usdPhysics/prismaticJoint.h>
#include <pxr/usd/usdPhysics/revoluteJoint.h>
#include <pxr/usd/usdPhysics/rigidBodyAPI.h>
#include <pxr/usd/usdPhysics/scene.h>
#include <pxr/usd/usdPhysics/sphericalJoint.h>
#include <pxr/usd/usdShade/material.h>
#include <pxr/usd/usdShade/materialBindingAPI.h>
using pxr::MjcPhysicsTokens;
using pxr::TfToken;
template <typename T>
using TfStaticData = pxr::TfStaticData<T>;
// clang-format off
TF_DEFINE_PRIVATE_TOKENS(kNewtonTokens,
((NewtonMaterialAPI, "NewtonMaterialAPI"))
((NewtonMeshCollisionAPI, "NewtonMeshCollisionAPI"))
((newtonMaxSolverIterations, "newton:maxSolverIterations"))
((newtonTimeStepsPerSecond, "newton:timeStepsPerSecond"))
((newtonGravityEnabled, "newton:gravityEnabled"))
((newtonContactMargin, "newton:contactMargin"))
((newtonContactGap, "newton:contactGap"))
((newtonMaxHullVertices, "newton:maxHullVertices"))
((newtonTorsionalFriction, "newton:torsionalFriction"))
((newtonRollingFriction, "newton:rollingFriction"))
((newtonMimicJoint, "newton:mimicJoint"))
((newtonMimicCoef0, "newton:mimicCoef0"))
((newtonMimicCoef1, "newton:mimicCoef1"))
((NewtonMimicAPI, "NewtonMimicAPI"))
);
// clang-format on
struct UsdCaches {
pxr::UsdGeomXformCache xform_cache;
pxr::UsdShadeMaterialBindingAPI::BindingsCache bindings_cache;
pxr::UsdShadeMaterialBindingAPI::CollectionQueryCache collection_query_cache;
std::map<pxr::SdfPath, mjsMaterial*> parsed_materials;
};
constexpr const char* kUsdPrimPathKey = "usd_primpath";
void SetUsdPrimPathUserValue(mjsElement* element,
const pxr::SdfPath& prim_path) {
// The value is a pointer to a newly allocated SdfPath, which will be deleted
// when the mjsElement is deleted.
const pxr::SdfPath* usd_primpath = new pxr::SdfPath(prim_path);
mjs_setUserValueWithCleanup(
element, kUsdPrimPathKey, usd_primpath,
[](const void* data) { delete static_cast<const pxr::SdfPath*>(data); });
}
pxr::SdfPath GetUsdPrimPathUserValue(mjsElement* element) {
const void* user_data = mjs_getUserValue(element, kUsdPrimPathKey);
if (user_data) {
return *static_cast<const pxr::SdfPath*>(user_data);
}
return pxr::SdfPath();
}
void SetDoubleArrFromGfVec3d(double* to, const pxr::GfVec3d& from) {
to[0] = from[0];
to[1] = from[1];
to[2] = from[2];
}
void SetMjtNumArrFromGfVec3d(mjtNum* to, const pxr::GfVec3d& from) {
to[0] = from[0];
to[1] = from[1];
to[2] = from[2];
}
void SetDoubleArrFromGfQuatd(double* to, const pxr::GfQuatd& from) {
// pxr::GfQuatd uses wxyz stored as a real and an imaginary component.
to[0] = from.GetReal();
to[1] = from.GetImaginary()[0];
to[2] = from.GetImaginary()[1];
to[3] = from.GetImaginary()[2];
}
template <typename T>
void SetLocalPoseFromPrim(const pxr::UsdPrim& prim,
const pxr::UsdPrim& parent_prim, T* element,
pxr::UsdGeomXformCache& xform_cache) {
pxr::GfMatrix4d xform = xform_cache.GetLocalToWorldTransform(prim);
pxr::GfMatrix4d parent_xform =
xform_cache.GetLocalToWorldTransform(parent_prim);
pxr::GfMatrix4d relative_xform = xform * parent_xform.GetInverse();
pxr::GfVec3d translation = relative_xform.ExtractTranslation();
pxr::GfQuatd rotation =
relative_xform.RemoveScaleShear().ExtractRotationQuat();
SetDoubleArrFromGfVec3d(element->pos, translation);
SetDoubleArrFromGfQuatd(element->quat, rotation);
}
pxr::GfVec3d GetScale(const pxr::GfMatrix4d& matrix) {
pxr::GfMatrix4d rotation;
pxr::GfVec3d scale;
pxr::GfMatrix4d u;
pxr::GfVec3d translation;
pxr::GfMatrix4d p;
if (!matrix.Factor(&rotation, &scale, &u, &translation, &p)) {
// In the event that we could not factorize, return the identity.
mju_error("Could not factorise matrix.");
return pxr::GfVec3d(1, 1, 1);
}
return scale;
}
bool IsUniformScale(const pxr::GfVec3d& scale) {
static const double epsilon = 1e-6;
return fabs(scale[0] - scale[1]) < epsilon &&
fabs(scale[1] - scale[2]) < epsilon;
}
template <typename T>
bool MaybeParseGeomPrimitive(const pxr::UsdPrim& prim, T* element,
pxr::UsdGeomXformCache& xform_cache) {
auto world_xform = xform_cache.GetLocalToWorldTransform(prim);
auto scale = GetScale(world_xform);
if (prim.IsA<pxr::UsdGeomSphere>()) {
double radius;
if (!pxr::UsdGeomSphere(prim).GetRadiusAttr().Get<double>(&radius)) {
mju_error("Could not get sphere radius attr.");
return false;
}
// If scale is uniform (or *very close*) then create a sphere, otherwise
// this is an ellipsoid.
if (IsUniformScale(scale)) {
element->type = mjGEOM_SPHERE;
element->size[0] = scale[0] * radius;
element->size[1] = scale[0] * radius;
element->size[2] = scale[0] * radius;
} else {
element->type = mjGEOM_ELLIPSOID;
element->size[0] = scale[0] * radius;
element->size[1] = scale[1] * radius;
element->size[2] = scale[2] * radius;
}
} else if (prim.IsA<pxr::UsdGeomCylinder>()) {
auto cylinder = pxr::UsdGeomCylinder(prim);
element->type = mjGEOM_CYLINDER;
double radius;
if (!cylinder.GetRadiusAttr().Get<double>(&radius)) {
mju_error("Could not get cylinder radius attr.");
return false;
}
double height;
if (!cylinder.GetHeightAttr().Get<double>(&height)) {
mju_error("Could not get cylinder height attr.");
return false;
}
element->size[0] = scale[0] * radius;
element->size[1] = scale[1] * height / 2.0f;
element->size[2] = 0;
} else if (prim.IsA<pxr::UsdGeomCapsule>()) {
auto capsule = pxr::UsdGeomCapsule(prim);
element->type = mjGEOM_CAPSULE;
double radius;
if (!capsule.GetRadiusAttr().Get<double>(&radius)) {
mju_error("Could not get capsule radius attr.");
return false;
}
double height;
if (!capsule.GetHeightAttr().Get<double>(&height)) {
mju_error("Could not get capsule height attr.");
return false;
}
element->size[0] = scale[0] * radius;
element->size[1] = scale[1] * height / 2.0f;
element->size[2] = 0;
TfToken axis;
capsule.GetAxisAttr().Get(&axis);
// Mujoco (and USD) capsules are aligned with Z by default.
// When USD axis is X or Y, we apply a rotation to align with the Z axis.
pxr::GfQuatd axis_rot(1.0);
if (axis == pxr::UsdGeomTokens->x) {
axis_rot = pxr::GfRotation(pxr::GfVec3d::XAxis(), pxr::GfVec3d::ZAxis())
.GetQuat();
} else if (axis == pxr::UsdGeomTokens->y) {
axis_rot = pxr::GfRotation(pxr::GfVec3d::YAxis(), pxr::GfVec3d::ZAxis())
.GetQuat();
}
pxr::GfQuatd current_rot(element->quat[0], element->quat[1],
element->quat[2], element->quat[3]);
pxr::GfQuatd new_rot = current_rot * axis_rot;
SetDoubleArrFromGfQuatd(element->quat, new_rot);
} else if (prim.IsA<pxr::UsdGeomCube>()) {
element->type = mjGEOM_BOX;
auto cube = pxr::UsdGeomCube(prim);
double size;
if (!cube.GetSizeAttr().Get<double>(&size)) {
mju_error("Could not get cube size attr.");
return false;
}
// MuJoCo uses half-length for box size.
size = size / 2;
element->size[0] = scale[0] * size;
element->size[1] = scale[1] * size;
element->size[2] = scale[2] * size;
} else if (prim.IsA<pxr::UsdGeomPlane>()) {
element->type = mjGEOM_PLANE;
pxr::UsdGeomPlane plane(prim);
TfToken axis;
if (!plane.GetAxisAttr().Get(&axis)) {
mju_error("Could not get plane axis attr.");
return false;
}
if (axis != pxr::UsdGeomTokens->z) {
mju_error("Only z-axis planes are supported.");
return false;
}
double length;
if (!plane.GetLengthAttr().Get(&length)) {
mju_error("Could not get plane length attr.");
return false;
}
double width;
if (!plane.GetWidthAttr().Get(&width)) {
mju_error("Could not get plane width attr.");
return false;
}
// MuJoCo uses half-length for plane size.
width = width / 2;
length = length / 2;
// Plane geoms in mjc are always infinite. Scale is used for visualization.
element->size[0] = scale[0] * width;
element->size[1] = scale[1] * length;
element->size[2] = scale[2];
} else {
return false;
}
return true;
}
mjsMesh* ParseUsdMesh(mjSpec* spec, const pxr::UsdPrim& prim, mjsGeom* geom,
pxr::UsdGeomXformCache& xform_cache) {
if (!prim.IsA<pxr::UsdGeomMesh>()) {
return nullptr;
}
mjsMesh* mesh = mjs_addMesh(spec, nullptr);
SetUsdPrimPathUserValue(mesh->element, prim.GetPath());
geom->type = mjGEOM_MESH;
pxr::UsdGeomMesh usd_mesh(prim);
std::vector<float> uservert;
std::vector<int> userface;
pxr::VtVec3fArray points;
usd_mesh.GetPointsAttr().Get(&points);
pxr::VtVec2fArray uvs;
pxr::VtIntArray uv_indices;
std::vector<float> texcoord;
std::vector<int> userfacetexcoord;
pxr::UsdGeomPrimvarsAPI primvarsAPI(prim);
pxr::UsdGeomPrimvar st_primvar =
primvarsAPI.FindPrimvarWithInheritance(pxr::TfToken("st"));
uservert.reserve(points.size() * 3);
for (const auto& pt : points) {
uservert.push_back(pt[0]);
uservert.push_back(pt[1]);
uservert.push_back(pt[2]);
}
bool has_uvs = st_primvar.HasAuthoredValue();
bool face_varying_uvs = has_uvs && st_primvar.GetInterpolation() ==
pxr::UsdGeomTokens->faceVarying;
bool st_indexed = st_primvar.IsIndexed();
if (has_uvs) {
pxr::VtVec2fArray uvs;
st_primvar.Get(&uvs);
if (st_indexed) {
st_primvar.GetIndices(&uv_indices);
}
// If the UVs do not vary per point per face, then we need to compute the
// effective uv array taking indexing into account as we do not support UV
// indexing in mujoco.
if (!face_varying_uvs && st_primvar.IsIndexed()) {
texcoord.reserve(uv_indices.size() * 2);
for (const auto& idx : uv_indices) {
auto uv = uvs[idx];
texcoord.push_back(uv[0]);
// USD origin is bottom left, MuJoCo is top left.
texcoord.push_back(1.0f - uv[1]);
}
} else {
texcoord.reserve(uvs.size() * 2);
for (const auto& uv : uvs) {
texcoord.push_back(uv[0]);
// USD origin is bottom left, MuJoCo is top left.
texcoord.push_back(1.0f - uv[1]);
}
}
mjs_setFloat(mesh->usertexcoord, texcoord.data(), texcoord.size());
}
pxr::VtIntArray indices;
usd_mesh.GetFaceVertexIndicesAttr().Get(&indices);
pxr::VtIntArray counts;
usd_mesh.GetFaceVertexCountsAttr().Get(&counts);
userface.reserve(indices.size());
int vtx_idx = 0;
for (int count : counts) {
int k = 1;
// If the prim is a triangle create a triangle fan rooted
// at the first index.
while (k < count - 1) {
userface.push_back(indices[vtx_idx]);
userface.push_back(indices[vtx_idx + k]);
userface.push_back(indices[vtx_idx + k + 1]);
// If the UVs vary per face, then we need to compute the effective
// index array after we've created the triangle fan for non triangular
// faces.
if (face_varying_uvs) {
userfacetexcoord.push_back(st_indexed ? uv_indices[vtx_idx] : vtx_idx);
userfacetexcoord.push_back(st_indexed ? uv_indices[vtx_idx + k]
: vtx_idx + k);
userfacetexcoord.push_back(st_indexed ? uv_indices[vtx_idx + k + 1]
: vtx_idx + k + 1);
}
k++;
}
vtx_idx += count;
}
auto world_xform = xform_cache.GetLocalToWorldTransform(prim);
auto scale = GetScale(world_xform);
mesh->scale[0] = scale[0];
mesh->scale[1] = scale[1];
mesh->scale[2] = scale[2];
std::string mesh_name = usd_mesh.GetPath().GetAsString();
mjs_setName(mesh->element, mesh_name.c_str());
mjs_setFloat(mesh->uservert, uservert.data(), uservert.size());
mjs_setInt(mesh->userface, userface.data(), userface.size());
if (face_varying_uvs) {
mjs_setInt(mesh->userfacetexcoord, userfacetexcoord.data(),
userfacetexcoord.size());
}
mjs_setString(geom->meshname, mesh_name.c_str());
return mesh;
}
void SetGravityAttributes(
mjSpec* spec, const pxr::UsdStageRefPtr stage,
std::optional<pxr::GfVec3f> gravity_direction = std::nullopt,
std::optional<float> gravity_magnitude = std::nullopt) {
// Parse gravity and gravity direction.
if (!gravity_direction.has_value()) {
TfToken up_axis = pxr::UsdGeomGetStageUpAxis(stage);
if (up_axis == pxr::UsdGeomTokens->y) {
gravity_direction = pxr::GfVec3f(0, -1, 0);
} else if (up_axis == pxr::UsdGeomTokens->z) {
gravity_direction = pxr::GfVec3f(0, 0, -1);
} else {
mju_error("Invalid stage up axis token %s", up_axis.GetString().c_str());
}
}
if (!gravity_magnitude.has_value()) {
gravity_magnitude = 9.81f / pxr::UsdGeomGetStageMetersPerUnit(stage);
}
pxr::GfVec3f gravity = gravity_direction.value() * gravity_magnitude.value();
spec->option.gravity[0] = gravity[0];
spec->option.gravity[1] = gravity[1];
spec->option.gravity[2] = gravity[2];
}
void ParseUsdPhysicsScene(mjSpec* spec,
const pxr::UsdPhysicsScene& physics_scene) {
std::optional<pxr::GfVec3f> gravity_direction = std::nullopt;
std::optional<float> gravity_magnitude = std::nullopt;
auto stage = physics_scene.GetPrim().GetStage();
// Parse gravity and gravity direction.
auto gravity_direction_attr = physics_scene.GetGravityDirectionAttr();
if (gravity_direction_attr.HasAuthoredValue()) {
pxr::GfVec3f authored_gravity_dir;
gravity_direction_attr.Get(&authored_gravity_dir);
gravity_direction = authored_gravity_dir;
}
auto gravity_magnitude_attr = physics_scene.GetGravityMagnitudeAttr();
if (gravity_magnitude_attr.HasAuthoredValue()) {
float authored_gravity_magnitude;
gravity_magnitude_attr.Get(&authored_gravity_magnitude);
gravity_magnitude = authored_gravity_magnitude;
}
SetGravityAttributes(spec, stage, gravity_direction, gravity_magnitude);
// Parse Newton scene attributes if present (works for Newton-only files)
pxr::UsdPrim scene_prim = physics_scene.GetPrim();
auto newton_iterations = scene_prim.GetAttribute(
kNewtonTokens->newtonMaxSolverIterations);
if (newton_iterations && newton_iterations.HasAuthoredValue()) {
int val;
newton_iterations.Get(&val);
if (val >= 0) spec->option.iterations = val;
}
auto newton_timesteps = scene_prim.GetAttribute(
kNewtonTokens->newtonTimeStepsPerSecond);
if (newton_timesteps && newton_timesteps.HasAuthoredValue()) {
int val;
newton_timesteps.Get(&val);
if (val > 0) spec->option.timestep = 1.0 / val;
}
auto newton_gravity = scene_prim.GetAttribute(
kNewtonTokens->newtonGravityEnabled);
if (newton_gravity && newton_gravity.HasAuthoredValue()) {
bool enabled;
newton_gravity.Get(&enabled);
if (!enabled) {
spec->option.disableflags |= mjDSBL_GRAVITY;
}
}
// Early exit if there's no MjcPhysicsSceneAPI applied.
if (!scene_prim.HasAPI<pxr::MjcPhysicsSceneAPI>()) {
return;
}
auto mjc_physics_scene = pxr::MjcPhysicsSceneAPI(scene_prim);
// MJC values override Newton values only when explicitly authored.
auto timestep_attr = mjc_physics_scene.GetTimestepAttr();
if (timestep_attr.HasAuthoredValue()) {
double timestep;
timestep_attr.Get(×tep);
spec->option.timestep = timestep;
mju_warning("Scene '%s' uses deprecated mjc:option:timestep. "
"Please migrate to newton:timeStepsPerSecond.",
scene_prim.GetPath().GetText());
}
double impratio;
mjc_physics_scene.GetImpRatioAttr().Get(&impratio);
spec->option.impratio = impratio;
double tolerance;
mjc_physics_scene.GetToleranceAttr().Get(&tolerance);
spec->option.tolerance = tolerance;
double ls_tolerance;
mjc_physics_scene.GetLSToleranceAttr().Get(&ls_tolerance);
spec->option.ls_tolerance = ls_tolerance;
double noslip_tolerance;
mjc_physics_scene.GetNoslipToleranceAttr().Get(&noslip_tolerance);
spec->option.noslip_tolerance = noslip_tolerance;
double ccd_tolerance;
mjc_physics_scene.GetCCDToleranceAttr().Get(&ccd_tolerance);
spec->option.ccd_tolerance = ccd_tolerance;
pxr::GfVec3d wind;
mjc_physics_scene.GetWindAttr().Get(&wind);
SetMjtNumArrFromGfVec3d(spec->option.wind, wind);
pxr::GfVec3d magnetic;
mjc_physics_scene.GetMagneticAttr().Get(&magnetic);
SetMjtNumArrFromGfVec3d(spec->option.magnetic, magnetic);
double density;
mjc_physics_scene.GetDensityAttr().Get(&density);
spec->option.density = density;
double viscosity;
mjc_physics_scene.GetViscosityAttr().Get(&viscosity);
spec->option.viscosity = viscosity;
double o_margin;
mjc_physics_scene.GetOMarginAttr().Get(&o_margin);
spec->option.o_margin = o_margin;
pxr::VtDoubleArray o_solref;
mjc_physics_scene.GetOSolRefAttr().Get(&o_solref);
if (o_solref.size() != mjNREF) {
mju_error("Invalid size for o_solref attribute: %zu expected %d",
o_solref.size(), mjNREF);
return;
}
for (int i = 0; i < mjNREF; ++i) {
spec->option.o_solref[i] = o_solref[i];
}
pxr::VtDoubleArray o_solimp;
mjc_physics_scene.GetOSolImpAttr().Get(&o_solimp);
if (o_solimp.size() != mjNIMP) {
mju_error("Invalid size for o_solimp attribute: %zu expected %d",
o_solimp.size(), mjNIMP);
return;
}
for (int i = 0; i < mjNIMP; ++i) {
spec->option.o_solimp[i] = o_solimp[i];
}
pxr::VtDoubleArray o_friction;
mjc_physics_scene.GetOFrictionAttr().Get(&o_friction);
if (o_friction.size() != 5) {
mju_error("Invalid size for o_friction attribute: %zu expected %d",
o_friction.size(), 5);
return;
}
for (int i = 0; i < 5; ++i) {
spec->option.o_friction[i] = o_friction[i];
}
TfToken integrator;
mjc_physics_scene.GetIntegratorAttr().Get(&integrator);
if (integrator == MjcPhysicsTokens->euler) {
spec->option.integrator = mjINT_EULER;
} else if (integrator == MjcPhysicsTokens->rk4) {
spec->option.integrator = mjINT_RK4;
} else if (integrator == MjcPhysicsTokens->implicit) {
spec->option.integrator = mjINT_IMPLICIT;
} else if (integrator == MjcPhysicsTokens->implicitfast) {
spec->option.integrator = mjINT_IMPLICITFAST;
}
TfToken cone;
mjc_physics_scene.GetConeAttr().Get(&cone);
if (cone == MjcPhysicsTokens->elliptic) {
spec->option.cone = mjCONE_ELLIPTIC;
} else if (cone == MjcPhysicsTokens->pyramidal) {
spec->option.cone = mjCONE_PYRAMIDAL;
}
TfToken jacobian;
mjc_physics_scene.GetJacobianAttr().Get(&jacobian);
if (jacobian == MjcPhysicsTokens->auto_) {
spec->option.jacobian = mjJAC_AUTO;
} else if (jacobian == MjcPhysicsTokens->dense) {
spec->option.jacobian = mjJAC_DENSE;
} else if (jacobian == MjcPhysicsTokens->sparse) {
spec->option.jacobian = mjJAC_SPARSE;
}
TfToken solver;
mjc_physics_scene.GetSolverAttr().Get(&solver);
if (solver == MjcPhysicsTokens->newton) {
spec->option.solver = mjSOL_NEWTON;
} else if (solver == MjcPhysicsTokens->cg) {
spec->option.solver = mjSOL_CG;
} else if (solver == MjcPhysicsTokens->pgs) {
spec->option.solver = mjSOL_PGS;
}
auto iterations_attr = mjc_physics_scene.GetIterationsAttr();
if (iterations_attr.HasAuthoredValue()) {
int iterations;
iterations_attr.Get(&iterations);
spec->option.iterations = iterations;
mju_warning("Scene '%s' uses deprecated mjc:option:iterations. "
"Please migrate to newton:maxSolverIterations.",
scene_prim.GetPath().GetText());
}
int ls_iterations;
mjc_physics_scene.GetLSIterationsAttr().Get(&ls_iterations);
spec->option.ls_iterations = ls_iterations;
int noslip_iterations;
mjc_physics_scene.GetNoslipIterationsAttr().Get(&noslip_iterations);
spec->option.noslip_iterations = noslip_iterations;
int ccd_iterations;
mjc_physics_scene.GetCCDIterationsAttr().Get(&ccd_iterations);
spec->option.ccd_iterations = ccd_iterations;
int sdf_initpoints;
mjc_physics_scene.GetSDFInitPointsAttr().Get(&sdf_initpoints);
spec->option.sdf_initpoints = sdf_initpoints;
int sdf_iterations;
mjc_physics_scene.GetSDFIterationsAttr().Get(&sdf_iterations);
spec->option.sdf_iterations = sdf_iterations;
bool constraint_flag;
mjc_physics_scene.GetConstraintFlagAttr().Get(&constraint_flag);
spec->option.disableflags |= (!constraint_flag ? mjDSBL_CONSTRAINT : 0);
bool equality_flag;
mjc_physics_scene.GetEqualityFlagAttr().Get(&equality_flag);
spec->option.disableflags |= (!equality_flag ? mjDSBL_EQUALITY : 0);
bool frictionloss_flag;
mjc_physics_scene.GetFrictionLossFlagAttr().Get(&frictionloss_flag);
spec->option.disableflags |= (!frictionloss_flag ? mjDSBL_FRICTIONLOSS : 0);
bool limit_flag;
mjc_physics_scene.GetLimitFlagAttr().Get(&limit_flag);
spec->option.disableflags |= (!limit_flag ? mjDSBL_LIMIT : 0);
bool contact_flag;
mjc_physics_scene.GetContactFlagAttr().Get(&contact_flag);
spec->option.disableflags |= (!contact_flag ? mjDSBL_CONTACT : 0);
bool spring_flag;
mjc_physics_scene.GetSpringFlagAttr().Get(&spring_flag);
spec->option.disableflags |= (!spring_flag ? mjDSBL_SPRING : 0);
bool damper_flag;
mjc_physics_scene.GetDamperFlagAttr().Get(&damper_flag);
spec->option.disableflags |= (!damper_flag ? mjDSBL_DAMPER : 0);
auto gravity_flag_attr = mjc_physics_scene.GetGravityFlagAttr();
if (gravity_flag_attr.HasAuthoredValue()) {
bool gravity_flag;
gravity_flag_attr.Get(&gravity_flag);
if (!gravity_flag) {
spec->option.disableflags |= mjDSBL_GRAVITY;
} else {
spec->option.disableflags &= ~mjDSBL_GRAVITY;
}
mju_warning("Scene '%s' uses deprecated mjc:flag:gravity. "
"Please migrate to newton:gravityEnabled.",
scene_prim.GetPath().GetText());
}
bool clampctrl_flag;
mjc_physics_scene.GetClampCtrlFlagAttr().Get(&clampctrl_flag);
spec->option.disableflags |= (!clampctrl_flag ? mjDSBL_CLAMPCTRL : 0);
bool warmstart_flag;
mjc_physics_scene.GetWarmStartFlagAttr().Get(&warmstart_flag);
spec->option.disableflags |= (!warmstart_flag ? mjDSBL_WARMSTART : 0);
bool filterparent_flag;
mjc_physics_scene.GetFilterParentFlagAttr().Get(&filterparent_flag);
spec->option.disableflags |= (!filterparent_flag ? mjDSBL_FILTERPARENT : 0);
bool actuation_flag;
mjc_physics_scene.GetActuationFlagAttr().Get(&actuation_flag);
spec->option.disableflags |= (!actuation_flag ? mjDSBL_ACTUATION : 0);
bool refsafe_flag;
mjc_physics_scene.GetRefSafeFlagAttr().Get(&refsafe_flag);
spec->option.disableflags |= (!refsafe_flag ? mjDSBL_REFSAFE : 0);
bool sensor_flag;
mjc_physics_scene.GetSensorFlagAttr().Get(&sensor_flag);
spec->option.disableflags |= (!sensor_flag ? mjDSBL_SENSOR : 0);
bool midphase_flag;
mjc_physics_scene.GetMidPhaseFlagAttr().Get(&midphase_flag);
spec->option.disableflags |= (!midphase_flag ? mjDSBL_MIDPHASE : 0);
bool nativeccd_flag;
mjc_physics_scene.GetNativeCCDFlagAttr().Get(&nativeccd_flag);
spec->option.disableflags |= (!nativeccd_flag ? mjDSBL_NATIVECCD : 0);
bool eulerdamp_flag;
mjc_physics_scene.GetEulerDampFlagAttr().Get(&eulerdamp_flag);
spec->option.disableflags |= (!eulerdamp_flag ? mjDSBL_EULERDAMP : 0);
bool autoreset_flag;
mjc_physics_scene.GetAutoResetFlagAttr().Get(&autoreset_flag);
spec->option.disableflags |= (!autoreset_flag ? mjDSBL_AUTORESET : 0);
bool island_flag;
mjc_physics_scene.GetIslandFlagAttr().Get(&island_flag);
spec->option.disableflags |= (!island_flag ? mjDSBL_ISLAND : 0);
bool override_flag;
mjc_physics_scene.GetOverrideFlagAttr().Get(&override_flag);
spec->option.enableflags |= (override_flag ? mjENBL_OVERRIDE : 0);
bool energy_flag;
mjc_physics_scene.GetEnergyFlagAttr().Get(&energy_flag);
spec->option.enableflags |= (energy_flag ? mjENBL_ENERGY : 0);
bool fwdinv_flag;
mjc_physics_scene.GetFwdinvFlagAttr().Get(&fwdinv_flag);
spec->option.enableflags |= (fwdinv_flag ? mjENBL_FWDINV : 0);
bool invdiscrete_flag;
mjc_physics_scene.GetInvDiscreteFlagAttr().Get(&invdiscrete_flag);
spec->option.enableflags |= (invdiscrete_flag ? mjENBL_INVDISCRETE : 0);
bool multiccd_flag;
mjc_physics_scene.GetMultiCCDFlagAttr().Get(&multiccd_flag);
spec->option.enableflags |= (multiccd_flag ? mjENBL_MULTICCD : 0);
// Compiler attributes
auto auto_limits_attr = mjc_physics_scene.GetAutoLimitsAttr();
if (auto_limits_attr.HasAuthoredValue()) {
bool autolimits;
auto_limits_attr.Get(&autolimits);
spec->compiler.autolimits = autolimits;
}
auto use_thread_attr = mjc_physics_scene.GetUseThreadAttr();
if (use_thread_attr.HasAuthoredValue()) {
bool use_thread;
use_thread_attr.Get(&use_thread);
spec->compiler.usethread = use_thread;
}
auto balance_inertia_attr = mjc_physics_scene.GetBalanceInertiaAttr();
if (balance_inertia_attr.HasAuthoredValue()) {
bool balanceinertia;
balance_inertia_attr.Get(&balanceinertia);
spec->compiler.balanceinertia = balanceinertia;
}
auto angle_attr = mjc_physics_scene.GetAngleAttr();
if (angle_attr.HasAuthoredValue()) {
pxr::TfToken angle;
angle_attr.Get(&angle);
spec->compiler.degree = angle == MjcPhysicsTokens->degree;
}
auto fit_aabb_attr = mjc_physics_scene.GetFitAABBAttr();
if (fit_aabb_attr.HasAuthoredValue()) {
bool fitaabb;
fit_aabb_attr.Get(&fitaabb);
spec->compiler.fitaabb = fitaabb;
}
auto fuse_static_attr = mjc_physics_scene.GetFuseStaticAttr();
if (fuse_static_attr.HasAuthoredValue()) {
bool fusestatic;
fuse_static_attr.Get(&fusestatic);
spec->compiler.fusestatic = fusestatic;
}
auto inertia_from_geom_attr = mjc_physics_scene.GetInertiaFromGeomAttr();
if (inertia_from_geom_attr.HasAuthoredValue()) {
pxr::TfToken inertiafromgeom;
inertia_from_geom_attr.Get(&inertiafromgeom);
if (inertiafromgeom == MjcPhysicsTokens->auto_) {
spec->compiler.inertiafromgeom = mjINERTIAFROMGEOM_AUTO;
} else if (inertiafromgeom == MjcPhysicsTokens->false_) {
spec->compiler.inertiafromgeom = mjINERTIAFROMGEOM_FALSE;
} else if (inertiafromgeom == MjcPhysicsTokens->true_) {
spec->compiler.inertiafromgeom = mjINERTIAFROMGEOM_TRUE;
} else {
mju_warning("Invalid inertiafromgeom token: %s",
inertiafromgeom.GetText());
}
}
auto align_free_attr = mjc_physics_scene.GetAlignFreeAttr();
if (align_free_attr.HasAuthoredValue()) {
bool alignfree;
align_free_attr.Get(&alignfree);
spec->compiler.alignfree = alignfree;
}
auto inertia_group_range_min_attr =
mjc_physics_scene.GetInertiaGroupRangeMinAttr();
auto inertia_group_range_max_attr =
mjc_physics_scene.GetInertiaGroupRangeMaxAttr();
if (inertia_group_range_min_attr.HasAuthoredValue() &&
inertia_group_range_max_attr.HasAuthoredValue()) {
int inertiagrouprangemin;
inertia_group_range_min_attr.Get(&inertiagrouprangemin);
int inertiagrouprangemax;
inertia_group_range_max_attr.Get(&inertiagrouprangemax);
spec->compiler.inertiagrouprange[0] = inertiagrouprangemin;
spec->compiler.inertiagrouprange[1] = inertiagrouprangemax;
} else if (inertia_group_range_min_attr.HasAuthoredValue() ||
inertia_group_range_max_attr.HasAuthoredValue()) {
mju_warning(
"Only one of inertiaGroupRangeMin and inertiaGroupRangeMax was "
"authored, ignoring both.");
}
auto save_inertial_attr = mjc_physics_scene.GetSaveInertialAttr();
if (save_inertial_attr.HasAuthoredValue()) {
bool saveinertial;
save_inertial_attr.Get(&saveinertial);
spec->compiler.saveinertial = saveinertial;
}
mjc_physics_scene.GetBoundMassAttr().Get(&spec->compiler.boundmass);
mjc_physics_scene.GetBoundInertiaAttr().Get(&spec->compiler.boundinertia);
mjc_physics_scene.GetSetTotalMassAttr().Get(&spec->compiler.settotalmass);
}
void ParseUsdPhysicsMassAPIForBody(mjsBody* body,
const pxr::UsdPhysicsMassAPI& mass_api) {
auto mass_attr = mass_api.GetMassAttr();
if (mass_attr.HasAuthoredValue()) {
float mass;
mass_attr.Get(&mass);
body->mass = mass;
}
auto com_attr = mass_api.GetCenterOfMassAttr();
if (com_attr.HasAuthoredValue()) {
pxr::GfVec3f com;
com_attr.Get(&com);
SetDoubleArrFromGfVec3d(body->ipos, com);
}
auto principle_axes_attr = mass_api.GetPrincipalAxesAttr();
if (principle_axes_attr.HasAuthoredValue()) {
pxr::GfQuatf principle_axes;
principle_axes_attr.Get(&principle_axes);
SetDoubleArrFromGfQuatd(body->iquat, principle_axes);
}
auto diag_inertia_attr = mass_api.GetDiagonalInertiaAttr();
if (diag_inertia_attr.HasAuthoredValue()) {
pxr::GfVec3f diag_inertia;
diag_inertia_attr.Get(&diag_inertia);
SetDoubleArrFromGfVec3d(body->inertia, diag_inertia);
}
}
void ParseUsdPhysicsMassAPIForGeom(mjsGeom* geom,
const pxr::UsdPhysicsMassAPI& mass_api) {
auto mass_attr = mass_api.GetMassAttr();
if (mass_attr.HasAuthoredValue()) {
float mass;
mass_attr.Get(&mass);
geom->mass = mass;
}
auto density_attr = mass_api.GetDensityAttr();
if (density_attr.HasAuthoredValue()) {
float density;
density_attr.Get(&density);
geom->density = density;
}
}
void ParseMjcPhysicsCollisionAPI(
mjsGeom* geom, const pxr::MjcPhysicsCollisionAPI& collision_api) {
auto shell_inertia_attr = collision_api.GetShellInertiaAttr();
if (shell_inertia_attr.HasAuthoredValue()) {
bool shell_inertia;
shell_inertia_attr.Get(&shell_inertia);
geom->typeinertia = shell_inertia ? mjtGeomInertia::mjINERTIA_SHELL
: mjtGeomInertia::mjINERTIA_VOLUME;
}
auto group_attr = collision_api.GetGroupAttr();
if (group_attr.HasAuthoredValue()) {
group_attr.Get(&geom->group);
}
auto priority_attr = collision_api.GetPriorityAttr();
if (priority_attr.HasAuthoredValue()) {
priority_attr.Get(&geom->priority);
}
auto condim_attr = collision_api.GetConDimAttr();
if (condim_attr.HasAuthoredValue()) {
condim_attr.Get(&geom->condim);
}
auto solmix_attr = collision_api.GetSolMixAttr();
if (solmix_attr.HasAuthoredValue()) {
solmix_attr.Get(&geom->solmix);
}
auto solref_attr = collision_api.GetSolRefAttr();
if (solref_attr.HasAuthoredValue()) {
pxr::VtDoubleArray solref;
solref_attr.Get(&solref);
if (solref.size() == mjNREF) {
for (int i = 0; i < mjNREF; ++i) {
geom->solref[i] = solref[i];
}
} else {
mju_warning(
"solref attribute for geom %s has incorrect size %zu, "
"expected %d.",
mjs_getName(geom->element)->c_str(), solref.size(), mjNREF);
}
}
auto solimp_attr = collision_api.GetSolImpAttr();
if (solimp_attr.HasAuthoredValue()) {
pxr::VtDoubleArray solimp;
solimp_attr.Get(&solimp);
if (solimp.size() == mjNIMP) {
for (int i = 0; i < mjNIMP; ++i) {
geom->solimp[i] = solimp[i];
}
} else {
mju_warning(
"solimp attribute for geom %s has incorrect size %zu, "
"expected %d.",
mjs_getName(geom->element)->c_str(), solimp.size(), mjNIMP);
}
}
auto margin_attr = collision_api.GetMarginAttr();
auto gap_attr = collision_api.GetGapAttr();
bool mjc_margin_authored = margin_attr.HasAuthoredValue();
bool mjc_gap_authored = gap_attr.HasAuthoredValue();
if (mjc_margin_authored) {
margin_attr.Get(&geom->margin);
mju_warning("Prim '%s' uses deprecated mjc:margin. "
"Please migrate to newton:contactMargin and newton:contactGap.",
collision_api.GetPrim().GetPath().GetText());
}
if (mjc_gap_authored) {
gap_attr.Get(&geom->gap);
mju_warning("Prim '%s' uses deprecated mjc:gap. "