From fb32a0c61f7bdee87e87fb427112fea8e6a927b0 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Mon, 20 Jun 2022 12:06:41 -0700 Subject: [PATCH] Use new Joint APIs for Parent/Child name Follow-up to gazebosim/sdformat#1053. Signed-off-by: Steve Peters --- src/EntityComponentManager_TEST.cc | 4 ++-- src/SdfEntityCreator.cc | 12 ++++++------ src/SdfEntityCreator_TEST.cc | 4 ++-- src/SimulationRunner_TEST.cc | 4 ++-- .../component_inspector_editor/ModelEditor.cc | 4 ++-- .../VisualizationCapabilities.cc | 12 ++++++------ src/rendering/RenderUtil.cc | 12 ++++++------ src/systems/physics/Physics.cc | 4 ++-- src/systems/wheel_slip/WheelSlip.cc | 2 +- test/integration/components.cc | 12 ++++++------ test/integration/save_world.cc | 4 ++-- 11 files changed, 37 insertions(+), 37 deletions(-) diff --git a/src/EntityComponentManager_TEST.cc b/src/EntityComponentManager_TEST.cc index e31b35eab9..064225335d 100644 --- a/src/EntityComponentManager_TEST.cc +++ b/src/EntityComponentManager_TEST.cc @@ -2874,9 +2874,9 @@ TEST_P(EntityComponentManagerFixture, manager.CreateComponent(jointEntity, components::Name("jointEntity")); manager.CreateComponent(jointEntity, components::Joint()); manager.CreateComponent(jointEntity, - components::ParentLinkName(parentLinkEntityName)); + components::ParentName(parentLinkEntityName)); manager.CreateComponent(jointEntity, - components::ChildLinkName(childLinkEntityName)); + components::ChildName(childLinkEntityName)); Entity childLinkEntity = manager.CreateEntity(); manager.CreateComponent(childLinkEntity, components::ParentEntity(parentModelEntity)); diff --git a/src/SdfEntityCreator.cc b/src/SdfEntityCreator.cc index aa9a102579..69ded133fe 100644 --- a/src/SdfEntityCreator.cc +++ b/src/SdfEntityCreator.cc @@ -658,7 +658,7 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Joint *_joint, std::string resolvedParentLinkName; if (_resolved) { - resolvedParentLinkName = _joint->ParentLinkName(); + resolvedParentLinkName = _joint->ParentName(); } else { @@ -668,7 +668,7 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Joint *_joint, if (!resolveParentErrors.empty()) { gzerr << "Failed to resolve parent link for joint '" << _joint->Name() - << "' with parent name '" << _joint->ParentLinkName() << "'" + << "' with parent name '" << _joint->ParentName() << "'" << std::endl; for (const auto &error : resolveParentErrors) { @@ -679,12 +679,12 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Joint *_joint, } } this->dataPtr->ecm->CreateComponent( - jointEntity, components::ParentLinkName(resolvedParentLinkName)); + jointEntity, components::ParentName(resolvedParentLinkName)); std::string resolvedChildLinkName; if (_resolved) { - resolvedChildLinkName = _joint->ChildLinkName(); + resolvedChildLinkName = _joint->ChildName(); } else { @@ -693,7 +693,7 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Joint *_joint, if (!resolveChildErrors.empty()) { gzerr << "Failed to resolve child link for joint '" << _joint->Name() - << "' with child name '" << _joint->ChildLinkName() << "'" + << "' with child name '" << _joint->ChildName() << "'" << std::endl; for (const auto &error : resolveChildErrors) { @@ -705,7 +705,7 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Joint *_joint, } this->dataPtr->ecm->CreateComponent( - jointEntity, components::ChildLinkName(resolvedChildLinkName)); + jointEntity, components::ChildName(resolvedChildLinkName)); return jointEntity; } diff --git a/src/SdfEntityCreator_TEST.cc b/src/SdfEntityCreator_TEST.cc index 414175f998..6ed123c82f 100644 --- a/src/SdfEntityCreator_TEST.cc +++ b/src/SdfEntityCreator_TEST.cc @@ -1031,8 +1031,8 @@ TEST_F(SdfEntityCreatorTest, CreateJointEntities) if (_checkAxis2) testAxis(_joint->Name(), _joint->Axis(1), _axis2); - EXPECT_EQ(_joint->ParentLinkName(), _parentLinkName->Data()); - EXPECT_EQ(_joint->ChildLinkName(), _childLinkName->Data()); + EXPECT_EQ(_joint->ParentName(), _parentLinkName->Data()); + EXPECT_EQ(_joint->ChildName(), _childLinkName->Data()); EXPECT_EQ(_joint->Name(), _name->Data()); }; diff --git a/src/SimulationRunner_TEST.cc b/src/SimulationRunner_TEST.cc index bc8106de3d..5cd44ad6c1 100644 --- a/src/SimulationRunner_TEST.cc +++ b/src/SimulationRunner_TEST.cc @@ -994,8 +994,8 @@ TEST_P(SimulationRunnerTest, CreateJointEntities) if (_checkAxis2) testAxis(_joint->Name(), _joint->Axis(1), _axis2); - EXPECT_EQ(_joint->ParentLinkName(), _parentLinkName->Data()); - EXPECT_EQ(_joint->ChildLinkName(), _childLinkName->Data()); + EXPECT_EQ(_joint->ParentName(), _parentLinkName->Data()); + EXPECT_EQ(_joint->ChildName(), _childLinkName->Data()); EXPECT_EQ(_joint->Name(), _name->Data()); }; diff --git a/src/gui/plugins/component_inspector_editor/ModelEditor.cc b/src/gui/plugins/component_inspector_editor/ModelEditor.cc index f018dfa737..a838054b80 100644 --- a/src/gui/plugins/component_inspector_editor/ModelEditor.cc +++ b/src/gui/plugins/component_inspector_editor/ModelEditor.cc @@ -506,8 +506,8 @@ std::optional ModelEditorPrivate::CreateJoint( return std::nullopt; } - joint.SetParentLinkName(_eta.data.at("parent_link")); - joint.SetChildLinkName(_eta.data.at("child_link")); + joint.SetParentName(_eta.data.at("parent_link")); + joint.SetChildName(_eta.data.at("child_link")); std::string jointName = "joint"; Entity jointEnt = _ecm.EntityByComponents( diff --git a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc index 936da55244..f6bdc36f36 100644 --- a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc +++ b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc @@ -656,12 +656,12 @@ void VisualizationCapabilitiesPrivate::OnRender() !this->viewingInertias[jointEntity]) { std::string childLinkName = - this->entityJoints[jointEntity].ChildLinkName(); + this->entityJoints[jointEntity].ChildName(); Entity childId = this->matchLinksWithEntities[model][childLinkName]; std::string parentLinkName = - this->entityJoints[jointEntity].ParentLinkName(); + this->entityJoints[jointEntity].ParentName(); Entity parentId = this->matchLinksWithEntities[model][parentLinkName]; @@ -2547,8 +2547,8 @@ void VisualizationCapabilities::Update(const UpdateInfo &, joint.SetType(_jointType->Data()); joint.SetRawPose(_pose->Data()); - joint.SetParentLinkName(_parentLinkName->Data()); - joint.SetChildLinkName(_childLinkName->Data()); + joint.SetParentName(_parentLinkName->Data()); + joint.SetChildName(_childLinkName->Data()); auto jointAxis = _ecm.Component(_entity); auto jointAxis2 = _ecm.Component(_entity); @@ -2708,8 +2708,8 @@ void VisualizationCapabilities::Update(const UpdateInfo &, joint.SetType(_jointType->Data()); joint.SetRawPose(_pose->Data()); - joint.SetParentLinkName(_parentLinkName->Data()); - joint.SetChildLinkName(_childLinkName->Data()); + joint.SetParentName(_parentLinkName->Data()); + joint.SetChildName(_childLinkName->Data()); auto jointAxis = _ecm.Component(_entity); auto jointAxis2 = _ecm.Component(_entity); diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 9224642273..fc8e0b268f 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -1426,12 +1426,12 @@ void RenderUtil::Update() if (!this->dataPtr->sceneManager.HasEntity(jointEntity)) { std::string childLinkName = - this->dataPtr->entityJoints[jointEntity].ChildLinkName(); + this->dataPtr->entityJoints[jointEntity].ChildName(); Entity childId = this->dataPtr->matchLinksWithEntities[model][childLinkName]; std::string parentLinkName = - this->dataPtr->entityJoints[jointEntity].ParentLinkName(); + this->dataPtr->entityJoints[jointEntity].ParentName(); Entity parentId = this->dataPtr->matchLinksWithEntities[model][parentLinkName]; @@ -1789,8 +1789,8 @@ void RenderUtilPrivate::CreateEntitiesFirstUpdate( joint.SetType(_jointType->Data()); joint.SetRawPose(_pose->Data()); - joint.SetParentLinkName(_parentLinkName->Data()); - joint.SetChildLinkName(_childLinkName->Data()); + joint.SetParentName(_parentLinkName->Data()); + joint.SetChildName(_childLinkName->Data()); auto jointAxis = _ecm.Component(_entity); auto jointAxis2 = _ecm.Component(_entity); @@ -2055,8 +2055,8 @@ void RenderUtilPrivate::CreateEntitiesRuntime( joint.SetType(_jointType->Data()); joint.SetRawPose(_pose->Data()); - joint.SetParentLinkName(_parentLinkName->Data()); - joint.SetChildLinkName(_childLinkName->Data()); + joint.SetParentName(_parentLinkName->Data()); + joint.SetChildName(_childLinkName->Data()); auto jointAxis = _ecm.Component(_entity); auto jointAxis2 = _ecm.Component(_entity); diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index 414e4c0c29..87c0ad0688 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -1575,8 +1575,8 @@ void PhysicsPrivate::CreateJointEntities(const EntityComponentManager &_ecm, joint.SetRawPose(_pose->Data()); joint.SetThreadPitch(_threadPitch->Data()); - joint.SetParentLinkName(_parentLinkName->Data()); - joint.SetChildLinkName(_childLinkName->Data()); + joint.SetParentName(_parentLinkName->Data()); + joint.SetChildName(_childLinkName->Data()); auto jointAxis = _ecm.Component(_entity); auto jointAxis2 = _ecm.Component(_entity); diff --git a/src/systems/wheel_slip/WheelSlip.cc b/src/systems/wheel_slip/WheelSlip.cc index fcd3ef8562..be2e2161f2 100644 --- a/src/systems/wheel_slip/WheelSlip.cc +++ b/src/systems/wheel_slip/WheelSlip.cc @@ -197,7 +197,7 @@ bool WheelSlipPrivate::Load(const EntityComponentManager &_ecm, auto joints = _ecm.ChildrenByComponents(model.Entity(), components::Joint(), - components::ChildLinkName(linkName)); + components::ChildName(linkName)); if (joints.empty() || joints.size() != 1) { gzerr << "There should be 1 parent joint for link named [" << linkName diff --git a/test/integration/components.cc b/test/integration/components.cc index 4712e5cbfb..856bece963 100644 --- a/test/integration/components.cc +++ b/test/integration/components.cc @@ -337,9 +337,9 @@ TEST_F(ComponentsTest, CanonicalLink) TEST_F(ComponentsTest, ChildLinkName) { // Create components - auto comp11 = components::ChildLinkName("comp1"); - auto comp12 = components::ChildLinkName("comp1"); - auto comp2 = components::ChildLinkName("comp2"); + auto comp11 = components::ChildName("comp1"); + auto comp12 = components::ChildName("comp1"); + auto comp2 = components::ChildName("comp2"); // Equality operators EXPECT_EQ(comp11, comp12); @@ -1349,9 +1349,9 @@ TEST_F(ComponentsTest, ParentEntity) TEST_F(ComponentsTest, ParentLinkName) { // Create components - auto comp11 = components::ParentLinkName("comp1"); - auto comp12 = components::ParentLinkName("comp1"); - auto comp2 = components::ParentLinkName("comp2"); + auto comp11 = components::ParentName("comp1"); + auto comp12 = components::ParentName("comp1"); + auto comp2 = components::ParentName("comp2"); // Equality operators EXPECT_EQ(comp11, comp12); diff --git a/test/integration/save_world.cc b/test/integration/save_world.cc index e3280316cc..ffe7759626 100644 --- a/test/integration/save_world.cc +++ b/test/integration/save_world.cc @@ -887,8 +887,8 @@ TEST_F(SdfGeneratorFixture, ModelWithJoints) auto *joint = model->JointByName("joint"); ASSERT_NE(nullptr, joint); - EXPECT_EQ("link1", joint->ParentLinkName()); - EXPECT_EQ("link2", joint->ChildLinkName()); + EXPECT_EQ("link1", joint->ParentName()); + EXPECT_EQ("link2", joint->ChildName()); EXPECT_EQ(sdf::JointType::REVOLUTE2, joint->Type()); // Get the first axis