Skip to content

Commit 1c1bb14

Browse files
yuvaltassacopybara-github
authored andcommitted
Order fields in mjxmacro like in mjmodel and mjdata headers, add tests.
PiperOrigin-RevId: 798848000 Change-Id: Id1a41f6a0a4e3e6f3bb197f096061bd1d72a4b51
1 parent 7479312 commit 1c1bb14

File tree

3 files changed

+170
-17
lines changed

3 files changed

+170
-17
lines changed

include/mujoco/mjxmacro.h

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -387,27 +387,27 @@
387387
X ( float, flex_texcoord, nflextexcoord, 2 ) \
388388
X ( int, mesh_vertadr, nmesh, 1 ) \
389389
X ( int, mesh_vertnum, nmesh, 1 ) \
390-
X ( int, mesh_normaladr, nmesh, 1 ) \
391-
X ( int, mesh_normalnum, nmesh, 1 ) \
392-
X ( int, mesh_texcoordadr, nmesh, 1 ) \
393-
X ( int, mesh_texcoordnum, nmesh, 1 ) \
394390
X ( int, mesh_faceadr, nmesh, 1 ) \
395391
X ( int, mesh_facenum, nmesh, 1 ) \
396392
X ( int, mesh_bvhadr, nmesh, 1 ) \
397393
X ( int, mesh_bvhnum, nmesh, 1 ) \
398394
X ( int, mesh_octadr, nmesh, 1 ) \
399395
X ( int, mesh_octnum, nmesh, 1 ) \
396+
X ( int, mesh_normaladr, nmesh, 1 ) \
397+
X ( int, mesh_normalnum, nmesh, 1 ) \
398+
X ( int, mesh_texcoordadr, nmesh, 1 ) \
399+
X ( int, mesh_texcoordnum, nmesh, 1 ) \
400400
X ( int, mesh_graphadr, nmesh, 1 ) \
401-
X ( mjtNum, mesh_scale, nmesh, 3 ) \
402-
X ( mjtNum, mesh_pos, nmesh, 3 ) \
403-
X ( mjtNum, mesh_quat, nmesh, 4 ) \
404401
XNV ( float, mesh_vert, nmeshvert, 3 ) \
405402
XNV ( float, mesh_normal, nmeshnormal, 3 ) \
406403
XNV ( float, mesh_texcoord, nmeshtexcoord, 2 ) \
407404
XNV ( int, mesh_face, nmeshface, 3 ) \
408405
XNV ( int, mesh_facenormal, nmeshface, 3 ) \
409406
XNV ( int, mesh_facetexcoord, nmeshface, 3 ) \
410407
XNV ( int, mesh_graph, nmeshgraph, 1 ) \
408+
X ( mjtNum, mesh_scale, nmesh, 3 ) \
409+
X ( mjtNum, mesh_pos, nmesh, 3 ) \
410+
X ( mjtNum, mesh_quat, nmesh, 4 ) \
411411
X ( int, mesh_pathadr, nmesh, 1 ) \
412412
XNV ( int, mesh_polynum, nmesh, 1 ) \
413413
XNV ( int, mesh_polyadr, nmesh, 1 ) \
@@ -670,8 +670,8 @@
670670
X ( int, ten_J_rownnz, ntendon, 1 ) \
671671
X ( int, ten_J_rowadr, ntendon, 1 ) \
672672
X ( int, ten_J_colind, ntendon, MJ_M(nv) ) \
673-
X ( mjtNum, ten_length, ntendon, 1 ) \
674673
X ( mjtNum, ten_J, ntendon, MJ_M(nv) ) \
674+
X ( mjtNum, ten_length, ntendon, 1 ) \
675675
X ( int, wrap_obj, nwrap, 2 ) \
676676
X ( mjtNum, wrap_xpos, nwrap, 6 ) \
677677
X ( mjtNum, actuator_length, nu, 1 ) \
@@ -741,8 +741,8 @@
741741
X ( mjtNum, efc_vel, MJ_D(nefc), 1 ) \
742742
X ( mjtNum, efc_aref, MJ_D(nefc), 1 ) \
743743
X ( mjtNum, efc_b, MJ_D(nefc), 1 ) \
744-
X ( mjtNum, efc_force, MJ_D(nefc), 1 ) \
745-
X ( int, efc_state, MJ_D(nefc), 1 )
744+
X ( int, efc_state, MJ_D(nefc), 1 ) \
745+
X ( mjtNum, efc_force, MJ_D(nefc), 1 )
746746

