diff --git a/dart/constraint/ConstraintSolver.cpp b/dart/constraint/ConstraintSolver.cpp index 58d3d4c130e1b..8c2686bd511fe 100644 --- a/dart/constraint/ConstraintSolver.cpp +++ b/dart/constraint/ConstraintSolver.cpp @@ -258,14 +258,6 @@ double ConstraintSolver::getTimeStep() const return mTimeStep; } -//============================================================================== -void ConstraintSolver::setCollisionDetector( - collision::CollisionDetector* collisionDetector) -{ - setCollisionDetector( - std::unique_ptr(collisionDetector)); -} - //============================================================================== void ConstraintSolver::setCollisionDetector( const std::shared_ptr& collisionDetector) @@ -363,9 +355,6 @@ void ConstraintSolver::solve() { for (auto& skeleton : mSkeletons) { skeleton->clearConstraintImpulses(); - DART_SUPPRESS_DEPRECATED_BEGIN - skeleton->clearCollidingBodies(); - DART_SUPPRESS_DEPRECATED_END } // Update constraints and collect active constraints @@ -514,17 +503,6 @@ void ConstraintSolver::updateConstraints() continue; } - // Set colliding bodies - auto shapeFrame1 = const_cast( - contact.collisionObject1->getShapeFrame()); - auto shapeFrame2 = const_cast( - contact.collisionObject2->getShapeFrame()); - - DART_SUPPRESS_DEPRECATED_BEGIN - shapeFrame1->asShapeNode()->getBodyNodePtr()->setColliding(true); - shapeFrame2->asShapeNode()->getBodyNodePtr()->setColliding(true); - DART_SUPPRESS_DEPRECATED_END - // If penetration depth is negative, then the collision isn't really // happening and the contact point should be ignored. // TODO(MXG): Investigate ways to leverage the proximity information of a diff --git a/dart/constraint/ConstraintSolver.hpp b/dart/constraint/ConstraintSolver.hpp index 4935eb5ffda98..057a6206e7aab 100644 --- a/dart/constraint/ConstraintSolver.hpp +++ b/dart/constraint/ConstraintSolver.hpp @@ -163,12 +163,6 @@ class ConstraintSolver /// Get time step double getTimeStep() const; - /// Set collision detector. This function acquires ownership of the - /// CollisionDetector passed as an argument. This method is deprecated in - /// favor of the overload that accepts a std::shared_ptr. - DART_DEPRECATED(6.0) - void setCollisionDetector(collision::CollisionDetector* collisionDetector); - /// Set collision detector void setCollisionDetector( const std::shared_ptr& collisionDetector); diff --git a/dart/dynamics/BodyNode.cpp b/dart/dynamics/BodyNode.cpp index 9026ca45b542a..7700725dd5015 100644 --- a/dart/dynamics/BodyNode.cpp +++ b/dart/dynamics/BodyNode.cpp @@ -1166,18 +1166,6 @@ const Eigen::Vector6d& BodyNode::getBodyVelocityChange() const return mDelV; } -//============================================================================== -void BodyNode::setColliding(bool _isColliding) -{ - mIsColliding = _isColliding; -} - -//============================================================================== -bool BodyNode::isColliding() -{ - return mIsColliding; -} - //============================================================================== void BodyNode::addExtForce( const Eigen::Vector3d& _force, @@ -1263,7 +1251,6 @@ BodyNode::BodyNode( Frame(Frame::World()), TemplatedJacobianNode(this), mID(BodyNode::msBodyNodeCount++), - mIsColliding(false), mParentJoint(_parentJoint), mParentBodyNode(nullptr), mPartialAcceleration(Eigen::Vector6d::Zero()), diff --git a/dart/dynamics/BodyNode.hpp b/dart/dynamics/BodyNode.hpp index 83bc96a597dba..034b0a6ab89a2 100644 --- a/dart/dynamics/BodyNode.hpp +++ b/dart/dynamics/BodyNode.hpp @@ -725,25 +725,13 @@ class BodyNode /// Return the velocity change due to the constraint impulse const Eigen::Vector6d& getBodyVelocityChange() const; - /// Set whether this body node is colliding with other objects. Note that - /// this status is set by the constraint solver during dynamics simulation but - /// not by collision detector. - /// \param[in] _isColliding True if this body node is colliding. - DART_DEPRECATED(6.0) - void setColliding(bool _isColliding); - - /// Return whether this body node is set to be colliding with other objects. - /// \return True if this body node is colliding. - DART_DEPRECATED(6.0) - bool isColliding(); - /// Add applying linear Cartesian forces to this node /// /// A force is defined by a point of application and a force vector. The /// last two parameters specify frames of the first two parameters. /// Coordinate transformations are applied when needed. The point of /// application and the force in local coordinates are stored in mContacts. - /// When conversion is needed, make sure the transformations are avaialble. + /// When conversion is needed, make sure the transformations are available. void addExtForce( const Eigen::Vector3d& _force, const Eigen::Vector3d& _offset = Eigen::Vector3d::Zero(), @@ -1105,10 +1093,6 @@ class BodyNode /// Counts the number of nodes globally. static std::size_t msBodyNodeCount; - /// Whether the node is currently in collision with another node. - /// \deprecated DART_DEPRECATED(6.0) See #670 for more detail. - bool mIsColliding; - //-------------------------------------------------------------------------- // Structural Properties //-------------------------------------------------------------------------- diff --git a/dart/dynamics/Joint.cpp b/dart/dynamics/Joint.cpp index b71f9178c4a2b..b453648ee459b 100644 --- a/dart/dynamics/Joint.cpp +++ b/dart/dynamics/Joint.cpp @@ -334,48 +334,6 @@ std::shared_ptr Joint::getSkeleton() const return mChildBodyNode ? mChildBodyNode->getSkeleton() : nullptr; } -//============================================================================== -const Eigen::Isometry3d& Joint::getLocalTransform() const -{ - return getRelativeTransform(); -} - -//============================================================================== -const Eigen::Vector6d& Joint::getLocalSpatialVelocity() const -{ - return getRelativeSpatialVelocity(); -} - -//============================================================================== -const Eigen::Vector6d& Joint::getLocalSpatialAcceleration() const -{ - return getRelativeSpatialAcceleration(); -} - -//============================================================================== -const Eigen::Vector6d& Joint::getLocalPrimaryAcceleration() const -{ - return getRelativePrimaryAcceleration(); -} - -//============================================================================== -const math::Jacobian Joint::getLocalJacobian() const -{ - return getRelativeJacobian(); -} - -//============================================================================== -math::Jacobian Joint::getLocalJacobian(const Eigen::VectorXd& positions) const -{ - return getRelativeJacobian(positions); -} - -//============================================================================== -const math::Jacobian Joint::getLocalJacobianTimeDeriv() const -{ - return getRelativeJacobianTimeDeriv(); -} - //============================================================================== const Eigen::Isometry3d& Joint::getRelativeTransform() const { @@ -599,42 +557,6 @@ DegreeOfFreedom* Joint::createDofPointer(std::size_t _indexInJoint) return new DegreeOfFreedom(this, _indexInJoint); } -//============================================================================== -void Joint::updateLocalTransform() const -{ - updateRelativeTransform(); -} - -//============================================================================== -void Joint::updateLocalSpatialVelocity() const -{ - updateRelativeSpatialVelocity(); -} - -//============================================================================== -void Joint::updateLocalSpatialAcceleration() const -{ - updateRelativeSpatialAcceleration(); -} - -//============================================================================== -void Joint::updateLocalPrimaryAcceleration() const -{ - updateRelativePrimaryAcceleration(); -} - -//============================================================================== -void Joint::updateLocalJacobian(bool mandatory) const -{ - updateRelativeJacobian(mandatory); -} - -//============================================================================== -void Joint::updateLocalJacobianTimeDeriv() const -{ - updateRelativeJacobianTimeDeriv(); -} - //============================================================================== void Joint::updateArticulatedInertia() const { diff --git a/dart/dynamics/Joint.hpp b/dart/dynamics/Joint.hpp index a49a787fdaae0..3b5875fe9e350 100644 --- a/dart/dynamics/Joint.hpp +++ b/dart/dynamics/Joint.hpp @@ -662,34 +662,6 @@ class Joint : public virtual common::Subject, //---------------------------------------------------------------------------- - /// Deprecated. Use getRelativeTransform() instead. - DART_DEPRECATED(6.0) - const Eigen::Isometry3d& getLocalTransform() const; - - /// Deprecated. Use getLocalSpatialVelocity() instead. - DART_DEPRECATED(6.0) - const Eigen::Vector6d& getLocalSpatialVelocity() const; - - /// Deprecated. Use getLocalSpatialAcceleration() instead. - DART_DEPRECATED(6.0) - const Eigen::Vector6d& getLocalSpatialAcceleration() const; - - /// Deprecated. Use getLocalPrimaryAcceleration() instead. - DART_DEPRECATED(6.0) - const Eigen::Vector6d& getLocalPrimaryAcceleration() const; - - /// Deprecated. Use getRelativeJacobian() instead. - DART_DEPRECATED(6.0) - const math::Jacobian getLocalJacobian() const; - - /// Deprecated. Use getRelativeJacobian() instead. - DART_DEPRECATED(6.0) - math::Jacobian getLocalJacobian(const Eigen::VectorXd& positions) const; - - /// Deprecated. Use getRelativeJacobianTimeDeriv() instead. - DART_DEPRECATED(6.0) - const math::Jacobian getLocalJacobianTimeDeriv() const; - /// Get transform of the child BodyNode relative to the parent BodyNode /// expressed in the child BodyNode frame const Eigen::Isometry3d& getRelativeTransform() const; @@ -836,30 +808,6 @@ class Joint : public virtual common::Subject, /// \{ \name Recursive dynamics routines //---------------------------------------------------------------------------- - /// Deprecated. Use updateRelativeTransform() instead. - DART_DEPRECATED(6.0) - void updateLocalTransform() const; - - /// Deprecated. Use updateRelativeSpatialVelocity() instead. - DART_DEPRECATED(6.0) - void updateLocalSpatialVelocity() const; - - /// Deprecated. Use updateRelativeSpatialAcceleration() instead. - DART_DEPRECATED(6.0) - void updateLocalSpatialAcceleration() const; - - /// Deprecated. Use updateRelativePrimaryAcceleration() instead. - DART_DEPRECATED(6.0) - void updateLocalPrimaryAcceleration() const; - - /// Deprecated. Use updateRelativeJacobian() instead. - DART_DEPRECATED(6.0) - void updateLocalJacobian(bool mandatory = true) const; - - /// Deprecated. Use updateRelativeJacobianTimeDeriv() instead. - DART_DEPRECATED(6.0) - void updateLocalJacobianTimeDeriv() const; - /// Update transform of the child BodyNode relative to the parent BodyNode /// expressed in the child BodyNode frame virtual void updateRelativeTransform() const = 0; diff --git a/dart/dynamics/Marker.cpp b/dart/dynamics/Marker.cpp index 43ee18a84cfb4..1235c67b2f443 100644 --- a/dart/dynamics/Marker.cpp +++ b/dart/dynamics/Marker.cpp @@ -64,18 +64,6 @@ void Marker::setAspectProperties(const AspectProperties& properties) setConstraintType(properties.mType); } -//============================================================================== -BodyNode* Marker::getBodyNode() -{ - return getBodyNodePtr(); -} - -//============================================================================== -const BodyNode* Marker::getBodyNode() const -{ - return getBodyNodePtr(); -} - //============================================================================== Eigen::Vector3d Marker::getLocalPosition() const { diff --git a/dart/dynamics/Marker.hpp b/dart/dynamics/Marker.hpp index 7cbf7e15a75b9..cf35b742fd944 100644 --- a/dart/dynamics/Marker.hpp +++ b/dart/dynamics/Marker.hpp @@ -67,18 +67,6 @@ class Marker final : public common::EmbedPropertiesOnTopOf< /// Set the AspectProperties of this Marker void setAspectProperties(const AspectProperties& properties); - /// Get the BodyNode this Marker belongs to - /// - /// Deprecated: Use getBodyNodePtr() instead - DART_DEPRECATED(6.0) - BodyNode* getBodyNode(); - - /// Get the (const) BodyNode this Marker belongs to - /// - /// Deprecated: Use getBodyNodePtr() instead - DART_DEPRECATED(6.0) - const BodyNode* getBodyNode() const; - /// Get position of this marker in the parent body node coordinates Eigen::Vector3d getLocalPosition() const; diff --git a/dart/dynamics/MetaSkeleton.hpp b/dart/dynamics/MetaSkeleton.hpp index a83affc750222..984ea2a990db6 100644 --- a/dart/dynamics/MetaSkeleton.hpp +++ b/dart/dynamics/MetaSkeleton.hpp @@ -836,10 +836,6 @@ class MetaSkeleton : public common::Subject /// Get the potential energy of this MetaSkeleton virtual double computePotentialEnergy() const = 0; - /// Clear collision flags of the BodyNodes in this MetaSkeleton - DART_DEPRECATED(6.0) - virtual void clearCollidingBodies() = 0; - /// \} //---------------------------------------------------------------------------- diff --git a/dart/dynamics/ReferentialSkeleton.cpp b/dart/dynamics/ReferentialSkeleton.cpp index 5da4124ec3540..09bacd88f2bb5 100644 --- a/dart/dynamics/ReferentialSkeleton.cpp +++ b/dart/dynamics/ReferentialSkeleton.cpp @@ -942,25 +942,6 @@ double ReferentialSkeleton::computePotentialEnergy() const return PE; } -//============================================================================== -void ReferentialSkeleton::clearCollidingBodies() -{ - for (auto i = 0u; i < getNumBodyNodes(); ++i) { - auto bodyNode = getBodyNode(i); - DART_SUPPRESS_DEPRECATED_BEGIN - bodyNode->setColliding(false); - DART_SUPPRESS_DEPRECATED_END - - auto softBodyNode = bodyNode->asSoftBodyNode(); - if (softBodyNode) { - auto& pointMasses = softBodyNode->getPointMasses(); - - for (auto pointMass : pointMasses) - pointMass->setColliding(false); - } - } -} - //============================================================================== Eigen::Vector3d ReferentialSkeleton::getCOM(const Frame* _withRespectTo) const { diff --git a/dart/dynamics/ReferentialSkeleton.hpp b/dart/dynamics/ReferentialSkeleton.hpp index d128aa31ca132..17d4da88018c1 100644 --- a/dart/dynamics/ReferentialSkeleton.hpp +++ b/dart/dynamics/ReferentialSkeleton.hpp @@ -349,10 +349,6 @@ class ReferentialSkeleton : public MetaSkeleton // Documentation inherited double computePotentialEnergy() const override; - // Documentation inherited - DART_DEPRECATED(6.0) - void clearCollidingBodies() override; - /// \} //---------------------------------------------------------------------------- diff --git a/dart/dynamics/Skeleton.cpp b/dart/dynamics/Skeleton.cpp index c844efc0471c1..44410dd9da873 100644 --- a/dart/dynamics/Skeleton.cpp +++ b/dart/dynamics/Skeleton.cpp @@ -631,12 +631,6 @@ void Skeleton::setAspectProperties(const AspectProperties& properties) setAdjacentBodyCheck(properties.mEnabledAdjacentBodyCheck); } -//============================================================================== -const Skeleton::AspectProperties& Skeleton::getSkeletonProperties() const -{ - return mAspectProperties; -} - //============================================================================== const std::string& Skeleton::setName(const std::string& _name) { @@ -710,20 +704,6 @@ void Skeleton::updateNameManagerNames() } } -//============================================================================== -void Skeleton::enableSelfCollision(bool enableAdjacentBodyCheck) -{ - enableSelfCollisionCheck(); - setAdjacentBodyCheck(enableAdjacentBodyCheck); -} - -//============================================================================== -void Skeleton::disableSelfCollision() -{ - disableSelfCollisionCheck(); - setAdjacentBodyCheck(false); -} - //============================================================================== void Skeleton::setSelfCollisionCheck(bool enable) { @@ -3868,25 +3848,6 @@ double Skeleton::computePotentialEnergy() const return PE; } -//============================================================================== -void Skeleton::clearCollidingBodies() -{ - for (auto i = 0u; i < getNumBodyNodes(); ++i) { - auto bodyNode = getBodyNode(i); - DART_SUPPRESS_DEPRECATED_BEGIN - bodyNode->setColliding(false); - DART_SUPPRESS_DEPRECATED_END - - auto softBodyNode = bodyNode->asSoftBodyNode(); - if (softBodyNode) { - auto& pointMasses = softBodyNode->getPointMasses(); - - for (auto pointMass : pointMasses) - pointMass->setColliding(false); - } - } -} - //============================================================================== Eigen::Vector3d Skeleton::getCOM(const Frame* _withRespectTo) const { diff --git a/dart/dynamics/Skeleton.hpp b/dart/dynamics/Skeleton.hpp index 9d4259802e24e..64a27a2253b9c 100644 --- a/dart/dynamics/Skeleton.hpp +++ b/dart/dynamics/Skeleton.hpp @@ -242,10 +242,6 @@ class Skeleton : public virtual common::VersionCounter, /// Set the Properties of this Skeleton void setProperties(const AspectProperties& properties); - /// Get the Properties of this Skeleton - DART_DEPRECATED(6.0) - const AspectProperties& getSkeletonProperties() const; - /// Set the AspectProperties of this Skeleton void setAspectProperties(const AspectProperties& properties); @@ -255,15 +251,6 @@ class Skeleton : public virtual common::VersionCounter, /// Get name. const std::string& getName() const override; - /// Deprecated. Please use enableSelfCollisionCheck() and - /// setAdjacentBodyCheck() instead. - DART_DEPRECATED(6.0) - void enableSelfCollision(bool enableAdjacentBodyCheck = false); - - /// Deprecated. Please use disableSelfCollisionCheck() instead. - DART_DEPRECATED(6.0) - void disableSelfCollision(); - /// Set whether to check self-collision. void setSelfCollisionCheck(bool enable); @@ -921,10 +908,6 @@ class Skeleton : public virtual common::VersionCounter, // Documentation inherited double computePotentialEnergy() const override; - // Documentation inherited - DART_DEPRECATED(6.0) - void clearCollidingBodies() override; - /// \} //---------------------------------------------------------------------------- diff --git a/dart/gui/glut/SimWindow.cpp b/dart/gui/glut/SimWindow.cpp index 2ff82999a15f4..766f70b3f9ab4 100644 --- a/dart/gui/glut/SimWindow.cpp +++ b/dart/gui/glut/SimWindow.cpp @@ -115,19 +115,6 @@ void SimWindow::drawSkeletons() const drawSkeleton(mWorld->getSkeleton(i).get()); } -//============================================================================== -void SimWindow::drawSkels() -{ - drawSkeletons(); -} - -//============================================================================== -void SimWindow::drawEntities() -{ - for (std::size_t i = 0; i < mWorld->getNumSimpleFrames(); ++i) - drawShapeFrame(mWorld->getSimpleFrame(i).get()); -} - void SimWindow::displayTimer(int _val) { int numIter = mDisplayTimeout / (mWorld->getTimeStep() * 1000); diff --git a/dart/gui/glut/SimWindow.hpp b/dart/gui/glut/SimWindow.hpp index 89ce2a9f09044..bee77754dbe8e 100644 --- a/dart/gui/glut/SimWindow.hpp +++ b/dart/gui/glut/SimWindow.hpp @@ -66,12 +66,6 @@ class SimWindow : public Win3D virtual void drawSkeletons() const; - DART_DEPRECATED(6.0) - virtual void drawSkels(); - - DART_DEPRECATED(6.0) - virtual void drawEntities(); - /// \brief void displayTimer(int _val) override; diff --git a/dart/math/Geometry.cpp b/dart/math/Geometry.cpp index 2944cb35c4c23..88589a4320763 100644 --- a/dart/math/Geometry.cpp +++ b/dart/math/Geometry.cpp @@ -1552,13 +1552,6 @@ Eigen::Isometry3d computeTransform( return result; } -//============================================================================== -Eigen::Isometry3d getFrameOriginAxisZ( - const Eigen::Vector3d& _origin, const Eigen::Vector3d& _axisZ) -{ - return computeTransform(_axisZ, _origin, AxisType::AXIS_Z); -} - //============================================================================== SupportPolygon computeSupportPolgyon( const SupportGeometry& _geometry, diff --git a/dart/math/Geometry.hpp b/dart/math/Geometry.hpp index e8982b82de530..09d88f4ae1012 100644 --- a/dart/math/Geometry.hpp +++ b/dart/math/Geometry.hpp @@ -453,11 +453,6 @@ Eigen::Isometry3d computeTransform( const Eigen::Vector3d& translation, AxisType axisType = AxisType::AXIS_X); -/// Generate frame given origin and z-axis -DART_DEPRECATED(6.0) -Eigen::Isometry3d getFrameOriginAxisZ( - const Eigen::Vector3d& _origin, const Eigen::Vector3d& _axisZ); - /// \brief Check if determinant of _R is equat to 1 and all the elements are not /// NaN values. bool verifyRotation(const Eigen::Matrix3d& _R); diff --git a/dart/simulation/World.cpp b/dart/simulation/World.cpp index 838372aaedbf5..2e88ceb01a3c7 100644 --- a/dart/simulation/World.cpp +++ b/dart/simulation/World.cpp @@ -516,19 +516,6 @@ std::set World::removeAllSimpleFrames() return ptrs; } -//============================================================================== -bool World::checkCollision(bool checkAllCollisions) -{ - collision::CollisionOption option; - - if (checkAllCollisions) - option.maxNumContacts = 1e+3; - else - option.maxNumContacts = 1u; - - return checkCollision(option); -} - //============================================================================== bool World::checkCollision( const collision::CollisionOption& option, diff --git a/dart/simulation/World.hpp b/dart/simulation/World.hpp index dc65bd0ca927b..73e6af45d0c23 100644 --- a/dart/simulation/World.hpp +++ b/dart/simulation/World.hpp @@ -192,10 +192,6 @@ class World : public virtual common::Subject // Collision checking //-------------------------------------------------------------------------- - /// Deprecated. Please use checkCollision(~) instead. - DART_DEPRECATED(6.0) - bool checkCollision(bool checkAllCollisions); - /// Perform collision checking with 'option' over all the feasible collision /// pairs in this World, and the result will be stored 'result'. If no /// argument is passed in then it will return just whether there is collision diff --git a/dart/utils/XmlHelpers.cpp b/dart/utils/XmlHelpers.cpp index b7c64cdd1accd..a719e98ba5a6e 100644 --- a/dart/utils/XmlHelpers.cpp +++ b/dart/utils/XmlHelpers.cpp @@ -663,19 +663,6 @@ bool hasAttribute(const tinyxml2::XMLElement* element, const char* const name) return result != nullptr; } -//============================================================================== -std::string getAttribute(tinyxml2::XMLElement* element, const char* const name) -{ - return getAttributeString(element, name); -} - -//============================================================================== -void getAttribute( - tinyxml2::XMLElement* element, const char* const name, double* d) -{ - *d = getAttributeDouble(element, name); -} - //============================================================================== std::string getAttributeString( const tinyxml2::XMLElement* element, const std::string& attributeName) diff --git a/dart/utils/XmlHelpers.hpp b/dart/utils/XmlHelpers.hpp index d27603f43e020..00c5fe67a130d 100644 --- a/dart/utils/XmlHelpers.hpp +++ b/dart/utils/XmlHelpers.hpp @@ -133,15 +133,6 @@ tinyxml2::XMLElement* getElement( bool hasAttribute(const tinyxml2::XMLElement* element, const char* const name); -// Please use getAttributeString() instead. -DART_DEPRECATED(6.0) -std::string getAttribute(tinyxml2::XMLElement* element, const char* const name); - -// Please use getAttributeDouble() instead. -DART_DEPRECATED(6.0) -void getAttribute( - tinyxml2::XMLElement* element, const char* const name, double* d); - std::string getAttributeString( const tinyxml2::XMLElement* element, const std::string& attributeName); bool getAttributeBool( diff --git a/dart/utils/sdf/SdfParser.cpp b/dart/utils/sdf/SdfParser.cpp index a6f43fb9dcf14..f118d2af82f68 100644 --- a/dart/utils/sdf/SdfParser.cpp +++ b/dart/utils/sdf/SdfParser.cpp @@ -247,15 +247,6 @@ Options::Options( // Do nothing } -//============================================================================== -simulation::WorldPtr readSdfFile( - const common::Uri& uri, const common::ResourceRetrieverPtr& nullOrRetriever) -{ - Options options; - options.mResourceRetriever = nullOrRetriever; - return readWorld(uri, options); -} - //============================================================================== bool checkVersion( const tinyxml2::XMLElement& sdfElement, const common::Uri& uri) diff --git a/dart/utils/sdf/SdfParser.hpp b/dart/utils/sdf/SdfParser.hpp index b352d4624ddda..f1d2f91f75b59 100644 --- a/dart/utils/sdf/SdfParser.hpp +++ b/dart/utils/sdf/SdfParser.hpp @@ -71,11 +71,6 @@ struct Options RootJointType defaultRootJointType = RootJointType::FLOATING); }; -DART_DEPRECATED(6.0) -simulation::WorldPtr readSdfFile( - const common::Uri& uri, - const common::ResourceRetrieverPtr& retriever = nullptr); - simulation::WorldPtr readWorld( const common::Uri& uri, const Options& options = Options()); diff --git a/python/dartpy/dynamics/ReferentialSkeleton.cpp b/python/dartpy/dynamics/ReferentialSkeleton.cpp index 535536269f8fc..9192a0ab2c932 100644 --- a/python/dartpy/dynamics/ReferentialSkeleton.cpp +++ b/python/dartpy/dynamics/ReferentialSkeleton.cpp @@ -487,11 +487,6 @@ void ReferentialSkeleton(py::module& m) +[](const dart::dynamics::ReferentialSkeleton* self) -> double { return self->computePotentialEnergy(); }) - // .def( - // "clearCollidingBodies", - // +[](dart::dynamics::ReferentialSkeleton* self) { - // self->clearCollidingBodies(); - // }) .def( "getCOM", +[](const dart::dynamics::ReferentialSkeleton* self) diff --git a/python/dartpy/dynamics/Skeleton.cpp b/python/dartpy/dynamics/Skeleton.cpp index 47bf9f35c6887..bfabfe861c845 100644 --- a/python/dartpy/dynamics/Skeleton.cpp +++ b/python/dartpy/dynamics/Skeleton.cpp @@ -1170,8 +1170,6 @@ void Skeleton(py::module& m) +[](const dart::dynamics::Skeleton* self) -> double { return self->computePotentialEnergy(); }) - // .def("clearCollidingBodies", +[](dart::dynamics::Skeleton *self) - // -> void { return self->clearCollidingBodies(); }) .def( "getCOM", +[](const dart::dynamics::Skeleton* self) -> Eigen::Vector3d { diff --git a/tests/integration/test_Collision.cpp b/tests/integration/test_Collision.cpp index 6af10c0f08d0f..a7dbfe1b035a6 100644 --- a/tests/integration/test_Collision.cpp +++ b/tests/integration/test_Collision.cpp @@ -1439,20 +1439,12 @@ void testCreateCollisionGroups(const std::shared_ptr& cd) world->getConstraintSolver()->setCollisionDetector(cd); world->addSkeleton(boxSkeleton1); world->addSkeleton(boxSkeleton2); - DART_SUPPRESS_DEPRECATED_BEGIN - EXPECT_FALSE(boxBodyNode1->isColliding()); - EXPECT_FALSE(boxBodyNode2->isColliding()); - DART_SUPPRESS_DEPRECATED_END const collision::CollisionResult& result1 = world->getLastCollisionResult(); EXPECT_FALSE(result1.inCollision(boxBodyNode1)); EXPECT_FALSE(result1.inCollision(boxBodyNode2)); world->step(); - DART_SUPPRESS_DEPRECATED_BEGIN - EXPECT_TRUE(boxBodyNode1->isColliding()); - EXPECT_TRUE(boxBodyNode2->isColliding()); - DART_SUPPRESS_DEPRECATED_END const collision::CollisionResult& result2 = world->getLastCollisionResult(); EXPECT_TRUE(result2.inCollision(boxBodyNode1));