Skip to content

Commit

Permalink
Fix segfault in the Breadcrumb system when associated model is unload…
Browse files Browse the repository at this point in the history
…ed (#454)

The segfault occurs when a model containing a Breadcrumbs system gets
unloaded by the level manager. Since systems don't get unloaded, the
Breadcrumbs system continues to operate assuming that the model it is
associated with is valid.

Signed-off-by: Addisu Z. Taddese <[email protected]>
  • Loading branch information
azeey authored Nov 11, 2020
1 parent 65fd2dc commit 327cde7
Show file tree
Hide file tree
Showing 3 changed files with 255 additions and 0 deletions.
15 changes: 15 additions & 0 deletions src/systems/breadcrumbs/Breadcrumbs.cc
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,12 @@ void Breadcrumbs::Configure(const Entity &_entity,
_sdf->Get<bool>("allow_renaming", this->allowRenaming).first;

this->model = Model(_entity);
if (!this->model.Valid(_ecm))
{
ignerr << "The Breadcrumbs system should be attached to a model entity. "
<< "Failed to initialize." << std::endl;
return;
}

if (!_sdf->HasElement("breadcrumb"))
{
Expand Down Expand Up @@ -160,6 +166,15 @@ void Breadcrumbs::PreUpdate(const ignition::gazebo::UpdateInfo &_info,
std::back_inserter(cmds));
this->pendingCmds.clear();
}
// Check that the model is valid before continuing. This check is needed
// because the model associated with the Breadcrumbs might have been
// unloaded by the level manager. Ideally, this system would have been
// unloaded along with the model, but that is not currently the case. See
// issue #113
if (!this->model.Valid(_ecm))
{
return;
}

auto poseComp = _ecm.Component<components::Pose>(this->model.Entity());

Expand Down
120 changes: 120 additions & 0 deletions test/integration/breadcrumbs.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,15 @@
#include <ignition/msgs/empty.pb.h>
#include <ignition/msgs/twist.pb.h>

#include <regex>

#include <sdf/Root.hh>
#include <sdf/World.hh>

#include <ignition/common/Console.hh>
#include <ignition/transport/Node.hh>

#include "ignition/gazebo/Entity.hh"
#include "ignition/gazebo/Server.hh"
#include "ignition/gazebo/SystemLoader.hh"
#include "ignition/gazebo/components/Name.hh"
Expand Down Expand Up @@ -547,6 +550,123 @@ TEST_F(BreadcrumbsTest, AllowRenaming)
EXPECT_TRUE(this->server->HasEntity("B1_0_1"));
}

/////////////////////////////////////////////////
/// Return a list of model entities whose names match the given regex
std::vector<Entity> ModelsByNameRegex(
const gazebo::EntityComponentManager &_ecm, const std::regex &_re)
{
std::vector<Entity> entities;
_ecm.Each<components::Model, components::Name>(
[&](const Entity _entity, const components::Model *,
const components::Name *_name)
{
if (std::regex_match(_name->Data(), _re))
{
entities.push_back(_entity);
}
return true;
});

return entities;
}

// The test checks that models containing Breadcrumbs can be unloaded and loaded
// safely
TEST_F(BreadcrumbsTest, LevelLoadUnload)
{
// Start server
this->LoadWorld("test/worlds/breadcrumbs_levels.sdf", true);

test::Relay testSystem;
transport::Node node;
auto deploy =
node.Advertise<msgs::Empty>("/model/tile_1/breadcrumbs/B1/deploy");

const std::size_t iterTestStart = 1000;
const std::size_t nIters = iterTestStart + 10000;

std::regex reTile1{"tile_1"};
std::regex reBreadcrumb{"B1_.*"};
testSystem.OnPostUpdate(
[&](const gazebo::UpdateInfo &_info,
const gazebo::EntityComponentManager &_ecm)
{
// Ensure that tile_1 is loaded at the start, deploy a breadcrumb
if (_info.iterations == iterTestStart)
{
auto tiles = ModelsByNameRegex(_ecm, reTile1);
EXPECT_EQ(1u, tiles.size());
EXPECT_TRUE(deploy.Publish(msgs::Empty()));
}
// Check if the breadcrumb has been deployed
else if (_info.iterations == iterTestStart + 1000)
{
auto breadcrumbs = ModelsByNameRegex(_ecm, reBreadcrumb);
EXPECT_EQ(1u, breadcrumbs.size());
}
// Move the performer (sphere) outside the level. This should cause
// tile_1 to be unloaded
else if (_info.iterations == iterTestStart + 1001)
{
msgs::Pose req;
req.set_name("sphere");
req.mutable_position()->set_x(30);
msgs::Boolean rep;
bool result;
node.Request("/world/breadcrumbs_levels/set_pose", req, 1000, rep,
result);
EXPECT_TRUE(result);
}
// Check that tile_1 is unloaded, then try deploying breadcrumb. This
// should fail because the model associated with the breadcrumb system
// is unloaded.
else if (_info.iterations == iterTestStart + 2000)
{
auto tiles = ModelsByNameRegex(_ecm, reTile1);
EXPECT_EQ(0u, tiles.size());
EXPECT_TRUE(deploy.Publish(msgs::Empty()));
}
// Check that no new breadcrumbs have been deployed
else if (_info.iterations == iterTestStart + 3000)
{
auto breadcrumbs = ModelsByNameRegex(_ecm, reBreadcrumb);
EXPECT_EQ(1u, breadcrumbs.size());
}
// Move the performer (sphere) back into the level. This should load
// tile_1 and a new Breadcrumbs system.
else if (_info.iterations == iterTestStart + 3001)
{
msgs::Pose req;
req.set_name("sphere");
req.mutable_position()->set_x(0);
msgs::Boolean rep;
bool result;
node.Request("/world/breadcrumbs_levels/set_pose", req, 1000, rep,
result);
EXPECT_TRUE(result);
}
// Check that tile_1 is loaded, then try deploying breadcrumb.
else if (_info.iterations == iterTestStart + 4000)
{
auto tiles = ModelsByNameRegex(_ecm, reTile1);
EXPECT_EQ(1u, tiles.size());
EXPECT_TRUE(deploy.Publish(msgs::Empty()));
}
// Check that only one additional breadcrumb has been deployed even
// though there are two Breadcrumbs systems associated with the model.
// The original Breadcrumbs system should now be invalid because the
// model gets a new Entity ID.
else if (_info.iterations == iterTestStart + 5000)
{
auto breadcrumbs = ModelsByNameRegex(_ecm, reBreadcrumb);
EXPECT_EQ(2u, breadcrumbs.size());
}
});

this->server->AddSystem(testSystem.systemPtr);
this->server->Run(true, nIters, false);
}

/////////////////////////////////////////////////
/// Main
int main(int _argc, char **_argv)
Expand Down
120 changes: 120 additions & 0 deletions test/worlds/breadcrumbs_levels.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,120 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="breadcrumbs_levels">

<physics name="1ms" type="ode">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="libignition-gazebo-physics-system.so"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="libignition-gazebo-user-commands-system.so"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin
filename="libignition-gazebo-scene-broadcaster-system.so"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>

<model name="tile_1">
<pose>0 0 0.1 0 0 0</pose>
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>10 10 0.2</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>10 10 0.2</size>
</box>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.0 0.8 0.0 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
<plugin filename="libignition-gazebo-breadcrumbs-system.so" name="ignition::gazebo::systems::Breadcrumbs">
<max_deployments>3</max_deployments>
<disable_physics_time>15</disable_physics_time>
<allow_renaming>true</allow_renaming>
<breadcrumb>
<sdf version="1.6">
<model name="B1">
<pose>0 0 5 0 0 0</pose>
<link name='body'>
<visual name='visual'>
<geometry>
<box>
<size>0.3 0.3 0.5</size>
</box>
</geometry>
</visual>
<collision name='collision'>
<geometry>
<box>
<size>0.3 0.3 0.5</size>
</box>
</geometry>
</collision>
</link>
</model>
</sdf>
</breadcrumb>
</plugin>
</model>

<model name="sphere">
<pose>0 0 2 0 0 0</pose>
<static>true</static>
<link name="sphere_link">
<collision name="sphere_collision">
<geometry>
<sphere>
<radius>1.0</radius>
</sphere>
</geometry>
</collision>
<visual name="sphere_visual">
<geometry>
<sphere>
<radius>1.0</radius>
</sphere>
</geometry>
</visual>
</link>
</model>

<plugin name="ignition::gazebo" filename="dummy">
<performer name="perf1">
<ref>sphere</ref>
<geometry>
<box>
<size>4 4 2</size>
</box>
</geometry>
</performer>
<level name="level1">
<pose>0 0 2.5 0 0 0</pose>
<geometry>
<box>
<size>10 10 10</size>
</box>
</geometry>
<buffer>2</buffer>
<ref>tile_1</ref>
</level>
</plugin>
</world>
</sdf>


0 comments on commit 327cde7

Please sign in to comment.