Skip to content

Commit

Permalink
Merge 95b3963 into 12e9c1f
Browse files Browse the repository at this point in the history
  • Loading branch information
scpeters authored Aug 17, 2022
2 parents 12e9c1f + 95b3963 commit 8223118
Show file tree
Hide file tree
Showing 6 changed files with 48 additions and 47 deletions.
6 changes: 6 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -538,6 +538,12 @@ ABI was broken for `sdf::Element`, and restored on version 11.2.1.

### Modifications

1. **joint.sdf**: axis limits default values have changed
+ `//limit/lower`: `-inf` (formerly `-1e16`)
+ `//limit/upper`: `inf` (formerly `1e16`)
+ `//limit/velocity`: `inf` (formerly `-1`)
+ `//limit/effort`: `inf` (formerly `-1`)

1. **plugin.sdf**: name attribute is now optional with empty default value.

## SDFormat specification 1.8 to 1.9
Expand Down
4 changes: 2 additions & 2 deletions python/test/pyJointAxis_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@ def test_default_construction(self):
self.assertAlmostEqual(0.0, axis.friction())
self.assertAlmostEqual(0.0, axis.spring_reference())
self.assertAlmostEqual(0.0, axis.spring_stiffness())
self.assertAlmostEqual(-1e16, axis.lower())
self.assertAlmostEqual(1e16, axis.upper())
self.assertAlmostEqual(-math.inf, axis.lower())
self.assertAlmostEqual(math.inf, axis.upper())
self.assertAlmostEqual(math.inf, axis.effort())
self.assertAlmostEqual(math.inf, axis.max_velocity())
self.assertAlmostEqual(1e8, axis.stiffness())
Expand Down
16 changes: 8 additions & 8 deletions sdf/1.10/joint.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -74,16 +74,16 @@
</element> <!-- End Dynamics -->
<element name="limit" required="1">
<description>specifies the limits of this joint</description>
<element name="lower" type="double" default="-1e16" required="1">
<element name="lower" type="double" default="-inf" required="1">
<description>Specifies the lower joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous.</description>
</element>
<element name="upper" type="double" default="1e16" required="1">
<element name="upper" type="double" default="inf" required="1">
<description>Specifies the upper joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous.</description>
</element>
<element name="effort" type="double" default="-1" required="0">
<element name="effort" type="double" default="inf" required="0">
<description>A value for enforcing the maximum joint effort applied. Limit is not enforced if value is negative.</description>
</element>
<element name="velocity" type="double" default="-1" required="0">
<element name="velocity" type="double" default="inf" required="0">
<description>A value for enforcing the maximum joint velocity.</description>
</element>

Expand Down Expand Up @@ -132,16 +132,16 @@

<element name="limit" required="1">
<description></description>
<element name="lower" type="double" default="-1e16" required="0">
<element name="lower" type="double" default="-inf" required="0">
<description>An attribute specifying the lower joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous.</description>
</element>
<element name="upper" type="double" default="1e16" required="0">
<element name="upper" type="double" default="inf" required="0">
<description>An attribute specifying the upper joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous.</description>
</element>
<element name="effort" type="double" default="-1" required="0">
<element name="effort" type="double" default="inf" required="0">
<description>An attribute for enforcing the maximum joint effort applied by Joint::SetForce. Limit is not enforced if value is negative.</description>
</element>
<element name="velocity" type="double" default="-1" required="0">
<element name="velocity" type="double" default="inf" required="0">
<description>(not implemented) An attribute for enforcing the maximum joint velocity.</description>
</element>

Expand Down
60 changes: 27 additions & 33 deletions src/JointAxis.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
*/
#include <algorithm>
#include <iterator>
#include <limits>

#include <gz/math/Pose3.hh>
#include <gz/math/Vector3.hh>
Expand All @@ -41,10 +42,6 @@ class sdf::JointAxis::Implementation
/// \brief Frame in which xyz is expressed in.
public: std::string xyzExpressedIn = "";

/// \brief Flag to interpret the axis xyz element in the parent model
/// frame instead of joint frame.
public: bool useParentModelFrame = false;

/// \brief The physical velocity dependent viscous damping coefficient
/// of the joint.
public: double damping = 0.0;
Expand All @@ -60,18 +57,18 @@ class sdf::JointAxis::Implementation

/// \brief Specifies the lower joint limit (radians for revolute joints,
/// meters for prismatic joints). Omit if joint is continuous.
public: double lower = -1e16;
public: double lower = -std::numeric_limits<double>::infinity();

/// \brief Specifies the upper joint limit (radians for revolute joints,
/// meters for prismatic joints). Omit if joint is continuous.
public: double upper = 1e16;
public: double upper = std::numeric_limits<double>::infinity();

/// \brief A value for enforcing the maximum joint effort applied.
/// Limit is not enforced if value is negative.
public: double effort = -1;
public: double effort = std::numeric_limits<double>::infinity();

/// \brief A value for enforcing the maximum joint velocity.
public: double maxVelocity = -1;
public: double maxVelocity = std::numeric_limits<double>::infinity();

/// \brief Joint stop stiffness.
public: double stiffness = 1e8;
Expand Down Expand Up @@ -106,7 +103,8 @@ Errors JointAxis::Load(ElementPtr _sdf)
if (_sdf->HasElement("xyz"))
{
using gz::math::Vector3d;
auto errs = this->SetXyz(_sdf->Get<Vector3d>("xyz", Vector3d::UnitZ).first);
auto errs = this->SetXyz(_sdf->Get<Vector3d>("xyz",
this->dataPtr->xyz).first);
std::copy(errs.begin(), errs.end(), std::back_inserter(errors));
auto e = _sdf->GetElement("xyz");
if (e->HasAttribute("expressed_in"))
Expand All @@ -120,37 +118,38 @@ Errors JointAxis::Load(ElementPtr _sdf)
"The xyz element in joint axis is required"});
}

