From b683fe7f345d983b0974fb0656cb4924e8042a6e Mon Sep 17 00:00:00 2001 From: Aditya Date: Tue, 22 Feb 2022 13:08:17 -0800 Subject: [PATCH] Changed delimiter, removed entity types from name, minor cleanup Signed-off-by: Aditya --- src/systems/physics/Physics.cc | 4 ++-- test/integration/contact_system.cc | 10 +++++----- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index 1d9d60da03..abf7ec416d 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -3260,10 +3260,10 @@ void PhysicsPrivate::UpdateCollisions(EntityComponentManager &_ecm) msgs::Contact *contactMsg = contactsComp.add_contact(); contactMsg->mutable_collision1()->set_id(_collEntity1); contactMsg->mutable_collision1()->set_name( - scopedName(_collEntity1, _ecm, ":", 1)); + removeParentScope(scopedName(_collEntity1, _ecm, "::", 0), "::")); contactMsg->mutable_collision2()->set_id(collEntity2); contactMsg->mutable_collision2()->set_name( - scopedName(collEntity2, _ecm, ":", 1)); + removeParentScope(scopedName(collEntity2, _ecm, "::", 0), "::")); for (const auto &contact : contactData) { auto *position = contactMsg->add_position(); diff --git a/test/integration/contact_system.cc b/test/integration/contact_system.cc index b09fd6fff2..7fdc88599a 100644 --- a/test/integration/contact_system.cc +++ b/test/integration/contact_system.cc @@ -100,12 +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 = + bool entityNameFound = contact.collision1().name() == - "world:contact_sensor:model:contact_model:link:link:collision:collision_sphere1" || - contact.collision1().name() == - "world:contact_sensor:model:contact_model:link:link:collision:collision_sphere2"; - EXPECT_TRUE(EntityNameFound); + "contact_model::link::collision_sphere1" || + contact.collision1().name() == + "contact_model::link::collision_sphere2"; + EXPECT_TRUE(entityNameFound); } }