Skip to content

Commit

Permalink
renamed function & strip //gripper/@name if prefix present
Browse files Browse the repository at this point in the history
Signed-off-by: Jenn Nguyen <jenn@openrobotics.org>
  • Loading branch information
jennuine committed Mar 18, 2021
1 parent 8dfcd7f commit 3e0cd5d
Show file tree
Hide file tree
Showing 4 changed files with 47 additions and 23 deletions.
28 changes: 10 additions & 18 deletions src/Converter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -42,11 +42,11 @@ bool EndsWith(const std::string& _a, const std::string& _b)
}

/////////////////////////////////////////////////
// returns true if the element is one of the listed for Unflatten conversion
bool IsInterfaceElement(const std::string &_elemName)
// returns true if the element is not one of the listed for Unflatten conversion
bool IsNotFlattenedElement(const std::string &_elemName)
{
return (_elemName != "frame" && _elemName != "joint"
&& _elemName != "link" && _elemName != "model");
return (_elemName != "frame" && _elemName != "joint" && _elemName != "link"
&& _elemName != "model" && _elemName != "gripper");
}

/////////////////////////////////////////////////
Expand Down Expand Up @@ -262,9 +262,6 @@ void Converter::ConvertImpl(tinyxml2::XMLElement *_elem,
else if (name == "unflatten")
{
Unflatten(_elem);
// TODO(jenn) delete debug statements
// std::cout << "\n\n_elem after unflatten:\n"
// << ElementToString(_elem) << std::endl;
}
else if (name != "convert")
{
Expand Down Expand Up @@ -292,7 +289,7 @@ void Converter::Unflatten(tinyxml2::XMLElement *_elem)
std::string elemName = elem->Name();

// skip element if not one of the following or if missing name attribute
if (IsInterfaceElement(elemName) || !elem->Attribute("name"))
if (IsNotFlattenedElement(elemName) || !elem->Attribute("name"))
continue;

std::string attrName = elem->Attribute("name");
Expand All @@ -303,12 +300,7 @@ void Converter::Unflatten(tinyxml2::XMLElement *_elem)
// recursive unflatten
if (elemName == "model")
{
// std::cout << "before recursive:\n"
// << ElementToString(elem) << std::endl;
Unflatten(elem);

// std::cout << "unflatteneded model:\n"
// << ElementToString(elem) << std::endl;
break;
}

Expand All @@ -329,7 +321,6 @@ void Converter::Unflatten(tinyxml2::XMLElement *_elem)

if (!firstUnflatModel)
firstUnflatModel = newModel;
// std::cout << "newModel:\n" << ElementToString(newModel) << std::endl;
}
}
}
Expand Down Expand Up @@ -357,9 +348,9 @@ bool Converter::FindNewModelElements(tinyxml2::XMLElement *_elem,

if (elemAttrName.empty() ||
elemAttrName.compare(0, newModelNameSize, newModelName) != 0 ||
IsInterfaceElement(elemName))
IsNotFlattenedElement(elemName))
{
// since //gripper/@name is not flattened but the children are
// since //gripper/@name may not be flattened but the children are
// & elemAttrName.compare will evaluate to true, don't skip this element
if (elemName != "gripper")
{
Expand All @@ -368,9 +359,10 @@ bool Converter::FindNewModelElements(tinyxml2::XMLElement *_elem,
}
}

// Child attribute name w/ newModelName prefix stripped except for //gripper
// Child attribute name w/ newModelName prefix stripped except for
// possibly //gripper, which may or may not have a prefix
std::string childAttrName;
if (elemName != "gripper")
if (elemAttrName.compare(0, newModelNameSize, newModelName) == 0)
{
childAttrName = elemAttrName.substr(_childNameIdx);
elem->SetAttribute("name", childAttrName.c_str());
Expand Down
1 change: 0 additions & 1 deletion src/Converter.hh
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
#include <tinyxml2.h>

#include <string>
#include <vector>
#include <tuple>

#include <sdf/sdf_config.h>
Expand Down
35 changes: 33 additions & 2 deletions src/Converter_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2142,14 +2142,14 @@ TEST(Converter, Pose_16_to_17)
}

const std::string CONVERT_DOC_17_18 =
sdf::filesystem::append(PROJECT_SOURCE_PATH, "sdf", "1.8", "1_7.convert");
sdf::testing::SourceFile("sdf", "1.8", "1_7.convert");

/////////////////////////////////////////////////
/// Test conversion unflattened world in 1.7 to 1.8
TEST(Converter, World_17_to_18)
{
// for ElementToString
using namespace sdf::SDF_VERSION_NAMESPACE;
using namespace sdf;

// ------- The flattened world in 1.7 format
std::string xmlString = R"(
Expand Down Expand Up @@ -2207,35 +2207,44 @@ TEST(Converter, World_17_to_18)

// Check some basic elements
tinyxml2::XMLElement *convertedElem = xmlDoc.FirstChildElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "sdf");
convertedElem = convertedElem->FirstChildElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "world");
convertedElem = convertedElem->FirstChildElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "model");
EXPECT_STREQ(convertedElem->Attribute("name"), "include_links");

