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

Remove use of deprecated function sdf::JointAxis::InitialPosition #276

Merged
merged 2 commits into from
Jul 18, 2021
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
38 changes: 0 additions & 38 deletions dartsim/src/SDFFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -126,20 +126,6 @@ static void CopyStandardJointAxisProperties(
const int _index, Properties &_properties,
const ::sdf::JointAxis *_sdfAxis)
{
#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#else
# pragma warning(push)
# pragma warning(disable: 4996)
#endif
// TODO(anyone): stop using this deprecated function
_properties.mInitialPositions[_index] = _sdfAxis->InitialPosition();
#ifndef _WIN32
# pragma GCC diagnostic pop
#else
# pragma warning(pop)
#endif
_properties.mDampingCoefficients[_index] = _sdfAxis->Damping();
_properties.mFrictions[_index] = _sdfAxis->Friction();
_properties.mRestPositions[_index] = _sdfAxis->SpringReference();
Expand Down Expand Up @@ -1115,30 +1101,6 @@ Identity SDFFeatures::ConstructSdfJoint(
joint->setTransformFromParentBodyNode(parent_T_prejoint_init);
joint->setTransformFromChildBodyNode(child_T_postjoint);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is this block up here still needed? The comment seems outdated

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

agreed, the comment seems outdated

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm going to merge this now to unbreak things but will open an issue to follow up on this comment

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, the code is needed, but the comment is indeed outdated. I think it can simply be removed.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.


// This is the transform inside the joint produced by whatever the current
// joint position happens to be.
const Eigen::Isometry3d T_child_parent_postjoint =
_parent ? _child->getTransform(_parent) : _child->getTransform();

const Eigen::Isometry3d prejoint_T_postjoint =
parent_T_prejoint_init.inverse()
* T_child_parent_postjoint
* child_T_postjoint;

// This is the corrected transform needed to get the child link to its
// correct pose (as specified by the loaded SDF) for the current initial
// position
const Eigen::Isometry3d T_parent_postjoint =
_parent ? _parent->getWorldTransform() : Eigen::Isometry3d::Identity();

const Eigen::Isometry3d parent_T_prejoint_final =
T_parent_postjoint.inverse()
* T_child
* child_T_postjoint
* prejoint_T_postjoint.inverse();

joint->setTransformFromParentBodyNode(parent_T_prejoint_final);

const std::size_t jointID = this->AddJoint(joint);

return this->GenerateIdentity(jointID, this->joints.at(jointID));
Expand Down
8 changes: 3 additions & 5 deletions dartsim/src/SDFFeatures_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -323,12 +323,10 @@ TEST_P(SDFFeatures_TEST, CheckDartsimData)
ASSERT_EQ(3u, skeleton->getNumBodyNodes());

auto verify = [](const dart::dynamics::DegreeOfFreedom * dof,
double initialPos, double damping, double friction,
double damping, double friction,
double springRest, double stiffness, double lower,
double upper, double maxForce, double maxVelocity)
{
EXPECT_DOUBLE_EQ(initialPos, dof->getPosition());
EXPECT_DOUBLE_EQ(initialPos, dof->getInitialPosition());
EXPECT_DOUBLE_EQ(damping, dof->getDampingCoefficient());
EXPECT_DOUBLE_EQ(friction, dof->getCoulombFriction());
EXPECT_DOUBLE_EQ(springRest, dof->getRestPosition());
Expand All @@ -344,12 +342,12 @@ TEST_P(SDFFeatures_TEST, CheckDartsimData)
// Test that things were parsed correctly. These values are either stated or
// implied in the test.world SDF file.
verify(skeleton->getJoint(1)->getDof(0),
1.5706796, 3.0, 0.0, 0.0, 0.0, -1e16, 1e16,
3.0, 0.0, 0.0, 0.0, -1e16, 1e16,
std::numeric_limits<double>::infinity(),
std::numeric_limits<double>::infinity());

verify(skeleton->getJoint(2)->getDof(0),
-0.429462, 3.0, 0.0, 0.0, 0.0, -1e16, 1e16,
3.0, 0.0, 0.0, 0.0, -1e16, 1e16,
std::numeric_limits<double>::infinity(),
std::numeric_limits<double>::infinity());

Expand Down
4 changes: 0 additions & 4 deletions dartsim/worlds/test.world
Original file line number Diff line number Diff line change
Expand Up @@ -221,8 +221,6 @@
<parent>base</parent>
<child>upper_link</child>
<axis>
<!-- TODO(anyone): stop using deprecated element -->
<initial_position>1.5706796</initial_position>
<xyz>1.0 0 0</xyz>
<dynamics>
<damping>3.0</damping>
Expand All @@ -234,8 +232,6 @@
<parent>upper_link</parent>
<child>lower_link</child>
<axis>
<!-- TODO(anyone): stop using deprecated element -->
<initial_position>-0.429462</initial_position>
<xyz>1.0 0 0</xyz>
<dynamics>
<damping>3.0</damping>
Expand Down