Skip to content

Commit

Permalink
Use new Joint APIs for Parent/Child name (#1548)
Browse files Browse the repository at this point in the history
Follow-up to gazebosim/sdformat#1053.

Signed-off-by: Steve Peters <[email protected]>
  • Loading branch information
scpeters authored Jun 21, 2022
1 parent 171e486 commit 136c840
Show file tree
Hide file tree
Showing 8 changed files with 26 additions and 26 deletions.
8 changes: 4 additions & 4 deletions src/SdfEntityCreator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -658,7 +658,7 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Joint *_joint,
std::string resolvedParentLinkName;
if (_resolved)
{
resolvedParentLinkName = _joint->ParentLinkName();
resolvedParentLinkName = _joint->ParentName();
}
else
{
Expand All @@ -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)
{
Expand All @@ -684,7 +684,7 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Joint *_joint,
std::string resolvedChildLinkName;
if (_resolved)
{
resolvedChildLinkName = _joint->ChildLinkName();
resolvedChildLinkName = _joint->ChildName();
}
else
{
Expand All @@ -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)
{
Expand Down
4 changes: 2 additions & 2 deletions src/SdfEntityCreator_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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());
};

Expand Down
4 changes: 2 additions & 2 deletions src/SimulationRunner_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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());
};

Expand Down
4 changes: 2 additions & 2 deletions src/gui/plugins/component_inspector_editor/ModelEditor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -506,8 +506,8 @@ std::optional<sdf::Joint> 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(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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];

Expand Down Expand Up @@ -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<components::JointAxis>(_entity);
auto jointAxis2 = _ecm.Component<components::JointAxis2>(_entity);
Expand Down Expand Up @@ -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<components::JointAxis>(_entity);
auto jointAxis2 = _ecm.Component<components::JointAxis2>(_entity);
Expand Down
12 changes: 6 additions & 6 deletions src/rendering/RenderUtil.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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];

Expand Down Expand Up @@ -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<components::JointAxis>(_entity);
auto jointAxis2 = _ecm.Component<components::JointAxis2>(_entity);
Expand Down Expand Up @@ -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<components::JointAxis>(_entity);
auto jointAxis2 = _ecm.Component<components::JointAxis2>(_entity);
Expand Down
4 changes: 2 additions & 2 deletions src/systems/physics/Physics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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<components::JointAxis>(_entity);
auto jointAxis2 = _ecm.Component<components::JointAxis2>(_entity);
Expand Down
4 changes: 2 additions & 2 deletions test/integration/save_world.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit 136c840

Please sign in to comment.