// Check unnested elements
convertedElem = convertedElem->FirstChildElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "model");
EXPECT_STREQ(convertedElem->Attribute("name"), "A");
EXPECT_STREQ(convertedElem->Attribute("canonical_link"), "B::C");
EXPECT_EQ(convertedElem->NextSiblingElement(), nullptr);
convertedElem = convertedElem->FirstChildElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "pose");
EXPECT_STREQ(convertedElem->Attribute("relative_to"), "__model__");

convertedElem = convertedElem->NextSiblingElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "model");
EXPECT_STREQ(convertedElem->Attribute("canonical_link"), "C");
EXPECT_EQ(convertedElem->NextSiblingElement(), nullptr);
convertedElem = convertedElem->FirstChildElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "pose");
EXPECT_STREQ(convertedElem->Attribute("relative_to"), "__model__");
convertedElem = convertedElem->NextSiblingElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "link");
EXPECT_STREQ(convertedElem->Attribute("name"), "C");
EXPECT_EQ(convertedElem->NextSiblingElement(), nullptr);
convertedElem = convertedElem->FirstChildElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "pose");
EXPECT_STREQ(convertedElem->Attribute("relative_to"), "__model__");

Expand Down Expand Up @@ -2295,6 +2304,10 @@ TEST(Converter, World_17_to_18)
<gripper_link>ChildModel::L1</gripper_link>
<palm_link>ChildModel::L2</palm_link>
</gripper>
<gripper name="ChildModel::gripper2">
<gripper_link>ChildModel::L1</gripper_link>
<palm_link>ChildModel::L2</palm_link>
</gripper>
</model>
</world>
</sdf>)";
Expand Down Expand Up @@ -2361,6 +2374,10 @@ TEST(Converter, World_17_to_18)
<gripper_link>L1</gripper_link>
<palm_link>L2</palm_link>
</gripper>
<gripper name="gripper2">
<gripper_link>L1</gripper_link>
<palm_link>L2</palm_link>
</gripper>
</model>
</model>
</world>
Expand Down Expand Up @@ -2446,54 +2463,68 @@ TEST(Converter, World_17_to_18)

// Check some basic elements
convertedElem = xmlDoc.FirstChildElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "sdf");
convertedElem = convertedElem->FirstChildElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "world");
convertedElem = convertedElem->FirstChildElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "model");
EXPECT_STREQ(convertedElem->Attribute("name"), "ParentModel");
EXPECT_EQ(convertedElem->NextSiblingElement(), nullptr);