// Get whether to use the parent model frame.
this->dataPtr->useParentModelFrame = _sdf->Get<bool>(
"use_parent_model_frame", false).first;

// Load dynamic values, if present
if (_sdf->HasElement("dynamics"))
{
sdf::ElementPtr dynElement = _sdf->GetElement("dynamics");

this->dataPtr->damping = dynElement->Get<double>("damping", 0.0).first;
this->dataPtr->friction = dynElement->Get<double>("friction", 0.0).first;
this->dataPtr->springReference =
dynElement->Get<double>("spring_reference", 0.0).first;
this->dataPtr->springStiffness =
dynElement->Get<double>("spring_stiffness", 0.0).first;
this->dataPtr->damping = dynElement->Get<double>("damping",
this->dataPtr->damping).first;
this->dataPtr->friction = dynElement->Get<double>("friction",
this->dataPtr->friction).first;
this->dataPtr->springReference = dynElement->Get<double>("spring_reference",
this->dataPtr->springReference).first;
this->dataPtr->springStiffness = dynElement->Get<double>("spring_stiffness",
this->dataPtr->springStiffness).first;
}

// Load limit values
if (_sdf->HasElement("limit"))
{
sdf::ElementPtr limitElement = _sdf->GetElement("limit");

this->dataPtr->lower = limitElement->Get<double>("lower", -1e16).first;
this->dataPtr->upper = limitElement->Get<double>("upper", 1e16).first;
this->dataPtr->effort = limitElement->Get<double>("effort", -1).first;
this->dataPtr->maxVelocity = limitElement->Get<double>(
"velocity", -1).first;
this->dataPtr->stiffness = limitElement->Get<double>(
"stiffness", 1e8).first;
this->dataPtr->dissipation = limitElement->Get<double>(
"dissipation", 1.0).first;
this->dataPtr->lower = limitElement->Get<double>("lower",
this->dataPtr->lower).first;
this->dataPtr->upper = limitElement->Get<double>("upper",
this->dataPtr->upper).first;
this->dataPtr->effort = limitElement->Get<double>("effort",
this->dataPtr->effort).first;
this->dataPtr->maxVelocity = limitElement->Get<double>("velocity",
this->dataPtr->maxVelocity).first;
this->dataPtr->stiffness = limitElement->Get<double>("stiffness",
this->dataPtr->stiffness).first;
this->dataPtr->dissipation = limitElement->Get<double>("dissipation",
this->dataPtr->dissipation).first;
}
else
{
Expand Down Expand Up @@ -392,11 +391,6 @@ sdf::ElementPtr JointAxis::ToElement(unsigned int _index) const
xyzElem->GetAttribute("expressed_in")->Set<std::string>(
this->XyzExpressedIn());
}
else if (this->dataPtr->useParentModelFrame)
{
xyzElem->GetAttribute("expressed_in")->Set<std::string>(
"__model__");
}
sdf::ElementPtr dynElem = axisElem->GetElement("dynamics");
dynElem->GetElement("damping")->Set<double>(this->Damping());
dynElem->GetElement("friction")->Set<double>(this->Friction());
Expand Down
5 changes: 3 additions & 2 deletions src/JointAxis_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
*/

#include <gtest/gtest.h>
#include <limits>
#include "sdf/JointAxis.hh"

/////////////////////////////////////////////////
Expand All @@ -29,8 +30,8 @@ TEST(DOMJointAxis, Construction)
EXPECT_DOUBLE_EQ(0.0, axis.Friction());
EXPECT_DOUBLE_EQ(0.0, axis.SpringReference());
EXPECT_DOUBLE_EQ(0.0, axis.SpringStiffness());
EXPECT_DOUBLE_EQ(-1e16, axis.Lower());
EXPECT_DOUBLE_EQ(1e16, axis.Upper());
EXPECT_DOUBLE_EQ(-std::numeric_limits<double>::infinity(), axis.Lower());
EXPECT_DOUBLE_EQ(std::numeric_limits<double>::infinity(), axis.Upper());
EXPECT_DOUBLE_EQ(std::numeric_limits<double>::infinity(), axis.Effort());
EXPECT_DOUBLE_EQ(std::numeric_limits<double>::infinity(), axis.MaxVelocity());
EXPECT_DOUBLE_EQ(1e8, axis.Stiffness());
Expand Down
4 changes: 2 additions & 2 deletions test/integration/joint_axis_dom.cc
Original file line number Diff line number Diff line change
Expand Up @@ -244,8 +244,8 @@ TEST(DOMJointAxis, InfiniteLimits)
ASSERT_NE(nullptr, joint);
auto axis = joint->Axis(0);
ASSERT_NE(nullptr, axis);
EXPECT_DOUBLE_EQ(-1e16, axis->Lower());
EXPECT_DOUBLE_EQ(1e16, axis->Upper());
EXPECT_DOUBLE_EQ(-kInf, axis->Lower());
EXPECT_DOUBLE_EQ(kInf, axis->Upper());
EXPECT_DOUBLE_EQ(kInf, axis->Effort());
EXPECT_DOUBLE_EQ(kInf, axis->MaxVelocity());
}
Expand Down

0 comments on commit 8223118

Please sign in to comment.