From bff502f7b81562d8b8e9620150ebca52cdd7b9d1 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Wed, 29 Dec 2021 11:06:23 -0800 Subject: [PATCH] sdf_custom: fix nested model expectations (#807) Account for new behavior of nested models and :: syntax. Signed-off-by: Steve Peters --- test/integration/sdf_custom.cc | 40 ++++++++++++++++++++-------------- 1 file changed, 24 insertions(+), 16 deletions(-) diff --git a/test/integration/sdf_custom.cc b/test/integration/sdf_custom.cc index 9f3ad54ab..9f4a378cd 100644 --- a/test/integration/sdf_custom.cc +++ b/test/integration/sdf_custom.cc @@ -293,45 +293,53 @@ R"( ASSERT_NE(nullptr, world2); // //model[@name=test] - const sdf::Model *model11 = world1->ModelByIndex(0); - const sdf::Model *model12 = world2->ModelByIndex(0); + const sdf::Model *model01 = world1->ModelByIndex(0); + const sdf::Model *model02 = world2->ModelByIndex(0); + ASSERT_NE(nullptr, model01); + ASSERT_NE(nullptr, model02); + EXPECT_EQ("test", model01->Name()); + EXPECT_EQ("test", model02->Name()); + EXPECT_EQ(model01->Element()->ToString(""), model02->Element()->ToString("")); + + // //model[@name=test]/model[@name=M1] + const sdf::Model *model11 = model01->ModelByIndex(0); + const sdf::Model *model12 = model02->ModelByIndex(0); ASSERT_NE(nullptr, model11); ASSERT_NE(nullptr, model12); + EXPECT_EQ("M1", model11->Name()); + EXPECT_EQ("M1", model12->Name()); EXPECT_EQ(model11->Element()->ToString(""), model12->Element()->ToString("")); - // //model[@name=test]/frame[@name=M1::__model__] - const sdf::Frame *frame1 = model11->FrameByIndex(0); - const sdf::Frame *frame2 = model12->FrameByIndex(0); - ASSERT_NE(nullptr, frame1); - ASSERT_NE(nullptr, frame2); - EXPECT_EQ(frame1->Element()->ToString(""), frame2->Element()->ToString("")); - - // //model[@name=test]/link[@name=M1::L1] + // //model[@name=test]/model[@name=M1]/link[@name=L1] const sdf::Link *model11link1 = model11->LinkByIndex(0); const sdf::Link *model12link2 = model12->LinkByIndex(0); ASSERT_NE(nullptr, model11link1); ASSERT_NE(nullptr, model12link2); + EXPECT_EQ("L1", model11link1->Name()); + EXPECT_EQ("L1", model12link2->Name()); const std::string linkCustomAttrStr = -R"( - 0 0 0 0 -0 0 - +R"( )"; EXPECT_EQ(linkCustomAttrStr, model11link1->Element()->ToString("")); EXPECT_EQ(linkCustomAttrStr, model12link2->Element()->ToString("")); - // //model[@name=test]/model[@name=M1::M2] + // //model[@name=test]/model[@name=M1]/model[@name=M2] const sdf::Model *model21 = model11->ModelByIndex(0); const sdf::Model *model22 = model12->ModelByIndex(0); ASSERT_NE(nullptr, model21); ASSERT_NE(nullptr, model22); + EXPECT_EQ("M2", model21->Name()); + EXPECT_EQ("M2", model22->Name()); EXPECT_EQ(model21->Element()->ToString(""), model22->Element()->ToString("")); - // //model[@name=test]/model[@name=M1::M2]/link[@name=M1::L1] + // //model[@name=test]/model[@name=M1]/model[@name=M2]/link[@name=L1] const sdf::Link *model21link1 = model21->LinkByIndex(0); const sdf::Link *model22link2 = model22->LinkByIndex(0); ASSERT_NE(nullptr, model21link1); ASSERT_NE(nullptr, model22link2); + EXPECT_EQ("L1", model21link1->Name()); + EXPECT_EQ("L1", model22link2->Name()); EXPECT_EQ(model21link1->Element()->ToString(""), model22link2->Element()->ToString("")); @@ -357,7 +365,7 @@ R"( const std::string customElemStr = R"( transmission_interface/SimpleTransmission - + EffortJointInterface