Skip to content

Commit

Permalink
parser: update joint check function, add tests
Browse files Browse the repository at this point in the history
Signed-off-by: Steve Peters <[email protected]>
  • Loading branch information
scpeters committed Jun 23, 2020
1 parent 85ab1c5 commit f1198d5
Show file tree
Hide file tree
Showing 3 changed files with 87 additions and 8 deletions.
51 changes: 49 additions & 2 deletions src/ign_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -197,7 +197,7 @@ TEST(check, SDF)
// Check joint_invalid_child.sdf
std::string output =
custom_exec_str(g_ignCommand + " sdf -k " + path + g_sdfVersion);
EXPECT_NE(output.find("Error: Child link with name[invalid] specified by "
EXPECT_NE(output.find("Error: Child frame with name[invalid] specified by "
"joint with name[joint] not found in model with "
"name[joint_invalid_child]."),
std::string::npos) << output;
Expand All @@ -210,12 +210,37 @@ TEST(check, SDF)
// Check joint_invalid_parent.sdf
std::string output =
custom_exec_str(g_ignCommand + " sdf -k " + path + g_sdfVersion);
EXPECT_NE(output.find("Error: parent link with name[invalid] specified by "
EXPECT_NE(output.find("Error: parent frame with name[invalid] specified by "
"joint with name[joint] not found in model with "
"name[joint_invalid_parent]."),
std::string::npos) << output;
}

// Check an SDF file with a joint with an invalid child link.
{
std::string path = pathBase +"/joint_invalid_self_child.sdf";

// Check joint_invalid_self_child.sdf
std::string output =
custom_exec_str(g_ignCommand + " sdf -k " + path + g_sdfVersion);
EXPECT_NE(output.find("Error: FrameAttachedToGraph cycle detected, "
"already visited vertex [self]."),
std::string::npos) << output;
}

// Check an SDF file with a joint with an invalid parent link.
{
std::string path = pathBase +"/joint_invalid_self_parent.sdf";

// Check joint_invalid_self_parent.sdf
std::string output =
custom_exec_str(g_ignCommand + " sdf -k " + path + g_sdfVersion);
EXPECT_NE(output.find("Error: joint with name[self] in model with "
"name[joint_invalid_self_parent] must not specify "
"its own name as the parent frame."),
std::string::npos) << output;
}

// Check an SDF file with a joint with identical parent and child.
{
std::string path = pathBase +"/joint_invalid_parent_same_as_child.sdf";
Expand Down Expand Up @@ -252,6 +277,28 @@ TEST(check, SDF)
EXPECT_EQ("Valid.\n", output) << output;
}

// Check an SDF file with the world specified as a parent link.
// This is a valid file.
{
std::string path = pathBase +"/joint_child_frame.sdf";

// Check joint_child_frame.sdf
std::string output =
custom_exec_str(g_ignCommand + " sdf -k " + path + g_sdfVersion);
EXPECT_EQ("Valid.\n", output) << output;
}

// Check an SDF file with the world specified as a parent link.
// This is a valid file.
{
std::string path = pathBase +"/joint_parent_frame.sdf";

// Check joint_parent_frame.sdf
std::string output =
custom_exec_str(g_ignCommand + " sdf -k " + path + g_sdfVersion);
EXPECT_EQ("Valid.\n", output) << output;
}

// Check an SDF file with the second link specified as the canonical link.
// This is a valid file.
{
Expand Down
40 changes: 36 additions & 4 deletions src/parser.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1824,9 +1824,11 @@ bool checkJointParentChildLinkNames(const sdf::Root *_root)
auto joint = _model->JointByIndex(j);

const std::string &parentName = joint->ParentLinkName();
if (parentName != "world" && !_model->LinkNameExists(parentName))
if (parentName != "world" && !_model->LinkNameExists(parentName) &&
!_model->JointNameExists(parentName) &&
!_model->FrameNameExists(parentName))
{
std::cerr << "Error: parent link with name[" << parentName
std::cerr << "Error: parent frame with name[" << parentName
<< "] specified by joint with name[" << joint->Name()
<< "] not found in model with name[" << _model->Name()
<< "]."
Expand All @@ -1835,16 +1837,46 @@ bool checkJointParentChildLinkNames(const sdf::Root *_root)
}

const std::string &childName = joint->ChildLinkName();
if (childName != "world" && !_model->LinkNameExists(childName))
if (childName == "world")
{
std::cerr << "Error: child link with name[" << childName
std::cerr << "Error: invalid child name[world"
<< "] specified by joint with name[" << joint->Name()
<< "] in model with name[" << _model->Name()
<< "]."
<< std::endl;
modelResult = false;
}

if (!_model->LinkNameExists(childName) &&
!_model->JointNameExists(childName) &&
!_model->FrameNameExists(childName))
{
std::cerr << "Error: child frame with name[" << childName
<< "] specified by joint with name[" << joint->Name()
<< "] not found in model with name[" << _model->Name()
<< "]."
<< std::endl;
modelResult = false;
}

if (childName == joint->Name())
{
std::cerr << "Error: joint with name[" << joint->Name()
<< "] in model with name[" << _model->Name()
<< "] must not specify its own name as the child frame."
<< std::endl;
modelResult = false;
}

if (parentName == joint->Name())
{
std::cerr << "Error: joint with name[" << joint->Name()
<< "] in model with name[" << _model->Name()
<< "] must not specify its own name as the parent frame."
<< std::endl;
modelResult = false;
}

if (childName == parentName)
{
std::cerr << "Error: joint with name[" << joint->Name()
Expand Down
4 changes: 2 additions & 2 deletions test/integration/joint_dom.cc
Original file line number Diff line number Diff line change
Expand Up @@ -221,7 +221,7 @@ TEST(DOMJoint, LoadInvalidJointChildWorld)
EXPECT_EQ(errors[1].Code(), sdf::ErrorCode::JOINT_CHILD_LINK_INVALID);
EXPECT_NE(std::string::npos,
errors[1].Message().find(
"Child link with name[world] specified by joint with name[joint] "
"Child frame with name[world] specified by joint with name[joint] "
"not found in model with name[joint_child_world]"));
}

Expand Down Expand Up @@ -366,7 +366,7 @@ TEST(DOMJoint, LoadInvalidChild)
EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::JOINT_CHILD_LINK_INVALID);
EXPECT_NE(std::string::npos,
errors[0].Message().find(
"Child link with name[invalid] specified by joint with name[joint] not "
"Child frame with name[invalid] specified by joint with name[joint] not "
"found"));
EXPECT_EQ(errors[1].Code(), sdf::ErrorCode::FRAME_ATTACHED_TO_GRAPH_ERROR);
EXPECT_NE(std::string::npos,
Expand Down

0 comments on commit f1198d5

Please sign in to comment.