Skip to content

Send state message when components are removed #1235

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

Merged
merged 5 commits into from
Dec 8, 2021
Merged
Show file tree
Hide file tree
Changes from 4 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
4 changes: 4 additions & 0 deletions include/ignition/gazebo/EntityComponentManager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -669,6 +669,10 @@ namespace ignition
/// \param[in] _offset Offset value.
public: void SetEntityCreateOffset(uint64_t _offset);

/// \brief Return true if there are components marked for removal.
/// \return True if there are components marked for removal.
public: bool HasRemovedComponents() const;

/// \brief Clear the list of newly added entities so that a call to
/// EachAdded after this will have no entities to iterate. This function
/// is protected to facilitate testing.
Expand Down
7 changes: 7 additions & 0 deletions src/EntityComponentManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -557,6 +557,13 @@ void EntityComponentManager::ClearNewlyCreatedEntities()
}
}

/////////////////////////////////////////////////
bool EntityComponentManager::HasRemovedComponents() const
{
std::lock_guard<std::mutex> lock(this->dataPtr->removedComponentsMutex);
return !this->dataPtr->removedComponents.empty();
}

/////////////////////////////////////////////////
void EntityComponentManager::ClearRemovedComponents()
{
Expand Down
2 changes: 2 additions & 0 deletions src/EntityComponentManager_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -125,6 +125,7 @@ TEST_P(EntityComponentManagerFixture, InvalidComponentType)
EXPECT_EQ(2u, manager.CreateEntity());
EXPECT_TRUE(manager.HasEntity(2));
EXPECT_FALSE(manager.RemoveComponent(2, IntComponent::typeId));
EXPECT_FALSE(manager.HasRemovedComponents());

// We should get a nullptr if the component type doesn't exist.
EXPECT_TRUE(manager.HasEntity(1u));
Expand Down Expand Up @@ -182,6 +183,7 @@ TEST_P(EntityComponentManagerFixture, RemoveComponent)
EXPECT_FALSE(manager.EntityHasComponentType(eInt, IntComponent::typeId));
EXPECT_TRUE(manager.ComponentTypes(eInt).empty());
EXPECT_EQ(nullptr, manager.Component<IntComponent>(eInt));
EXPECT_TRUE(manager.HasRemovedComponents());

EXPECT_TRUE(manager.RemoveComponent(eDouble, DoubleComponent::typeId));
EXPECT_FALSE(manager.EntityHasComponentType(eDouble,
Expand Down
2 changes: 1 addition & 1 deletion src/systems/scene_broadcaster/SceneBroadcaster.cc
Original file line number Diff line number Diff line change
Expand Up @@ -284,7 +284,7 @@ void SceneBroadcaster::PostUpdate(const UpdateInfo &_info,
bool jumpBackInTime = _info.dt < std::chrono::steady_clock::duration::zero();
bool changeEvent = _manager.HasEntitiesMarkedForRemoval() ||
_manager.HasNewEntities() || _manager.HasOneTimeComponentChanges() ||
jumpBackInTime;
jumpBackInTime || _manager.HasRemovedComponents();
auto now = std::chrono::system_clock::now();
bool itsPubTime = !_info.paused && (now - this->dataPtr->lastStatePubTime >
this->dataPtr->statePublishPeriod);
Expand Down
125 changes: 125 additions & 0 deletions test/integration/scene_broadcaster_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,12 +22,16 @@

#include <ignition/common/Console.hh>
#include <ignition/common/Util.hh>
#include "ignition/gazebo/components/Model.hh"
#include "ignition/gazebo/components/Name.hh"
#include "ignition/gazebo/components/Pose.hh"
#include <ignition/transport/Node.hh>

#include "ignition/gazebo/Server.hh"
#include "ignition/gazebo/test_config.hh"

#include "../helpers/EnvTestFixture.hh"
#include "../helpers/Relay.hh"

using namespace ignition;

Expand Down Expand Up @@ -612,6 +616,127 @@ TEST_P(SceneBroadcasterTest, StateStatic)
EXPECT_TRUE(received);
}

/////////////////////////////////////////////////
/// Test whether the scene topic is published when a component is removed.
TEST_P(SceneBroadcasterTest, RemovedComponent)
{
// Start server
ignition::gazebo::ServerConfig serverConfig;
serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) +
"/test/worlds/shapes.sdf");

gazebo::Server server(serverConfig);
EXPECT_FALSE(server.Running());
EXPECT_FALSE(*server.Running(0));

// Create a system that removes a component
ignition::gazebo::test::Relay testSystem;

testSystem.OnUpdate([](const gazebo::UpdateInfo &_info,
gazebo::EntityComponentManager &_ecm)
{
if (_info.iterations > 1)
{
_ecm.Each<ignition::gazebo::components::Model,
ignition::gazebo::components::Name,
ignition::gazebo::components::Pose>(
[&](const ignition::gazebo::Entity &_entity,
const ignition::gazebo::components::Model *,
const ignition::gazebo::components::Name *_name,
const ignition::gazebo::components::Pose *)->bool
{
if (_name->Data() == "box")
{
_ecm.RemoveComponent<ignition::gazebo::components::Pose>(_entity);
}
return true;
});
}
});
server.AddSystem(testSystem.systemPtr);

bool received = false;
bool hasState = false;
std::function<void(const msgs::SerializedStepMap &)> cb =
[&](const msgs::SerializedStepMap &_res)
{
hasState = _res.has_state();
// Check the received state.
if (hasState)
{
ignition::gazebo::EntityComponentManager localEcm;
localEcm.SetState(_res.state());
bool hasBox = false;
localEcm.Each<ignition::gazebo::components::Model,
ignition::gazebo::components::Name>(
[&](const ignition::gazebo::Entity &_entity,
const ignition::gazebo::components::Model *,
const ignition::gazebo::components::Name *_name)->bool
{
if (_name->Data() == "box")
{
hasBox = true;
if (_res.stats().iterations() > 1)
{
// The pose component should be gone
EXPECT_FALSE(localEcm.EntityHasComponentType(
_entity, ignition::gazebo::components::Pose::typeId));
}
else
{
// The pose component should exist
EXPECT_TRUE(localEcm.EntityHasComponentType(
_entity, ignition::gazebo::components::Pose::typeId));
}
}
return true;
});
EXPECT_TRUE(hasBox);
}
received = true;
};

transport::Node node;
EXPECT_TRUE(node.Subscribe("/world/default/state", cb));

unsigned int sleep = 0u;
unsigned int maxSleep = 30u;

// Run server once. The first time should send the state message
server.RunOnce(true);
// cppcheck-suppress unmatchedSuppression
// cppcheck-suppress knownConditionTrueFalse
while (!received && sleep++ < maxSleep)
IGN_SLEEP_MS(100);
EXPECT_TRUE(received);
EXPECT_TRUE(hasState);

// Run server again. The second time shouldn't send the state message.
sleep = 0u;
received = false;
hasState = false;
server.RunOnce(true);
// cppcheck-suppress unmatchedSuppression
// cppcheck-suppress knownConditionTrueFalse
while (!received && sleep++ < maxSleep)
IGN_SLEEP_MS(100);
EXPECT_FALSE(received);
EXPECT_FALSE(hasState);

// Run server again. The third time should send the state message because
// the test system removed a component.
sleep = 0u;
received = false;
hasState = false;
server.RunOnce(true);
// cppcheck-suppress unmatchedSuppression
// cppcheck-suppress knownConditionTrueFalse
while (!received && sleep++ < maxSleep)
IGN_SLEEP_MS(100);
EXPECT_TRUE(received);
EXPECT_TRUE(hasState);
}

// Run multiple times
INSTANTIATE_TEST_SUITE_P(ServerRepeat, SceneBroadcasterTest,
::testing::Range(1, 2));