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

Populate names of colliding entities in contact points message #1351

Merged
merged 10 commits into from
Feb 28, 2022
4 changes: 4 additions & 0 deletions src/systems/physics/Physics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3259,7 +3259,11 @@ 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), "::"));
for (const auto &contact : contactData)
{
auto *position = contactMsg->add_position();
Expand Down
6 changes: 6 additions & 0 deletions test/integration/contact_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -100,6 +100,12 @@ TEST_F(ContactSystemTest,
EXPECT_NEAR(0.25, std::abs(contact.position(0).x()), 5e-2);
EXPECT_NEAR(1, std::abs(contact.position(0).y()), 5e-2);
EXPECT_NEAR(1, contact.position(0).z(), 5e-2);
bool entityNameFound =
contact.collision1().name() ==
"contact_model::link::collision_sphere1" ||
contact.collision1().name() ==
"contact_model::link::collision_sphere2";
EXPECT_TRUE(entityNameFound);
}
}

Expand Down