From 04a4d507259eaa79a025416d92f60894693a2602 Mon Sep 17 00:00:00 2001 From: Michael Koval Date: Wed, 8 Jul 2015 21:48:23 -0500 Subject: [PATCH] Added isPositionLimitEnforced. - Added isPositionLimitEnforced and setPositionLimitEnforced. - Deprecated isPositionLimited and setPositionLimited. - Updated references throughout DART. --- dart/constraint/ConstraintSolver.cpp | 2 +- dart/dynamics/Joint.cpp | 18 +++++++++++++++--- dart/dynamics/Joint.h | 11 +++++++++-- 3 files changed, 25 insertions(+), 6 deletions(-) diff --git a/dart/constraint/ConstraintSolver.cpp b/dart/constraint/ConstraintSolver.cpp index 5113966758fd1..fc13796744e3d 100644 --- a/dart/constraint/ConstraintSolver.cpp +++ b/dart/constraint/ConstraintSolver.cpp @@ -410,7 +410,7 @@ void ConstraintSolver::updateConstraints() { dynamics::Joint* joint = skel->getBodyNode(i)->getParentJoint(); - if (joint->isDynamic() && joint->isPositionLimited()) + if (joint->isDynamic() && joint->isPositionLimitEnforced()) mJointLimitConstraints.push_back(new JointLimitConstraint(joint)); } } diff --git a/dart/dynamics/Joint.cpp b/dart/dynamics/Joint.cpp index 1a731095ccae6..09eabfaee5a75 100644 --- a/dart/dynamics/Joint.cpp +++ b/dart/dynamics/Joint.cpp @@ -79,7 +79,7 @@ void Joint::setProperties(const Properties& _properties) setName(_properties.mName); setTransformFromParentBodyNode(_properties.mT_ParentBodyToJoint); setTransformFromChildBodyNode(_properties.mT_ChildBodyToJoint); - setPositionLimited(_properties.mIsPositionLimited); + setPositionLimitEnforced(_properties.mIsPositionLimited); setActuatorType(_properties.mActuatorType); } @@ -277,17 +277,29 @@ const Eigen::Vector6d& Joint::getLocalPrimaryAcceleration() const } //============================================================================== -void Joint::setPositionLimited(bool _isPositionLimited) +void Joint::setPositionLimitEnforced(bool _isPositionLimited) { mJointP.mIsPositionLimited = _isPositionLimited; } //============================================================================== -bool Joint::isPositionLimited() const +void Joint::setPositionLimited(bool _isPositionLimited) +{ + setPositionLimitEnforced(_isPositionLimited); +} + +//============================================================================== +bool Joint::isPositionLimitEnforced() const { return mJointP.mIsPositionLimited; } +//============================================================================== +bool Joint::isPositionLimited() const +{ + return isPositionLimitEnforced(); +} + //============================================================================== size_t Joint::getJointIndexInSkeleton() const { diff --git a/dart/dynamics/Joint.h b/dart/dynamics/Joint.h index f911f4e662f66..caaf4aead97cc 100644 --- a/dart/dynamics/Joint.h +++ b/dart/dynamics/Joint.h @@ -42,6 +42,7 @@ #include #include +#include "dart/common/Deprecated.h" #include "dart/common/Subject.h" #include "dart/math/MathTypes.h" #include "dart/dynamics/SmartPointer.h" @@ -244,7 +245,10 @@ class Joint : public virtual common::Subject /// PASSIVE/FORCE. /// /// \sa ActuatorType - void setPositionLimited(bool _isPositionLimited); + void setPositionLimitEnforced(bool _isPositionLimited); + + /// Deprecated. Replaced by setPositionLimitEnforced. + DEPRECATED(5.0) void setPositionLimited(bool _isPositionLimited); /// Get whether enforcing joint position limit /// @@ -252,7 +256,10 @@ class Joint : public virtual common::Subject /// PASSIVE/FORCE. /// /// \sa ActuatorType - bool isPositionLimited() const; + bool isPositionLimitEnforced() const; + + /// Deprecated. Replaced by isPositionLimitEnforced. + DEPRECATED(5.0) bool isPositionLimited() const; /// Get a unique index in skeleton of a generalized coordinate in this Joint virtual size_t getIndexInSkeleton(size_t _index) const = 0;