Skip to content

Commit f7d38da

Browse files
quaglacopybara-github
authored andcommitted
Add recursive call to FindSpec for handling nested attachments.
PiperOrigin-RevId: 713629578 Change-Id: I23efa5a86bac187fc42eb955d29cc03cbacfd9e0
1 parent 40ef08c commit f7d38da

File tree

3 files changed

+39
-7
lines changed

3 files changed

+39
-7
lines changed

src/user/user_mesh.cc

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -151,6 +151,7 @@ mjCMesh::mjCMesh(mjCModel* _model, mjCDef* _def) {
151151

152152
// set model, def
153153
model = _model;
154+
if (_model) compiler = &_model->spec.compiler;
154155
classname = (_def ? _def->name : (_model ? "main" : ""));
155156

156157
// in case this body is not compiled
@@ -1981,6 +1982,7 @@ mjCSkin::mjCSkin(mjCModel* _model) {
19811982

19821983
// set model pointer
19831984
model = _model;
1985+
if (model) compiler = &model->spec.compiler;
19841986

19851987
// clear data
19861988
spec_file_.clear();
@@ -2638,6 +2640,7 @@ mjCFlex::mjCFlex(mjCModel* _model) {
26382640

26392641
// set model
26402642
model = _model;
2643+
if (_model) compiler = &_model->spec.compiler;
26412644

26422645
// clear internal variables
26432646
nvert = 0;

src/user/user_model.cc

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -236,7 +236,7 @@ void mjCModel::CopyList(std::vector<T*>& dest,
236236
}
237237
// copy the element from the other model to this model
238238
source[i]->ForgetKeyframes();
239-
mjSpec* origin = FindSpec(mjs_getString(source[i]->model->spec.modelname));
239+
mjSpec* origin = FindSpec(source[i]->compiler);
240240
dest.push_back(candidate);
241241
dest.back()->model = this;
242242
dest.back()->compiler = origin ? &origin->compiler : &spec.compiler;
@@ -1228,9 +1228,13 @@ mjSpec* mjCModel::FindSpec(std::string name) const {
12281228

12291229
// find spec by mjsCompiler pointer
12301230
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;
1231+
if (&GetSourceSpec()->compiler == compiler_) {
1232+
return (mjSpec*)&spec;
1233+
}
1234+
for (auto s : specs_) {
1235+
mjSpec* source = static_cast<mjCModel*>(s->element)->FindSpec(compiler_);
1236+
if (source) {
1237+
return source;
12341238
}
12351239
}
12361240
return nullptr;

test/user/user_api_test.cc

Lines changed: 28 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -2033,6 +2033,19 @@ TEST_F(MujocoTest, ResizeParentKeyframe) {
20332033
}
20342034

20352035
TEST_F(MujocoTest, DifferentUnitsAllowed) {
2036+
static constexpr char gchild_xml[] = R"(
2037+
<mujoco model="gchild">
2038+
<compiler angle="radian"/>
2039+
2040+
<worldbody>
2041+
<body name="gchild" euler="-1.5707963 0 0">
2042+
<geom type="box" size="1 1 1"/>
2043+
<joint name="gchild_joint" range="-3.1415926 3.1415926"/>
2044+
</body>
2045+
</worldbody>
2046+
</mujoco>
2047+
)";
2048+
20362049
static constexpr char child_xml[] = R"(
20372050
<mujoco>
20382051
<compiler angle="radian"/>
@@ -2041,6 +2054,7 @@ TEST_F(MujocoTest, DifferentUnitsAllowed) {
20412054
<body name="child" euler="-1.5707963 0 0">
20422055
<geom type="box" size="1 1 1"/>
20432056
<joint name="child_joint" range="-3.1415926 3.1415926"/>
2057+
<frame name="frame" euler="1.5707963 0 0"/>
20442058
</body>
20452059
</worldbody>
20462060
</mujoco>
@@ -2059,38 +2073,49 @@ TEST_F(MujocoTest, DifferentUnitsAllowed) {
20592073
)";
20602074

20612075
std::array<char, 1024> error;
2076+
mjSpec* gchild =
2077+
mj_parseXMLString(gchild_xml, 0, error.data(), error.size());
20622078
mjSpec* child = mj_parseXMLString(child_xml, 0, error.data(), error.size());
20632079
mjSpec* spec = mj_parseXMLString(parent_xml, 0, error.data(), error.size());
20642080
ASSERT_THAT(spec, NotNull()) << error.data();
2065-
mjs_attachBody(mjs_findFrame(spec, "frame"), mjs_findBody(child, "child"),
2081+
mjs_attachBody(mjs_findFrame(child, "frame"),
2082+
mjs_findBody(gchild, "gchild"),
2083+
"gchild_", "");
2084+
mjs_attachBody(mjs_findFrame(spec, "frame"),
2085+
mjs_findBody(child, "child"),
20662086
"child_", "");
20672087

20682088
mjModel* model = mj_compile(spec, 0);
20692089
EXPECT_THAT(model, NotNull());
2070-
EXPECT_THAT(model->njnt, 2);
2090+
EXPECT_THAT(model->njnt, 3);
20712091
EXPECT_NEAR(model->jnt_range[0], -mjPI, 1e-6);
20722092
EXPECT_NEAR(model->jnt_range[1], mjPI, 1e-6);
20732093
EXPECT_NEAR(model->jnt_range[2], -mjPI, 1e-6);
20742094
EXPECT_NEAR(model->jnt_range[3], mjPI, 1e-6);
2095+
EXPECT_NEAR(model->jnt_range[4], -mjPI, 1e-6);
2096+
EXPECT_NEAR(model->jnt_range[5], mjPI, 1e-6);
20752097
EXPECT_NEAR(model->body_quat[4], 1, 1e-12);
20762098
EXPECT_NEAR(model->body_quat[5], 0, 1e-12);
20772099
EXPECT_NEAR(model->body_quat[6], 0, 1e-12);
20782100
EXPECT_NEAR(model->body_quat[7], 0, 1e-12);
20792101

20802102
mjSpec* copied_spec = mj_copySpec(spec);
20812103
ASSERT_THAT(copied_spec, NotNull());
2104+
mj_deleteSpec(gchild);
20822105
mj_deleteSpec(child);
20832106
mj_deleteSpec(spec);
20842107
mj_deleteModel(model);
20852108

20862109
// check that deleting `parent` or `child` does not invalidate the copy
20872110
mjModel* copied_model = mj_compile(copied_spec, 0);
20882111
EXPECT_THAT(copied_model, NotNull());
2089-
EXPECT_THAT(copied_model->njnt, 2);
2112+
EXPECT_THAT(copied_model->njnt, 3);
20902113
EXPECT_NEAR(copied_model->jnt_range[0], -mjPI, 1e-6);
20912114
EXPECT_NEAR(copied_model->jnt_range[1], mjPI, 1e-6);
20922115
EXPECT_NEAR(copied_model->jnt_range[2], -mjPI, 1e-6);
20932116
EXPECT_NEAR(copied_model->jnt_range[3], mjPI, 1e-6);
2117+
EXPECT_NEAR(copied_model->jnt_range[4], -mjPI, 1e-6);
2118+
EXPECT_NEAR(copied_model->jnt_range[5], mjPI, 1e-6);
20942119
EXPECT_NEAR(copied_model->body_quat[4], 1, 1e-12);
20952120
EXPECT_NEAR(copied_model->body_quat[5], 0, 1e-12);
20962121
EXPECT_NEAR(copied_model->body_quat[6], 0, 1e-12);

0 commit comments

Comments
 (0)