diff --git a/Migration.md b/Migration.md index a169cb5bf..c1c88f5c2 100644 --- a/Migration.md +++ b/Migration.md @@ -19,7 +19,20 @@ one root level model, actor or light. ### Removals -1. **src/Root.hh**: The following deprecated methods have been removed. +The following deprecated methods and classes have been removed. + +1. **sdf/Element.hh** + + void SetInclude(const std::string); + + std::string GetInclude() const; + +1. **sdf/Types.hh** + + sdf::Color class + +1. **sdf/JointAxis.hh** + + double InitialPosition() const; + + void SetInitialPosition(const double) + +1. **sdf/Root.hh**: + const sdf::Model \*ModelByIndex(); + uint64_t ModelCount(); + bool ModelNameExists(const std::string &\_name) const; @@ -351,6 +364,11 @@ ABI was broken for `sdf::Element`, and restored on version 11.2.1. ## SDFormat specification 1.8 to 1.9 +###Removals + +1. **joint.sdf** + + Deprecated elements `//joint/axis/initial_position` and `//joint/axis2/initial_position` have been removed + ## SDFormat specification 1.7 to 1.8 ### Additions diff --git a/include/sdf/Element.hh b/include/sdf/Element.hh index 2b47e655f..9d6332477 100644 --- a/include/sdf/Element.hh +++ b/include/sdf/Element.hh @@ -395,14 +395,6 @@ namespace sdf /// embedded Param. public: void Reset(); - /// \brief Set the include filename to the passed in filename. - /// \param[in] _filename the filename to set the include filename to. - public: void SetInclude(const std::string &_filename) SDF_DEPRECATED(11.0); - - /// \brief Get the include filename. - /// \return The include filename. - public: std::string GetInclude() const SDF_DEPRECATED(11.0); - /// \brief Set the element that was used to load this element. /// This is set by the parser on the first element of the included object /// (eg. Model, Actor, Light, etc). It is not passed down to children @@ -562,9 +554,6 @@ namespace sdf /// this is when saving a loaded world back to SDFormat. public: ElementPtr includeElement; - /// name of the include file that was used to create this element - public: std::string includeFilename; - /// \brief Name of reference sdf. public: std::string referenceSDF; diff --git a/include/sdf/JointAxis.hh b/include/sdf/JointAxis.hh index d16aac72f..d788d6f2d 100644 --- a/include/sdf/JointAxis.hh +++ b/include/sdf/JointAxis.hh @@ -52,17 +52,6 @@ namespace sdf /// an error code and message. An empty vector indicates no error. public: Errors Load(ElementPtr _sdf); - /// \brief Get the initial joint position for this joint axis. The - /// default value is zero (0.0). - /// \return The initial joint position. - /// \sa void SetInitialPosition(const double _pos) - public: double InitialPosition() const SDF_DEPRECATED(10.0); - - /// \brief Set the initial joint position for this joint axis. - /// \param[in] _pos The initial joint position. - /// \sa double InitialPosition() const - public: void SetInitialPosition(const double _pos) SDF_DEPRECATED(10.0); - /// \brief Get the x,y,z components of the axis unit vector. /// The axis is expressed in the frame named in XyzExpressedIn() and /// defaults to the joint frame if that method returns an empty string. diff --git a/include/sdf/Types.hh b/include/sdf/Types.hh index ada95baac..c0e964ced 100644 --- a/include/sdf/Types.hh +++ b/include/sdf/Types.hh @@ -112,66 +112,6 @@ namespace sdf SDFORMAT_VISIBLE std::ostream &operator<<( std::ostream &_out, const sdf::Errors &_errs); - /// \brief Defines a color - class SDFORMAT_VISIBLE Color - { - /// \brief Constructor - /// \param[in] _r Red value (range 0 to 1) - /// \param[in] _g Green value (range 0 to 1 - /// \param[in] _b Blue value (range 0 to 1 - /// \param[in] _a Alpha value (0=transparent, 1=opaque) - /// \deprecated Use ignition::math::Color - public: Color(float _r = 0.0f, float _g = 0.0f, - float _b = 0.0f, float _a = 1.0f) SDF_DEPRECATED(6.0) - : r(_r), g(_g), b(_b), a(_a) - {} - - /// \brief Stream insertion operator - /// \param[in] _out the output stream - /// \param[in] _pt the color - /// \return the output stream - public: friend std::ostream &operator<< (std::ostream &_out, - const Color &_pt) - { - _out << _pt.r << " " << _pt.g << " " << _pt.b << " " << _pt.a; - return _out; - } - - /// \brief Stream insertion operator - /// \param[in] _in the input stream - /// \param[in] _pt - public: friend std::istream &operator>> (std::istream &_in, Color &_pt) - { - // Skip white spaces - _in.setf(std::ios_base::skipws); - _in >> _pt.r >> _pt.g >> _pt.b >> _pt.a; - return _in; - } - - /// \brief Equality operator - /// \param[in] _clr The color to check for equality - /// \return True if the this color equals _clf - public: bool operator ==(const Color &_clr) const - { - return equal(this->r, _clr.r) && - equal(this->g, _clr.g) && - equal(this->b, _clr.b) && - equal(this->a, _clr.a); - } - - /// \brief Red value - public: float r; - - /// \brief Green value - public: float g; - - /// \brief Blue value - public: float b; - - /// \brief Alpha value - public: float a; - }; - /// \brief A Time class, can be used to hold wall- or sim-time. /// stored as sec and nano-sec. class SDFORMAT_VISIBLE Time diff --git a/sdf/1.9/1_8.convert b/sdf/1.9/1_8.convert index f184573b4..36fed6b5b 100644 --- a/sdf/1.9/1_8.convert +++ b/sdf/1.9/1_8.convert @@ -1,3 +1,12 @@ + + + + + + + + + diff --git a/sdf/1.9/joint.sdf b/sdf/1.9/joint.sdf index f58fa75fd..9e7ca7e1f 100644 --- a/sdf/1.9/joint.sdf +++ b/sdf/1.9/joint.sdf @@ -45,11 +45,6 @@ Parameters related to the axis of rotation for revolute joints, the axis of translation for prismatic joints. - - - (DEPRECATION WARNING: This tag has no known implementation. It is deprecated SDFormat 1.8 and will be removed in SDFormat 1.9) Default joint position for this joint axis. - - Represents the x,y,z components of the axis unit vector. The axis is @@ -107,11 +102,6 @@ Parameters related to the second axis of rotation for revolute2 joints and universal joints. - - - (DEPRECATION WARNING: This tag has no known implementation. It is deprecated SDFormat 1.8 and will be removed in SDFormat 1.9) Default joint position for this joint axis. - - Represents the x,y,z components of the axis unit vector. The axis is diff --git a/src/Element.cc b/src/Element.cc index b1383dcd6..3b3cecc38 100644 --- a/src/Element.cc +++ b/src/Element.cc @@ -184,7 +184,6 @@ ElementPtr Element::Clone() const clone->dataPtr->name = this->dataPtr->name; clone->dataPtr->required = this->dataPtr->required; clone->dataPtr->copyChildren = this->dataPtr->copyChildren; - clone->dataPtr->includeFilename = this->dataPtr->includeFilename; clone->dataPtr->referenceSDF = this->dataPtr->referenceSDF; clone->dataPtr->path = this->dataPtr->path; clone->dataPtr->lineNumber = this->dataPtr->lineNumber; @@ -233,7 +232,6 @@ void Element::Copy(const ElementPtr _elem) this->dataPtr->description = _elem->GetDescription(); this->dataPtr->required = _elem->GetRequired(); this->dataPtr->copyChildren = _elem->GetCopyChildren(); - this->dataPtr->includeFilename = _elem->dataPtr->includeFilename; this->dataPtr->referenceSDF = _elem->ReferenceSDF(); this->dataPtr->originalVersion = _elem->OriginalVersion(); this->dataPtr->path = _elem->FilePath(); @@ -552,15 +550,7 @@ std::string Element::ToString(const std::string &_prefix) const void Element::ToString(const std::string &_prefix, std::ostringstream &_out) const { - if (this->dataPtr->includeFilename.empty()) - { - PrintValuesImpl(_prefix, _out); - } - else - { - _out << _prefix << "\n"; - } + PrintValuesImpl(_prefix, _out); } ///////////////////////////////////////////////// @@ -966,18 +956,6 @@ void Element::AddElementDescription(ElementPtr _elem) this->dataPtr->elementDescriptions.push_back(_elem); } -///////////////////////////////////////////////// -void Element::SetInclude(const std::string &_filename) -{ - this->dataPtr->includeFilename = _filename; -} - -///////////////////////////////////////////////// -std::string Element::GetInclude() const -{ - return this->dataPtr->includeFilename; -} - ///////////////////////////////////////////////// void Element::SetIncludeElement(sdf::ElementPtr _includeElem) { diff --git a/src/Element_TEST.cc b/src/Element_TEST.cc index 2e2404a59..c7816a1cb 100644 --- a/src/Element_TEST.cc +++ b/src/Element_TEST.cc @@ -284,14 +284,6 @@ TEST(Element, Include) { sdf::Element elem; - SDF_SUPPRESS_DEPRECATED_BEGIN - ASSERT_EQ(elem.GetInclude(), ""); - - elem.SetInclude("foo.txt"); - - ASSERT_EQ(elem.GetInclude(), "foo.txt"); - SDF_SUPPRESS_DEPRECATED_END - auto includeElemToStore = std::make_shared(); includeElemToStore->SetName("include"); auto uriDesc = std::make_shared(); @@ -602,23 +594,6 @@ TEST(Element, ToStringClonedElement) EXPECT_EQ(parent->ToString("myprefix"), parentClone->ToString("myprefix")); } -///////////////////////////////////////////////// -TEST(Element, ToStringInclude) -{ - sdf::Element elem; - - SDF_SUPPRESS_DEPRECATED_BEGIN - ASSERT_EQ(elem.GetInclude(), ""); - - elem.SetInclude("foo.txt"); - - ASSERT_EQ(elem.GetInclude(), "foo.txt"); - SDF_SUPPRESS_DEPRECATED_END - - std::string stringval = elem.ToString("myprefix"); - ASSERT_EQ(stringval, "myprefix\n"); -} - ///////////////////////////////////////////////// TEST(Element, DocLeftPane) { diff --git a/src/JointAxis.cc b/src/JointAxis.cc index a6eee2fac..af2fc1b73 100644 --- a/src/JointAxis.cc +++ b/src/JointAxis.cc @@ -31,9 +31,6 @@ using namespace sdf; class sdf::JointAxis::Implementation { - /// \brief Default joint position for this joint axis. - public: double initialPosition = 0.0; - /// \brief Represents the x,y,z components of the axis unit vector. /// The axis is expressed in the joint frame unless the /// use_parent_model_frame flag is set to true. The vector should be @@ -104,10 +101,6 @@ Errors JointAxis::Load(ElementPtr _sdf) this->dataPtr->sdf = _sdf; - // Read the initial position. This is optional, with a default value of 0. - this->dataPtr->initialPosition = _sdf->Get( - "initial_position", 0.0).first; - // Read the xyz values. if (_sdf->HasElement("xyz")) { @@ -167,17 +160,6 @@ Errors JointAxis::Load(ElementPtr _sdf) return errors; } -///////////////////////////////////////////////// -double JointAxis::InitialPosition() const -{ - return this->dataPtr->initialPosition; -} -///////////////////////////////////////////////// -void JointAxis::SetInitialPosition(const double _pos) -{ - this->dataPtr->initialPosition = _pos; -} - ///////////////////////////////////////////////// ignition::math::Vector3d JointAxis::Xyz() const { diff --git a/src/JointAxis_TEST.cc b/src/JointAxis_TEST.cc index 770061080..d4be702d2 100644 --- a/src/JointAxis_TEST.cc +++ b/src/JointAxis_TEST.cc @@ -23,9 +23,6 @@ TEST(DOMJointAxis, Construction) { sdf::JointAxis axis; EXPECT_EQ(nullptr, axis.Element()); - SDF_SUPPRESS_DEPRECATED_BEGIN - EXPECT_DOUBLE_EQ(0.0, axis.InitialPosition()); - SDF_SUPPRESS_DEPRECATED_END EXPECT_EQ(ignition::math::Vector3d::UnitZ, axis.Xyz()); EXPECT_TRUE(axis.XyzExpressedIn().empty()); EXPECT_DOUBLE_EQ(0.0, axis.Damping()); @@ -39,11 +36,6 @@ TEST(DOMJointAxis, Construction) EXPECT_DOUBLE_EQ(1e8, axis.Stiffness()); EXPECT_DOUBLE_EQ(1.0, axis.Dissipation()); - SDF_SUPPRESS_DEPRECATED_BEGIN - axis.SetInitialPosition(1.2); - EXPECT_DOUBLE_EQ(1.2, axis.InitialPosition()); - SDF_SUPPRESS_DEPRECATED_END - { sdf::Errors errors = axis.SetXyz(ignition::math::Vector3d(0, 1, 0)); EXPECT_TRUE(errors.empty()); diff --git a/test/integration/joint_axis_dom.cc b/test/integration/joint_axis_dom.cc index e2bff61f0..6469001b2 100644 --- a/test/integration/joint_axis_dom.cc +++ b/test/integration/joint_axis_dom.cc @@ -86,11 +86,6 @@ TEST(DOMJointAxis, Complete) EXPECT_EQ("__model__", axis->XyzExpressedIn()); EXPECT_TRUE(axis2->XyzExpressedIn().empty()); - SDF_SUPPRESS_DEPRECATED_BEGIN - EXPECT_DOUBLE_EQ(0.5, axis->InitialPosition()); - EXPECT_DOUBLE_EQ(1.5, axis2->InitialPosition()); - SDF_SUPPRESS_DEPRECATED_END - EXPECT_DOUBLE_EQ(-0.5, axis->Lower()); EXPECT_DOUBLE_EQ(0.5, axis->Upper()); EXPECT_DOUBLE_EQ(-1.0, axis2->Lower()); @@ -113,6 +108,10 @@ TEST(DOMJointAxis, Complete) EXPECT_DOUBLE_EQ(10.6, axis->SpringStiffness()); EXPECT_DOUBLE_EQ(0.0, axis2->SpringStiffness()); + + // Ensure that //axis/initial_position is removed during conversion + EXPECT_FALSE(axis->Element()->HasElement("initial_position")); + EXPECT_FALSE(axis2->Element()->HasElement("initial_position")); } //////////////////////////////////////////////////