Skip to content

Commit 6654d63

Browse files
quaglacopybara-github
authored andcommitted
Add spec lookup in the attached spec array using the compiler option pointer.
This enables to find the spec associated with the compiler option stored in the objects, which do not necessarily belong to the model that owns them. PiperOrigin-RevId: 713259419 Change-Id: I579c770147ff07ed2a5edd20e7a795ee7cc27147
1 parent 8a5f092 commit 6654d63

File tree

6 files changed

+162
-40
lines changed

6 files changed

+162
-40
lines changed

doc/programming/modeledit.rst

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -117,6 +117,8 @@ to :ref:`attach a body to a site<mjs_attachToSite>`:
117117
118118
mjSpec* parent = mj_makeSpec();
119119
mjSpec* child = mj_makeSpec();
120+
parent->compiler.degree = 0;
121+
child->compiler.degree = 1;
120122
mjsFrame* frame = mjs_addFrame(mjs_findBody(parent, "world"), NULL);
121123
mjsSite* site = mjs_addSite(mjs_findBody(parent, "world"), NULL);
122124
mjsBody* body = mjs_addBody(mjs_findBody(child, "world"), NULL);
@@ -133,6 +135,11 @@ or :ref:`attach a frame to a body<mjs_attachFrame>`:
133135
mjsFrame* frame = mjs_addFrame(mjs_findBody(child, "world"), NULL);
134136
mjsFrame* attached_frame = mjs_attachFrame(body, frame, "attached-", "-1");
135137
138+
Note that in the above examples, the parent and child models have different values for ``compiler.degree``,
139+
corresponding to the :ref:`compiler/angle<compiler-angle>` attribute, specifying the units in which angles are
140+
interperted. Compiler options are carried over during attachment, so the child model will be compiled using X, while the
141+
parent will be compiled using Y.
142+
136143
.. _meDefault:
137144

138145
Default classes

src/user/user_model.cc

