Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use updated model names for spawned models when generating SDFormat #166

Merged
merged 2 commits into from
Jun 1, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@

### Ignition Gazebo 2.XX.XX (20XX-XX-XX)

1. Use updated model names for spawned models when generating SDFormat
* [Pull Request 166](https://github.com/ignitionrobotics/ign-gazebo/pull/166)

1. Allow renaming breadcrumb models if there is a name conflict
* [Pull Request 155](https://github.com/ignitionrobotics/ign-gazebo/pull/155)

Expand Down
4 changes: 4 additions & 0 deletions src/SdfGenerator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -376,9 +376,13 @@ namespace sdf_generator

// Update sdf based current components. Here are the list of components to
// be updated:
// - Name
// - Pose
// This list is to be updated as other components become updateable during
// simulation
auto *nameComp = _ecm.Component<components::Name>(_entity);
_elem->GetAttribute("name")->Set(nameComp->Data());

auto *poseComp = _ecm.Component<components::Pose>(_entity);

auto poseElem = _elem->GetElement("pose");
Expand Down
75 changes: 64 additions & 11 deletions test/integration/save_world.cc
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,20 @@ class SdfGeneratorFixture : public ::testing::Test
this->server = std::make_unique<Server>(serverConfig);
EXPECT_FALSE(server->Running());
}
public: std::string RequestGeneratedSdf()
{
transport::Node node;
msgs::SdfGeneratorConfig req;

msgs::StringMsg worldGenSdfRes;
bool result;
unsigned int timeout = 5000;
std::string service{"/world/save_world/generate_world_sdf"};
EXPECT_TRUE(node.Request(service, req, timeout, worldGenSdfRes, result));
EXPECT_TRUE(result);
return worldGenSdfRes.data();
}

public: std::unique_ptr<Server> server;
};

Expand Down Expand Up @@ -116,24 +130,23 @@ TEST_F(SdfGeneratorFixture, WorldWithModelsSpawnedAfterLoad)
EXPECT_TRUE(this->server->EntityByName("spawned_model").has_value());
EXPECT_NE(kNullEntity, this->server->EntityByName("spawned_model"));

msgs::SdfGeneratorConfig req;

msgs::StringMsg worldGenSdfRes;
bool result;
unsigned int timeout = 5000;
std::string service{"/world/save_world/generate_world_sdf"};

EXPECT_TRUE(node.Request(service, req, timeout, worldGenSdfRes, result));
EXPECT_TRUE(result);
const std::string worldGenSdfRes = this->RequestGeneratedSdf();
sdf::Root root;
sdf::Errors err = root.LoadSdfString(worldGenSdfRes.data());
sdf::Errors err = root.LoadSdfString(worldGenSdfRes);
EXPECT_TRUE(err.empty());
auto *world = root.WorldByIndex(0);
ASSERT_NE(nullptr, world);
EXPECT_EQ(6u, world->ModelCount());

EXPECT_TRUE(world->ModelNameExists("inlineM1"));
EXPECT_TRUE(world->ModelNameExists("backpack1"));
EXPECT_TRUE(world->ModelNameExists("backpack2"));
EXPECT_TRUE(world->ModelNameExists("backpack3"));
EXPECT_TRUE(world->ModelNameExists("test_ground_plane"));
EXPECT_TRUE(world->ModelNameExists("spawned_model"));

tinyxml2::XMLDocument genSdfDoc;
genSdfDoc.Parse(worldGenSdfRes.data().c_str());
genSdfDoc.Parse(worldGenSdfRes.c_str());
ASSERT_NE(nullptr, genSdfDoc.RootElement());
auto genWorld = genSdfDoc.RootElement()->FirstChildElement("world");
ASSERT_NE(nullptr, genWorld);
Expand Down Expand Up @@ -180,3 +193,43 @@ TEST_F(SdfGeneratorFixture, WorldWithModelsSpawnedAfterLoad)
EXPECT_EQ(2u, modelCount);
EXPECT_EQ(1u, spawnedModelCount);
}

/////////////////////////////////////////////////
TEST_F(SdfGeneratorFixture, ModelSpawnedWithNewName)
{
this->LoadWorld("test/worlds/save_world.sdf");

auto modelStr = R"(
<?xml version="1.0" ?>
<sdf version='1.6'>
<model name='spawned_model'>
<link name='link'/>
</model>
</sdf>)";

transport::Node node;
msgs::EntityFactory req;
msgs::Boolean res;
bool result;
unsigned int timeout = 5000;
std::string service{"/world/save_world/create"};

req.set_sdf(modelStr);
req.set_name("new_model_name");

EXPECT_TRUE(node.Request(service, req, timeout, res, result));
EXPECT_TRUE(result);
EXPECT_TRUE(res.data());
// Run an iteration and check it was created
server->Run(true, 1, false);
EXPECT_TRUE(this->server->EntityByName("new_model_name").has_value());
EXPECT_NE(kNullEntity, this->server->EntityByName("new_model_name"));

const std::string worldGenSdfRes = this->RequestGeneratedSdf();
sdf::Root root;
sdf::Errors err = root.LoadSdfString(worldGenSdfRes);
EXPECT_TRUE(err.empty());
auto *world = root.WorldByIndex(0);
ASSERT_NE(nullptr, world);
EXPECT_TRUE(world->ModelNameExists("new_model_name"));
}