// Check unnested elements
convertedElem = convertedElem->FirstChildElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "model");
EXPECT_STREQ(convertedElem->Attribute("name"), "C");
convertedElem = convertedElem->NextSiblingElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "model");
EXPECT_STREQ(convertedElem->Attribute("name"), "ChildModel");
EXPECT_STREQ(convertedElem->FirstChildElement()->Name(), "link");
EXPECT_STREQ(convertedElem->FirstChildElement()->Attribute("name"), "L1");
convertedElem = convertedElem->NextSiblingElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "model");
EXPECT_STREQ(convertedElem->Attribute("name"), "A");
EXPECT_STREQ(convertedElem->FirstChildElement()->Name(), "model");
EXPECT_STREQ(convertedElem->FirstChildElement()->Attribute("name"), "B");
EXPECT_EQ(convertedElem->NextSiblingElement(), nullptr);
convertedElem = convertedElem->PreviousSiblingElement();
ASSERT_NE(convertedElem, nullptr);
convertedElem = convertedElem->PreviousSiblingElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "model");
EXPECT_STREQ(convertedElem->Attribute("name"), "C");
convertedElem = convertedElem->FirstChildElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "model");
EXPECT_STREQ(convertedElem->Attribute("name"), "D");
EXPECT_STREQ(convertedElem->FirstChildElement()->Name(), "link");
EXPECT_STREQ(convertedElem->FirstChildElement()->Attribute("name"), "E");
convertedElem = convertedElem->NextSiblingElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "model");
EXPECT_STREQ(convertedElem->Attribute("name"), "F");
convertedElem = convertedElem->FirstChildElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "model");
EXPECT_STREQ(convertedElem->Attribute("name"), "G");
EXPECT_EQ(convertedElem->NextSiblingElement(), nullptr);
convertedElem = convertedElem->FirstChildElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "link");
EXPECT_STREQ(convertedElem->Attribute("name"), "H");
EXPECT_EQ(convertedElem->NextSiblingElement(), nullptr);
convertedElem = convertedElem->FirstChildElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "visual");
EXPECT_STREQ(convertedElem->Attribute("name"), "v1");
EXPECT_EQ(convertedElem->NextSiblingElement(), nullptr);
convertedElem = convertedElem->FirstChildElement();
ASSERT_NE(convertedElem, nullptr);
EXPECT_STREQ(convertedElem->Name(), "pose");
EXPECT_STREQ(convertedElem->Attribute("relative_to"), "__model__");
EXPECT_STREQ(convertedElem->NextSiblingElement()->Name(), "geometry");
Expand Down
6 changes: 4 additions & 2 deletions test/integration/converter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -156,10 +156,9 @@ void ParserStringConverter(const std::string &_version)
TEST(ConverterIntegration, UnflattenConversion)
{
const std::string filename =
sdf::filesystem::append(PROJECT_SOURCE_PATH, "test", "sdf",
sdf::testing::SourceFile("test", "sdf",
"flattened_test_nested_model_with_frames.sdf");


sdf::SDFPtr sdf(new sdf::SDF());
sdf::init(sdf);

Expand Down Expand Up @@ -240,6 +239,7 @@ TEST(ConverterIntegration, UnflattenConversion)
ASSERT_NE(nullptr, jointElem);
EXPECT_EQ(jointElem->Get<std::string>("name"), "J1");
poseElem = jointElem->GetElement("pose");
ASSERT_NE(nullptr, poseElem);
EXPECT_EQ(poseElem->Get<std::string>("relative_to"), "L1");
EXPECT_EQ(jointElem->Get<std::string>("parent"), "L1");
EXPECT_EQ(jointElem->Get<std::string>("child"), "L2");
Expand All @@ -263,6 +263,7 @@ TEST(ConverterIntegration, UnflattenConversion)
ASSERT_NE(nullptr, jointElem);
EXPECT_EQ(jointElem->Get<std::string>("name"), "J3");
poseElem = jointElem->GetElement("pose");
ASSERT_NE(nullptr, poseElem);
EXPECT_EQ(poseElem->Get<std::string>("relative_to"), "__model__");
EXPECT_EQ(jointElem->Get<std::string>("parent"), "L3");
EXPECT_EQ(jointElem->Get<std::string>("child"), "L4");
Expand All @@ -271,5 +272,6 @@ TEST(ConverterIntegration, UnflattenConversion)
ASSERT_NE(nullptr, nestModelElem);
EXPECT_EQ(nestModelElem->Get<std::string>("name"), "M2");
poseElem = nestModelElem->GetElement("pose");
ASSERT_NE(nullptr, poseElem);
EXPECT_EQ(poseElem->Get<std::string>("relative_to"), "F1");
}

0 comments on commit 3e0cd5d

Please sign in to comment.