Lines changed: 25 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -146,6 +146,9 @@ mjCModel::mjCModel() {
146146
defaults_.push_back(new mjCDef);
147147
defaults_.back()->name = "main";
148148

149+
// point to model from spec
150+
PointToLocal();
151+
149152
// world body
150153
mjCBody* world = new mjCBody(this);
151154
mjuu_zerovec(world->pos, 3);
@@ -163,14 +166,15 @@ mjCModel::mjCModel() {
163166
// create mjCBase lists from children lists
164167
CreateObjectLists();
165168

166-
// point to model from spec
167-
PointToLocal();
169+
// the source spec is the model itself, overwritten in the copy constructor
170+
source_spec_ = &spec;
168171
}
169172

170173

171174

172175
mjCModel::mjCModel(const mjCModel& other) {
173176
CreateObjectLists();
177+
source_spec_ = (mjSpec*)&other.spec;
174178
*this = other;
175179
}
176180

@@ -1222,6 +1226,25 @@ mjSpec* mjCModel::FindSpec(std::string name) const {
12221226

12231227

12241228

1229+
// find spec by mjsCompiler pointer
1230+
mjSpec* mjCModel::FindSpec(const mjsCompiler* compiler_) const {
1231+
for (auto spec : specs_) {
1232+
if (&(static_cast<const mjCModel*>(spec->element)->GetSourceSpec()->compiler) == compiler_) {
1233+
return spec;
1234+
}
1235+
}
1236+
return nullptr;
1237+
}
1238+
1239+
1240+
1241+
// get the spec from which this model was created
1242+
mjSpec* mjCModel::GetSourceSpec() const {
1243+
return source_spec_;
1244+
}
1245+
1246+
1247+
12251248
//------------------------------- COMPILER PHASES --------------------------------------------------
12261249

12271250
// make lists of objects in tree: bodies, geoms, joints, sites, cameras, lights

src/user/user_model.h

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -236,6 +236,7 @@ class mjCModel : public mjCModel_, private mjSpec {
236236
mjCBase* FindObject(mjtObj type, std::string name) const; // find object given type and name
237237
mjCBase* FindTree(mjCBody* body, mjtObj type, std::string name); // find tree object given name
238238
mjSpec* FindSpec(std::string name) const; // find spec given name
239+
mjSpec* FindSpec(const mjsCompiler* compiler_) const; // find spec given mjsCompiler
239240
void ActivatePlugin(const mjpPlugin* plugin, int slot); // activate plugin
240241

241242
// accessors
@@ -303,10 +304,16 @@ class mjCModel : public mjCModel_, private mjSpec {
303304
// map from default class name to default class pointer
304305
std::unordered_map<std::string, mjCDef*> def_map;
305306

307+
// get the spec from which this model was created
308+
mjSpec* GetSourceSpec() const;
309+
306310
private:
307311
// settings for each defaults class
308312
std::vector<mjCDef*> defaults_;
309313

314+
// spec from which this model was created in copy constructor
315+
mjSpec* source_spec_;
316+
310317
// list of active plugins
311318
std::vector<std::pair<const mjpPlugin*, int>> active_plugins_;
312319

src/user/user_objects.cc

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -798,7 +798,7 @@ mjCBody::mjCBody(mjCModel* _model) {
798798

799799
mjCBody::mjCBody(const mjCBody& other, mjCModel* _model) {
800800
model = _model;
801-
mjSpec* origin = model->FindSpec(mjs_getString(other.model->spec.modelname));
801+
mjSpec* origin = model->FindSpec(other.compiler);
802802
compiler = origin ? &origin->compiler : &model->spec.compiler;
803803
*this = other;
804804
CopyPlugin();
@@ -881,7 +881,7 @@ mjCBody& mjCBody::operator+=(const mjCFrame& other) {
881881
}
882882

883883
// copy input frame
884-
mjSpec* origin = model->FindSpec(mjs_getString(other.model->spec.modelname));
884+
mjSpec* origin = model->FindSpec(other.compiler);
885885
frames.push_back(new mjCFrame(other));
886886
frames.back()->body = this;
887887
frames.back()->model = model;
@@ -947,7 +947,7 @@ void mjCBody::CopyList(std::vector<T*>& dst, const std::vector<T*>& src,
947947
if (pframe && !pframe->IsAncestor(src[i]->frame)) {
948948
continue; // skip if the element is not inside pframe
949949
}
950-
mjSpec* origin = model->FindSpec(mjs_getString(src[i]->model->spec.modelname));
950+
mjSpec* origin = model->FindSpec(src[i]->compiler);
951951
dst.push_back(new T(*src[i]));
952952
dst.back()->body = this;
953953
dst.back()->model = model;

test/user/user_api_test.cc

Lines changed: 54 additions & 35 deletions
Original file line numberDiff line numberDiff line change
@@ -2033,52 +2033,71 @@ TEST_F(MujocoTest, ResizeParentKeyframe) {
20332033
}
20342034

20352035
TEST_F(MujocoTest, DifferentUnitsAllowed) {
2036-
mjSpec* child = mj_makeSpec();
2037-
child->compiler.degree = 0;
2038-
mjsBody* body = mjs_addBody(mjs_findBody(child, "world"), 0);
2039-
body->alt.type = mjORIENTATION_EULER;
2040-
body->alt.euler[0] = -mjPI / 2;
2041-
mjsGeom* geom = mjs_addGeom(body, 0);
2042-
geom->size[0] = 1;
2043-
mjsJoint* joint = mjs_addJoint(body, 0);
2044-
joint->type = mjJNT_HINGE;
2045-
joint->range[0] = -mjPI / 4;
2046-
joint->range[1] = mjPI / 4;
2036+
static constexpr char child_xml[] = R"(
2037+
<mujoco>
2038+
<compiler angle="radian"/>
20472039
2048-
mjSpec* parent = mj_makeSpec();
2049-
parent->compiler.degree = 1;
2050-
mjsFrame* frame = mjs_addFrame(mjs_findBody(parent, "world"), 0);
2051-
frame->alt.type = mjORIENTATION_EULER;
2052-
frame->alt.euler[0] = 90;
2040+
<worldbody>
2041+
<body name="child" euler="-1.5707963 0 0">
2042+
<geom type="box" size="1 1 1"/>
2043+
<joint name="child_joint" range="-3.1415926 3.1415926"/>
2044+
</body>
2045+
</worldbody>
2046+
</mujoco>
2047+
)";
20532048

2054-
EXPECT_THAT(mjs_attachBody(frame, body, "child-", ""), NotNull());
2055-
mjModel* model = mj_compile(parent, 0);
2049+
static constexpr char parent_xml[] = R"(
2050+
<mujoco>
2051+
<worldbody>
2052+
<body name="parent">
2053+
<geom type="box" size="1 1 1"/>
2054+
<joint name="parent_joint" range="-180 180"/>
2055+
<frame name="frame" euler="90 0 0"/>
2056+
</body>
2057+
</worldbody>
2058+
</mujoco>
2059+
)";
2060+
2061+
std::array<char, 1024> error;
2062+
mjSpec* child = mj_parseXMLString(child_xml, 0, error.data(), error.size());
2063+
mjSpec* spec = mj_parseXMLString(parent_xml, 0, error.data(), error.size());
2064+
ASSERT_THAT(spec, NotNull()) << error.data();
2065+
mjs_attachBody(mjs_findFrame(spec, "frame"), mjs_findBody(child, "child"),
2066+
"child_", "");
2067+
2068+
mjModel* model = mj_compile(spec, 0);
20562069
EXPECT_THAT(model, NotNull());
2070+
EXPECT_THAT(model->njnt, 2);
2071+
EXPECT_NEAR(model->jnt_range[0], -mjPI, 1e-6);
2072+
EXPECT_NEAR(model->jnt_range[1], mjPI, 1e-6);
2073+
EXPECT_NEAR(model->jnt_range[2], -mjPI, 1e-6);
2074+
EXPECT_NEAR(model->jnt_range[3], mjPI, 1e-6);
20572075
EXPECT_NEAR(model->body_quat[4], 1, 1e-12);
20582076
EXPECT_NEAR(model->body_quat[5], 0, 1e-12);
20592077
EXPECT_NEAR(model->body_quat[6], 0, 1e-12);
20602078
EXPECT_NEAR(model->body_quat[7], 0, 1e-12);
2061-
EXPECT_NEAR(model->jnt_range[0], -mjPI / 4, 1e-7);
2062-
EXPECT_NEAR(model->jnt_range[1], mjPI / 4, 1e-7);
20632079

2064-
mjSpec* copy = mj_copySpec(parent);
2065-
EXPECT_THAT(copy, NotNull());
2066-
mj_deleteModel(model);
2080+
mjSpec* copied_spec = mj_copySpec(spec);
2081+
ASSERT_THAT(copied_spec, NotNull());
20672082
mj_deleteSpec(child);
2068-
mj_deleteSpec(parent);
2083+
mj_deleteSpec(spec);
2084+
mj_deleteModel(model);
20692085

20702086
// check that deleting `parent` or `child` does not invalidate the copy
2071-
mjModel* copy_model = mj_compile(copy, 0);
2072-
EXPECT_THAT(copy_model, NotNull());
2073-
EXPECT_NEAR(copy_model->body_quat[0], 1, 1e-12);
2074-
EXPECT_NEAR(copy_model->body_quat[1], 0, 1e-12);
2075-
EXPECT_NEAR(copy_model->body_quat[2], 0, 1e-12);
2076-
EXPECT_NEAR(copy_model->body_quat[3], 0, 1e-12);
2077-
EXPECT_NEAR(copy_model->jnt_range[0], -mjPI / 4, 1e-7);
2078-
EXPECT_NEAR(copy_model->jnt_range[1], mjPI / 4, 1e-7);
2079-
2080-
mj_deleteModel(copy_model);
2081-
mj_deleteSpec(copy);
2087+
mjModel* copied_model = mj_compile(copied_spec, 0);
2088+
EXPECT_THAT(copied_model, NotNull());
2089+
EXPECT_THAT(copied_model->njnt, 2);
2090+
EXPECT_NEAR(copied_model->jnt_range[0], -mjPI, 1e-6);
2091+
EXPECT_NEAR(copied_model->jnt_range[1], mjPI, 1e-6);
2092+
EXPECT_NEAR(copied_model->jnt_range[2], -mjPI, 1e-6);
2093+
EXPECT_NEAR(copied_model->jnt_range[3], mjPI, 1e-6);
2094+
EXPECT_NEAR(copied_model->body_quat[4], 1, 1e-12);
2095+
EXPECT_NEAR(copied_model->body_quat[5], 0, 1e-12);
2096+
EXPECT_NEAR(copied_model->body_quat[6], 0, 1e-12);
2097+
EXPECT_NEAR(copied_model->body_quat[7], 0, 1e-12);
2098+
2099+
mj_deleteSpec(copied_spec);
2100+
mj_deleteModel(copied_model);
20822101
}
20832102

20842103
TEST_F(MujocoTest, CopyAttachedSpec) {

test/xml/xml_native_reader_test.cc

Lines changed: 66 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1579,6 +1579,72 @@ TEST_F(XMLReaderTest, InvalidAttach) {
15791579
mj_deleteVFS(vfs.get());
15801580
}
15811581

1582+
TEST_F(XMLReaderTest, LookupCompilerOptionWithoutSpecCopy) {
1583+
static constexpr char child_xml[] = R"(
1584+
<mujoco>
1585+
<compiler angle="radian"/>
1586+
1587+
<worldbody>
1588+
<body name="child">
1589+
<geom type="box" size="1 1 1"/>
1590+
<joint name="child_joint" range="-3.1415926 3.1415926"/>
1591+
</body>
1592+
</worldbody>
1593+
</mujoco>
1594+
)";
1595+
1596+
static constexpr char parent_xml[] = R"(
1597+
<mujoco>
1598+
<asset>
1599+
<model name="child" file="child.xml"/>
1600+
</asset>
1601+
1602+
<worldbody>
1603+
<body name="parent">
1604+
<geom type="box" size="1 1 1"/>
1605+
<joint name="parent_joint" range="-180 180"/>
1606+
<attach model="child" body="child" prefix="child_"/>
1607+
</body>
1608+
</worldbody>
1609+
</mujoco>
1610+
)";
1611+
1612+
auto vfs = std::make_unique<mjVFS>();
1613+
mj_defaultVFS(vfs.get());
1614+
mj_addBufferVFS(vfs.get(), "child.xml", child_xml, sizeof(child_xml));
1615+
mj_addBufferVFS(vfs.get(), "parent.xml", parent_xml, sizeof(parent_xml));
1616+
1617+
std::array<char, 1024> error;
1618+
auto* spec = mj_parseXMLString(parent_xml, vfs.get(), error.data(),
1619+
error.size());
1620+
ASSERT_THAT(spec, NotNull()) << error.data();
1621+
1622+
mjModel* model = mj_compile(spec, vfs.get());
1623+
EXPECT_THAT(model, NotNull());
1624+
EXPECT_THAT(model->njnt, 2);
1625+
EXPECT_NEAR(model->jnt_range[0], -3.14159, 1e-5);
1626+
EXPECT_NEAR(model->jnt_range[1], 3.14159, 1e-5);
1627+
EXPECT_NEAR(model->jnt_range[2], -3.14159, 1e-5);
1628+
EXPECT_NEAR(model->jnt_range[3], 3.14159, 1e-5);
1629+
1630+
mjSpec* copied_spec = mj_copySpec(spec);
1631+
ASSERT_THAT(copied_spec, NotNull());
1632+
mjModel* copied_model = mj_compile(copied_spec, vfs.get());
1633+
EXPECT_THAT(copied_model, NotNull());
1634+
EXPECT_THAT(copied_model->njnt, 2);
1635+
EXPECT_NEAR(copied_model->jnt_range[0], -3.14159, 1e-5);
1636+
EXPECT_NEAR(copied_model->jnt_range[1], 3.14159, 1e-5);
1637+
EXPECT_NEAR(copied_model->jnt_range[2], -3.14159, 1e-5);
1638+
EXPECT_NEAR(copied_model->jnt_range[3], 3.14159, 1e-5);
1639+
1640+
mj_deleteSpec(spec);
1641+
mj_deleteSpec(copied_spec);
1642+
mj_deleteModel(model);
1643+
mj_deleteModel(copied_model);
1644+
1645+
mj_deleteVFS(vfs.get());
1646+
}
1647+
15821648
// ----------------------- test camera parsing ---------------------------------
15831649

15841650
TEST_F(XMLReaderTest, CameraInvalidFovyAndSensorsize) {

0 commit comments

Comments
 (0)