Skip to content

Commit

Permalink
Added parameter to disable populating colliding entity names
Browse files Browse the repository at this point in the history
Signed-off-by: Aditya <[email protected]>
  • Loading branch information
adityapande-1995 committed Feb 24, 2022
1 parent b683fe7 commit e08983e
Show file tree
Hide file tree
Showing 4 changed files with 211 additions and 4 deletions.
27 changes: 23 additions & 4 deletions src/systems/physics/Physics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -686,6 +686,10 @@ class ignition::gazebo::systems::PhysicsPrivate
/// through the GUI model editor, so that we can avoid premature creation
/// of joints. This also lets us suppress some invalid error messages.
public: std::set<Entity> jointAddedToModel;

/// \brief Flag to store whether the names of colliding entities should
/// be populated in the contact points.
public: bool contactsEntityNames = true;
};

//////////////////////////////////////////////////
Expand Down Expand Up @@ -732,6 +736,18 @@ void Physics::Configure(const Entity &_entity,
[](const std::string &_a, const std::string &_b){return _a == _b;});
}

// Check if entity names should be populated in contact points.
if (_sdf->HasElement("contacts"))
{
auto sdfClone = _sdf->Clone();
auto contactsElement = sdfClone->GetElement("contacts");
if (contactsElement->HasElement("include_entity_names"))
{
this->dataPtr->contactsEntityNames = contactsElement->Get<bool>(
"include_entity_names");
}
}

// Find engine shared library
// Look in:
// * Paths from environment variable
Expand Down Expand Up @@ -3259,11 +3275,14 @@ void PhysicsPrivate::UpdateCollisions(EntityComponentManager &_ecm)
{
msgs::Contact *contactMsg = contactsComp.add_contact();
contactMsg->mutable_collision1()->set_id(_collEntity1);
contactMsg->mutable_collision1()->set_name(
removeParentScope(scopedName(_collEntity1, _ecm, "::", 0), "::"));
contactMsg->mutable_collision2()->set_id(collEntity2);
contactMsg->mutable_collision2()->set_name(
removeParentScope(scopedName(collEntity2, _ecm, "::", 0), "::"));
if (this->contactsEntityNames)
{
contactMsg->mutable_collision1()->set_name(
removeParentScope(scopedName(_collEntity1, _ecm, "::", 0), "::"));
contactMsg->mutable_collision2()->set_name(
removeParentScope(scopedName(collEntity2, _ecm, "::", 0), "::"));
}
for (const auto &contact : contactData)
{
auto *position = contactMsg->add_position();
Expand Down
76 changes: 76 additions & 0 deletions test/integration/contact_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,82 @@ class ContactSystemTest : public InternalFixture<::testing::Test>
{
};

/////////////////////////////////////////////////
// This test verifies that colliding entity names are not populated in
// the contact points message.
TEST_F(ContactSystemTest,
IGN_UTILS_TEST_DISABLED_ON_WIN32(DisableCollidingEntityNames))
{
// Start server
ServerConfig serverConfig;
const auto sdfFile = std::string(PROJECT_SOURCE_PATH) +
"/test/worlds/contact_without_entity_names.sdf";
serverConfig.SetSdfFile(sdfFile);

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

using namespace std::chrono_literals;
server.SetUpdatePeriod(1ns);

std::mutex contactMutex;
std::vector<msgs::Contacts> contactMsgs;

auto contactCb = [&](const msgs::Contacts &_msg) -> void
{
std::lock_guard<std::mutex> lock(contactMutex);
contactMsgs.push_back(_msg);
};

// subscribe to contacts topic
transport::Node node;
// Have to create an lvalue here for Node::Subscribe to work.
auto callbackFunc = std::function<void(const msgs::Contacts &)>(contactCb);
node.Subscribe("/test_multiple_collisions", callbackFunc);

// Run server
size_t iters = 1000;
server.Run(true, iters, false);
{
std::lock_guard<std::mutex> lock(contactMutex);
ASSERT_GE(contactMsgs.size(), 1u);
}

// "contact_model" has one contact sensor, but the sensor uses two collisions
// as sensors. Therefore, once the "contact_model" model has fallen and has
// stabilized, we expect that each collision will have 1 contact point.
{
std::lock_guard<std::mutex> lock(contactMutex);
const auto &lastContacts = contactMsgs.back();
EXPECT_EQ(4, lastContacts.contact_size());

for (const auto &contact : lastContacts.contact())
{
ASSERT_EQ(1, contact.position_size());
bool entityNameFound =
contact.collision1().name() ==
"contact_model::link::collision_sphere1" ||
contact.collision1().name() ==
"contact_model::link::collision_sphere2";
EXPECT_FALSE(entityNameFound);
}
}

// Remove the colliding boxes and check that contacts are no longer generated.
server.RequestRemoveEntity("box1");
server.RequestRemoveEntity("box2");
// Run once to remove entities
server.Run(true, 1, false);

contactMsgs.clear();
server.Run(true, 10, false);
{
std::lock_guard<std::mutex> lock(contactMutex);
EXPECT_EQ(0u, contactMsgs.size());
}
}

/////////////////////////////////////////////////
// The test checks that contacts are published by the contact system
// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175
Expand Down
3 changes: 3 additions & 0 deletions test/worlds/contact.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,9 @@
<plugin
filename="ignition-gazebo-physics-system"
name="ignition::gazebo::systems::Physics">
<contacts>
<include_entity_names>true</include_entity_names>
</contacts>
</plugin>
<plugin
filename="ignition-gazebo-contact-system"
Expand Down
109 changes: 109 additions & 0 deletions test/worlds/contact_without_entity_names.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,109 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="contact_sensor">
<physics name="fast" type="ignored">
<real_time_factor>0</real_time_factor>
</physics>

<plugin
filename="ignition-gazebo-physics-system"
name="ignition::gazebo::systems::Physics">
<contacts>
<include_entity_names>false</include_entity_names>
</contacts>
</plugin>
<plugin
filename="ignition-gazebo-contact-system"
name="ignition::gazebo::systems::Contact">
</plugin>

<model name="contact_model">
<pose>0 0 3.0 0 0.0 0</pose>
<link name="link">
<collision name="collision_sphere1">
<pose>0 1 0.0 0 0.0 0</pose>
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
</collision>
<collision name="collision_sphere2">
<pose>0 -1 0.0 0 0.0 0</pose>
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
</collision>
<visual name="visual_sphere1">
<pose>0 1 0.0 0 0.0 0</pose>
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
</visual>
<visual name="visual_sphere2">
<pose>0 -1 0.0 0 0.0 0</pose>
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
</visual>
<sensor name='sensor_contact' type='contact'>
<contact>
<collision>collision_sphere1</collision>
<collision>collision_sphere2</collision>
<topic>/test_multiple_collisions</topic>
</contact>
<always_on>1</always_on>
<update_rate>1000</update_rate>
</sensor>
</link>
</model>

<model name="box1">
<static>1</static>
<pose>-0.75 0 0.5 0 0 0</pose>
<link name="link">
<collision name="collision_box1_box">
<geometry>
<box>
<size>1 4 1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>1 4 1</size>
</box>
</geometry>
</visual>
</link>
</model>

<model name="box2">
<static>1</static>
<pose>0.75 0 0.5 0 0 0</pose>
<link name="link">
<collision name="collision_box2_box">
<geometry>
<box>
<size>1 4 1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>1 4 1</size>
</box>
</geometry>
</visual>
</link>
</model>
</world>
</sdf>

0 comments on commit e08983e

Please sign in to comment.