747747
// array fields of mjData that are used in the dual problem
748748
#define MJDATA_ARENA_POINTERS_DUAL \
@@ -826,12 +826,12 @@
826826
// vector fields of mjData
827827
#define MJDATA_VECTOR \
828828
X( size_t, maxuse_threadstack, mjMAXTHREAD, 1 ) \
829-
X( mjWarningStat, warning, mjNWARNING, 1 ) \
830-
X( mjTimerStat, timer, mjNTIMER, 1 ) \
831829
X( mjSolverStat, solver, mjNISLAND, mjNSOLVER ) \
832830
X( int, solver_niter, mjNISLAND, 1 ) \
833831
X( int, solver_nnz, mjNISLAND, 1 ) \
834832
X( mjtNum, solver_fwdinv, 2, 1 ) \
833+
X( mjWarningStat, warning, mjNWARNING, 1 ) \
834+
X( mjTimerStat, timer, mjNTIMER, 1 ) \
835835
X( mjtNum, energy, 2, 1 )
836836

837837
// alias XNV to be the same as X

python/mujoco/structs.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -667,12 +667,12 @@ class MjWrapper<raw::MjData>: public WrapperBase<raw::MjData> {
667667
py_array_or_tuple_t<mjContact> contact;
668668

669669
py_array_or_tuple_t<size_t> maxuse_threadstack;
670-
py_array_or_tuple_t<raw::MjWarningStat> warning;
671-
py_array_or_tuple_t<raw::MjTimerStat> timer;
672670
py_array_or_tuple_t<raw::MjSolverStat> solver;
673671
py_array_or_tuple_t<int> solver_niter;
674672
py_array_or_tuple_t<int> solver_nnz;
675673
py_array_or_tuple_t<mjtNum> solver_fwdinv;
674+
py_array_or_tuple_t<raw::MjWarningStat> warning;
675+
py_array_or_tuple_t<raw::MjTimerStat> timer;
676676
py_array_or_tuple_t<mjtNum> energy;
677677

678678
protected:

test/header_test.cc

Lines changed: 156 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -15,20 +15,33 @@
1515
// Tests for structures in the public headers.
1616

1717
#include <cstddef>
18-
#include <cstring>
19-
#include <string>
20-
18+
#include <cstdint>
19+
#include <utility>
20+
#include <vector>
2121
#include <gtest/gtest.h>
2222
#include <mujoco/mjdata.h>
2323
#include <mujoco/mjmodel.h>
2424
#include <mujoco/mjrender.h>
2525
#include <mujoco/mjui.h>
2626
#include <mujoco/mjvisualize.h>
27+
#include <mujoco/mjxmacro.h>
2728
#include "test/fixture.h"
2829

2930
namespace mujoco {
3031
namespace {
3132

33+
// check that a vector of named pointers are ordered by address
34+
void CheckAddressOrdering(
35+
const std::vector<std::pair<const void*, const char*>>& pointers,
36+
const char* category_name) {
37+
for (size_t i = 0; i < pointers.size() - 1; ++i) {
38+
EXPECT_LT(reinterpret_cast<uintptr_t>(pointers[i].first),
39+
reinterpret_cast<uintptr_t>(pointers[i + 1].first))
40+
<< category_name << " '" << pointers[i].second
41+
<< "' should be declared before '" << pointers[i + 1].second << "'.";
42+
}
43+
}
44+
3245
using HeaderTest = MujocoTest;
3346

3447
TEST_F(HeaderTest, IntsHave4Bytes) {
@@ -84,5 +97,145 @@ TEST_F(HeaderTest, EnumsAreInts) {
8497
EXPECT_EQ(sizeof(mjtStereo), sizeof(int));
8598
}
8699

100+
TEST_F(HeaderTest, MjOptionFloatsOrdered) {
101+
mjOption o;
102+
std::vector<std::pair<const void*, const char*>> floats;
103+
104+
#define X(type, name) \
105+
floats.push_back({static_cast<const void*>(&o.name), #name});
106+
MJOPTION_FLOATS
107+
#undef X
108+
109+
CheckAddressOrdering(floats, "MJOPTION_FLOATS");
110+
}
111+
112+
TEST_F(HeaderTest, MjOptionVectorsOrdered) {
113+
mjOption o;
114+
std::vector<std::pair<const void*, const char*>> vectors;
115+
116+
#define X(name, dim) \
117+
vectors.push_back({static_cast<const void*>(&o.name), #name});
118+
MJOPTION_VECTORS
119+
#undef X
120+
121+
CheckAddressOrdering(vectors, "MJOPTION_VECTORS");
122+
}
123+
124+
TEST_F(HeaderTest, MjModelIntsOrdered) {
125+
mjModel m;
126+
std::vector<std::pair<const void*, const char*>> ints;
127+
128+
#define X(name) ints.push_back({static_cast<const void*>(&m.name), #name});
129+
MJMODEL_INTS
130+
#undef X
131+
132+
CheckAddressOrdering(ints, "MJMODEL_INT");
133+
}
134+
135+
TEST_F(HeaderTest, MjModelPointersOrdered) {
136+
mjModel m;
137+
std::vector<std::pair<const void*, const char*>> pointers;
138+
139+
#define X(type, name, dim1, dim2) \
140+
pointers.push_back({static_cast<const void*>(&m.name), #name});
141+
#define XNV X
142+
MJMODEL_POINTERS
143+
#undef XNV
144+
#undef X
145+
146+
CheckAddressOrdering(pointers, "MJMODEL_POINTER");
147+
}
148+
149+
150+
TEST_F(HeaderTest, MjDataPointersOrdered) {
151+
mjData d;
152+
std::vector<std::pair<const void*, const char*>> pointers;
153+
154+
#define X(type, name, dim1, dim2) \
155+
pointers.push_back({static_cast<const void*>(&d.name), #name});
156+
#define XNV X
157+
MJDATA_POINTERS
158+
#undef XNV
159+
#undef X
160+
161+
CheckAddressOrdering(pointers, "mjData pointer");
162+
}
163+
164+
TEST_F(HeaderTest, MjDataArenaPointersSolverOrdered) {
165+
mjData d;
166+
std::vector<std::pair<const void*, const char*>> pointers;
167+
168+
#define X(type, name, dim1, dim2) \
169+
pointers.push_back({static_cast<const void*>(&d.name), #name});
170+
#define XNV X
171+
#undef MJ_D
172+
#define MJ_D(n) 0
173+
MJDATA_ARENA_POINTERS_SOLVER
174+
#undef MJ_D
175+
#define MJ_D(n) n
176+
#undef XNV
177+
#undef X
178+
179+
CheckAddressOrdering(pointers, "MJDATA_ARENA_POINTERS_SOLVER");
180+
}
181+
182+
TEST_F(HeaderTest, MjDataArenaPointersDualOrdered) {
183+
mjData d;
184+
std::vector<std::pair<const void*, const char*>> pointers;
185+
186+
#define X(type, name, dim1, dim2) \
187+
pointers.push_back({static_cast<const void*>(&d.name), #name});
188+
#define XNV X
189+
#undef MJ_D
190+
#define MJ_D(n) 0
191+
MJDATA_ARENA_POINTERS_DUAL
192+
#undef MJ_D
193+
#define MJ_D(n) n
194+
#undef XNV
195+
#undef X
196+
197+
CheckAddressOrdering(pointers, "MJDATA_ARENA_POINTERS_DUAL");
198+
}
199+
200+
TEST_F(HeaderTest, MjDataArenaPointersIslandOrdered) {
201+
mjData d;
202+
std::vector<std::pair<const void*, const char*>> pointers;
203+
204+
#define X(type, name, dim1, dim2) \
205+
pointers.push_back({static_cast<const void*>(&d.name), #name});
206+
#define XNV X
207+
#undef MJ_D
208+
#define MJ_D(n) 0
209+
MJDATA_ARENA_POINTERS_ISLAND
210+
#undef MJ_D
211+
#define MJ_D(n) n
212+
#undef XNV
213+
#undef X
214+
215+
CheckAddressOrdering(pointers, "MJDATA_ARENA_POINTERS_ISLAND");
216+
}
217+
218+
TEST_F(HeaderTest, MjDataScalarsOrdered) {
219+
mjData d;
220+
std::vector<std::pair<const void*, const char*>> scalars;
221+
222+
#define X(type, name) \
223+
scalars.push_back({static_cast<const void*>(&d.name), #name});
224+
MJDATA_SCALAR
225+
#undef X
226+
CheckAddressOrdering(scalars, "mjData scalar");
227+
}
228+
229+
TEST_F(HeaderTest, MjDataVectorsOrdered) {
230+
mjData d;
231+
std::vector<std::pair<const void*, const char*>> vectors;
232+
233+
#define X(type, name, dim1, dim2) \
234+
vectors.push_back({static_cast<const void*>(&d.name), #name});
235+
MJDATA_VECTOR
236+
#undef X
237+
CheckAddressOrdering(vectors, "mjData vector");
238+
}
239+
87240
} // namespace
88241
} // namespace mujoco

0 commit comments

Comments
 (0)