Skip to content

Commit fa37f00

Browse files
authored
Merge ce8c032 into a55f9e3
2 parents a55f9e3 + ce8c032 commit fa37f00

File tree

4 files changed

+22
-0
lines changed

4 files changed

+22
-0
lines changed

src/Model.cc

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -397,9 +397,18 @@ Errors Model::Load(ElementPtr _sdf)
397397
errors.insert(errors.end(), setPoseRelativeToGraphErrors.begin(),
398398
setPoseRelativeToGraphErrors.end());
399399
}
400+
// Pass graph pointer to joint and check parent names
400401
for (auto &joint : this->dataPtr->joints)
401402
{
402403
joint.SetPoseRelativeToGraph(this->dataPtr->poseGraph);
404+
const std::string &parentLinkName = joint.ParentLinkName();
405+
if (parentLinkName != "world" && !this->LinkByName(parentLinkName))
406+
{
407+
errors.push_back({ErrorCode::JOINT_PARENT_LINK_INVALID,
408+
"parent link with name[" + parentLinkName +
409+
"] specified by joint with name[" + joint.Name() +
410+
"] not found in model with name[" + this->Name() + "]."});
411+
}
403412
}
404413
for (auto &frame : this->dataPtr->frames)
405414
{

src/ign_TEST.cc

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -260,6 +260,17 @@ TEST(check, IGN_UTILS_TEST_DISABLED_ON_WIN32(SDF))
260260
EXPECT_EQ("Valid.\n", output) << output;
261261
}
262262

263+
// Check an SDF file with the infinite values for joint axis limits.
264+
// This is a valid file.
265+
{
266+
std::string path = pathBase +"/joint_axis_infinite_limits.sdf";
267+
268+
// Check joint_axis_infinite_limits.sdf
269+
std::string output =
270+
custom_exec_str(IgnCommand() + " sdf -k " + path + SdfVersion());
271+
EXPECT_EQ("Valid.\n", output) << output;
272+
}
273+
263274
// Check an SDF file with the second link specified as the canonical link.
264275
// This is a valid file.
265276
{

test/sdf/joint_axis_infinite_limits.sdf

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66
<link name="link3"/>
77
<link name="link4"/>
88
<link name="link5"/>
9+
<link name="link6"/>
910

1011
<joint name="default_joint_limits" type="revolute">
1112
<child>link1</child>

test/sdf/joint_axis_xyz_normalization.sdf

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66
<link name="link3"/>
77
<link name="link4"/>
88
<link name="link5"/>
9+
<link name="link6"/>
910

1011
<joint name="joint1" type="revolute">
1112
<child>link1</child>

0 commit comments

Comments
 (0)