Skip to content

Commit

Permalink
[cleanup] Remove APIs deprecated in 6.0
Browse files Browse the repository at this point in the history
  • Loading branch information
jslee02 committed Mar 22, 2024
1 parent f9e1ac5 commit 9abba11
Show file tree
Hide file tree
Showing 26 changed files with 1 addition and 394 deletions.
22 changes: 0 additions & 22 deletions dart/constraint/ConstraintSolver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -258,14 +258,6 @@ double ConstraintSolver::getTimeStep() const
return mTimeStep;
}

//==============================================================================
void ConstraintSolver::setCollisionDetector(
collision::CollisionDetector* collisionDetector)
{
setCollisionDetector(
std::unique_ptr<collision::CollisionDetector>(collisionDetector));
}

//==============================================================================
void ConstraintSolver::setCollisionDetector(
const std::shared_ptr<collision::CollisionDetector>& collisionDetector)
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -514,17 +503,6 @@ void ConstraintSolver::updateConstraints()
continue;
}

// Set colliding bodies
auto shapeFrame1 = const_cast<dynamics::ShapeFrame*>(
contact.collisionObject1->getShapeFrame());
auto shapeFrame2 = const_cast<dynamics::ShapeFrame*>(
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
Expand Down
6 changes: 0 additions & 6 deletions dart/constraint/ConstraintSolver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<collision::CollisionDetector>& collisionDetector);
Expand Down
13 changes: 0 additions & 13 deletions dart/dynamics/BodyNode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down Expand Up @@ -1263,7 +1251,6 @@ BodyNode::BodyNode(
Frame(Frame::World()),
TemplatedJacobianNode<BodyNode>(this),
mID(BodyNode::msBodyNodeCount++),
mIsColliding(false),
mParentJoint(_parentJoint),
mParentBodyNode(nullptr),
mPartialAcceleration(Eigen::Vector6d::Zero()),
Expand Down
18 changes: 1 addition & 17 deletions dart/dynamics/BodyNode.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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(),
Expand Down Expand Up @@ -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
//--------------------------------------------------------------------------
Expand Down
78 changes: 0 additions & 78 deletions dart/dynamics/Joint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -334,48 +334,6 @@ std::shared_ptr<const Skeleton> 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
{
Expand Down Expand Up @@ -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
{
Expand Down
52 changes: 0 additions & 52 deletions dart/dynamics/Joint.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down
12 changes: 0 additions & 12 deletions dart/dynamics/Marker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand Down
12 changes: 0 additions & 12 deletions dart/dynamics/Marker.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
4 changes: 0 additions & 4 deletions dart/dynamics/MetaSkeleton.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;

/// \}

//----------------------------------------------------------------------------
Expand Down
19 changes: 0 additions & 19 deletions dart/dynamics/ReferentialSkeleton.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand Down
4 changes: 0 additions & 4 deletions dart/dynamics/ReferentialSkeleton.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -349,10 +349,6 @@ class ReferentialSkeleton : public MetaSkeleton
// Documentation inherited
double computePotentialEnergy() const override;

// Documentation inherited
DART_DEPRECATED(6.0)
void clearCollidingBodies() override;

/// \}

//----------------------------------------------------------------------------
Expand Down
Loading

0 comments on commit 9abba11

Please sign in to comment.