Skip to content

Commit

Permalink
Added isPositionLimitEnforced.
Browse files Browse the repository at this point in the history
- Added isPositionLimitEnforced and setPositionLimitEnforced.
- Deprecated isPositionLimited and setPositionLimited.
- Updated references throughout DART.
  • Loading branch information
Michael Koval committed Jul 9, 2015
1 parent 1432996 commit 04a4d50
Show file tree
Hide file tree
Showing 3 changed files with 25 additions and 6 deletions.
2 changes: 1 addition & 1 deletion dart/constraint/ConstraintSolver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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));
}
}
Expand Down
18 changes: 15 additions & 3 deletions dart/dynamics/Joint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}

Expand Down Expand Up @@ -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
{
Expand Down
11 changes: 9 additions & 2 deletions dart/dynamics/Joint.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@
#include <vector>
#include <memory>

#include "dart/common/Deprecated.h"
#include "dart/common/Subject.h"
#include "dart/math/MathTypes.h"
#include "dart/dynamics/SmartPointer.h"
Expand Down Expand Up @@ -244,15 +245,21 @@ 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
///
/// The joint position limit is valid when the actutor type is one of
/// 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;
Expand Down

0 comments on commit 04a4d50

Please sign in to comment.