Skip to content

Commit

Permalink
Merge pull request #209 from dartsim/get_num_dofs
Browse files Browse the repository at this point in the history
Rename getDof() to getNumDofs()
  • Loading branch information
jslee02 committed Jul 2, 2014
2 parents 43739e1 + bfd5b28 commit c155d90
Show file tree
Hide file tree
Showing 42 changed files with 264 additions and 224 deletions.
8 changes: 4 additions & 4 deletions apps/atlasRobot/Controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -208,7 +208,7 @@ void Controller::printDebugInfo() const
{
std::cout << "[ATLAS Robot]" << std::endl
<< " NUM NODES : " << mAtlasRobot->getNumBodyNodes() << std::endl
<< " NUM DOF : " << mAtlasRobot->getDof() << std::endl
<< " NUM DOF : " << mAtlasRobot->getNumDofs() << std::endl
<< " NUM JOINTS: " << mAtlasRobot->getNumBodyNodes() << std::endl;

for(size_t i = 0; i < mAtlasRobot->getNumBodyNodes(); ++i)
Expand All @@ -219,7 +219,7 @@ void Controller::printDebugInfo() const

std::cout << " Joint [" << i << "]: "
<< joint->getName()
<< " (" << joint->getDof() << ")"
<< " (" << joint->getNumDofs() << ")"
<< std::endl;
if (parentBody != NULL)
{
Expand Down Expand Up @@ -817,9 +817,9 @@ void Controller::_setJointDamping()
for (size_t i = 1; i < mAtlasRobot->getNumBodyNodes(); ++i)
{
Joint* joint = mAtlasRobot->getJoint(i);
if (joint->getDof() > 0)
if (joint->getNumDofs() > 0)
{
for (size_t j = 0; j < joint->getDof(); ++j)
for (size_t j = 0; j < joint->getNumDofs(); ++j)
joint->setDampingCoefficient(j, 80.0);
}
}
Expand Down
4 changes: 2 additions & 2 deletions apps/atlasRobot/State.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ State::State(Skeleton* _skeleton, const std::string& _name)
mDesiredGlobalPelvisAngleOnSagital(0.0),
mDesiredGlobalPelvisAngleOnCoronal(0.0)
{
int dof = mSkeleton->getDof();
int dof = mSkeleton->getNumDofs();

mDesiredJointPositions = Eigen::VectorXd::Zero(dof);
mDesiredJointPositionsBalance = Eigen::VectorXd::Zero(dof);
Expand Down Expand Up @@ -153,7 +153,7 @@ void State::computeControlForce(double _timestep)
{
assert(mNextState != NULL && "Next state should be set.");

int dof = mSkeleton->getDof();
int dof = mSkeleton->getNumDofs();
VectorXd q = mSkeleton->getPositions();
VectorXd dq = mSkeleton->getVelocities();

Expand Down
4 changes: 2 additions & 2 deletions apps/balance/Controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ Controller::Controller(dart::dynamics::Skeleton* _skel,
mConstraintSolver = _constraintSolver;
mTimestep = _t;
mFrame = 0;
int nDof = mSkel->getDof();
int nDof = mSkel->getNumDofs();
mKp = Eigen::MatrixXd::Identity(nDof, nDof);
mKd = Eigen::MatrixXd::Identity(nDof, nDof);
mConstrForces = Eigen::VectorXd::Zero(nDof);
Expand Down Expand Up @@ -94,7 +94,7 @@ void Controller::setDesiredDof(int _index, double _val) {
void Controller::computeTorques(const Eigen::VectorXd& _dof,
const Eigen::VectorXd& _dofVel) {
// SPD tracking
//size_t nDof = mSkel->getDof();
//size_t nDof = mSkel->getNumDofs();
Eigen::MatrixXd invM = (mSkel->getMassMatrix() + mKd * mTimestep).inverse();
Eigen::VectorXd p = -mKp * (_dof + _dofVel * mTimestep - mDesiredDofs);
Eigen::VectorXd d = -mKd * _dofVel;
Expand Down
2 changes: 1 addition & 1 deletion apps/balance/Main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ int main(int argc, char* argv[]) {
for (size_t i = 1; i < skeleton->getNumBodyNodes(); ++i)
{
dart::dynamics::Joint* joint = skeleton->getBodyNode(i)->getParentJoint();
for (size_t j = 0; j < joint->getDof(); ++j)
for (size_t j = 0; j < joint->getNumDofs(); ++j)
{
// joint->setPositionLowerLimit(j, -0.1);
// joint->setPositionUpperLimit(j, 0.1);
Expand Down
4 changes: 2 additions & 2 deletions apps/ballJointConstraintTest/Main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ int main(int argc, char* argv[])
myWorld->setGravity(gravity);
myWorld->setTimeStep(1.0/2000);

int dof = myWorld->getSkeleton(0)->getDof();
int dof = myWorld->getSkeleton(0)->getNumDofs();
Eigen::VectorXd initPose(dof);
for (int i = 0; i < dof; i++)
initPose[i] = random(-0.5, 0.5);
Expand All @@ -76,7 +76,7 @@ int main(int argc, char* argv[])
for (size_t i = 0; i < myWorld->getSkeleton(0)->getNumBodyNodes(); i++) {
BodyNode *bd = myWorld->getSkeleton(0)->getBodyNode(i);
Joint *jt = bd->getParentJoint();
for (size_t j = 0; j < jt->getDof(); j++)
for (size_t j = 0; j < jt->getNumDofs(); j++)
jt->setDampingCoefficient(j, 0.02);
}

Expand Down
2 changes: 1 addition & 1 deletion apps/ballJointConstraintTest/MyWindow.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ void MyWindow::timeStepping()

Eigen::VectorXd MyWindow::computeDamping()
{
int nDof = mWorld->getSkeleton(0)->getDof();
int nDof = mWorld->getSkeleton(0)->getNumDofs();
Eigen::VectorXd damping = Eigen::VectorXd::Zero(nDof);
// add damping to each joint; twist-dof has smaller damping
damping = -0.01 * mWorld->getSkeleton(0)->getVelocities();
Expand Down
2 changes: 1 addition & 1 deletion apps/closedLoop/Main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ int main(int argc, char* argv[])
myWorld->setGravity(gravity);
myWorld->setTimeStep(1.0/2000);

int dof = myWorld->getSkeleton(0)->getDof();
int dof = myWorld->getSkeleton(0)->getNumDofs();

Eigen::VectorXd initPose(dof);
initPose.setZero();
Expand Down
2 changes: 1 addition & 1 deletion apps/closedLoop/MyWindow.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ void MyWindow::timeStepping()

Eigen::VectorXd MyWindow::computeDamping()
{
int nDof = mWorld->getSkeleton(0)->getDof();
int nDof = mWorld->getSkeleton(0)->getNumDofs();
Eigen::VectorXd damping = Eigen::VectorXd::Zero(nDof);
// add damping to each joint; twist-dof has smaller damping
damping = -0.01 * mWorld->getSkeleton(0)->getVelocities();
Expand Down
2 changes: 1 addition & 1 deletion apps/forwardSim/Main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ int main(int argc, char* argv[]) {
myWorld->setGravity(gravity);
myWorld->setTimeStep(1.0/2000);

int dof = myWorld->getSkeleton(0)->getDof();
int dof = myWorld->getSkeleton(0)->getNumDofs();
Eigen::VectorXd initPose(dof);
for (int i = 0; i < dof; i++)
initPose[i] = dart::math::random(-0.5, 0.5);
Expand Down
2 changes: 1 addition & 1 deletion apps/forwardSim/MyWindow.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ void MyWindow::timeStepping() {
//==============================================================================
Eigen::VectorXd MyWindow::computeDamping()
{
int nDof = mWorld->getSkeleton(0)->getDof();
int nDof = mWorld->getSkeleton(0)->getNumDofs();
Eigen::VectorXd damping = Eigen::VectorXd::Zero(nDof);
// add damping to each joint; twist-dof has smaller damping
damping = -0.01 * mWorld->getSkeleton(0)->getVelocities();
Expand Down
4 changes: 2 additions & 2 deletions apps/hanging/Controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ Controller::Controller(dynamics::Skeleton* _skel,
mConstraintSolver = _constraintSolver;
mTimestep = _t;
mFrame = 0;
int nDof = mSkel->getDof();
int nDof = mSkel->getNumDofs();
mKp = MatrixXd::Identity(nDof, nDof);
mKd = MatrixXd::Identity(nDof, nDof);
mConstrForces = VectorXd::Zero(nDof);
Expand Down Expand Up @@ -88,7 +88,7 @@ Controller::Controller(dynamics::Skeleton* _skel,

void Controller::computeTorques(const VectorXd& _dof, const VectorXd& _dofVel) {
// SPD tracking
// int nDof = mSkel->getDof();
// int nDof = mSkel->getNumDofs();
MatrixXd invM = (mSkel->getMassMatrix() + mKd * mTimestep).inverse();
VectorXd p = -mKp * (_dof + _dofVel * mTimestep - mDesiredDofs);
VectorXd d = -mKd * _dofVel;
Expand Down
2 changes: 1 addition & 1 deletion apps/hanging/MyWindow.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ MyWindow::MyWindow(dart::simulation::World* _world)
mWorld->getConstraintSolver(),
mWorld->getTimeStep());

for (size_t i = 0; i < mWorld->getSkeleton(1)->getDof(); i++)
for (size_t i = 0; i < mWorld->getSkeleton(1)->getNumDofs(); i++)
mController->setDesiredDof(i, mController->getSkeleton()->getPosition(i));

// initialize constraint on the hand
Expand Down
4 changes: 2 additions & 2 deletions apps/harnessTest/Controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ Controller::Controller(dynamics::Skeleton* _skel,
mCollisionHandle = _collisionSolver;
mTimestep = _t;
mFrame = 0;
int nDof = mSkel->getDof();
int nDof = mSkel->getNumDofs();
mKp = Eigen::MatrixXd::Identity(nDof, nDof);
mKd = Eigen::MatrixXd::Identity(nDof, nDof);
mConstrForces = Eigen::VectorXd::Zero(nDof);
Expand Down Expand Up @@ -90,7 +90,7 @@ void Controller::computeTorques(const Eigen::VectorXd& _dof,
const Eigen::VectorXd& _dofVel)
{
// SPD tracking
// size_t nDof = mSkel->getDof();
// size_t nDof = mSkel->getNumDofs();
Eigen::MatrixXd invM = (mSkel->getMassMatrix() + mKd * mTimestep).inverse();
Eigen::VectorXd p = -mKp * (_dof + _dofVel * mTimestep - mDesiredDofs);
Eigen::VectorXd d = -mKd * _dofVel;
Expand Down
2 changes: 1 addition & 1 deletion apps/meshCollision/Main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ int main(int argc, char* argv[]) {
// Verify that our skeleton has something inside :)
std::printf("Our skeleton has %zu nodes \n", MeshSkel->getNumBodyNodes());
// std::printf("Our skeleton has %d joints \n", MeshSkel->getNumJoints());
std::printf("Our skeleton has %zu DOFs \n", MeshSkel->getDof());
std::printf("Our skeleton has %zu DOFs \n", MeshSkel->getNumDofs());

MyWindow window;
window.setWorld(myWorld);
Expand Down
2 changes: 1 addition & 1 deletion apps/softArticulatedBodiesTest/Main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ int main(int argc, char* argv[])
DART_DATA_PATH"skel/test/test_articulated_bodies_10bodies.skel");
assert(myWorld != NULL);

int dof = myWorld->getSkeleton(1)->getDof();
int dof = myWorld->getSkeleton(1)->getNumDofs();
Eigen::VectorXd initPose = Eigen::VectorXd::Zero(dof);
for (int i = 0; i < 3; i++)
initPose[i] = dart::math::random(-0.5, 0.5);
Expand Down
2 changes: 1 addition & 1 deletion apps/softOpenChain/Main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ int main(int argc, char* argv[])
DART_DATA_PATH"skel/soft_open_chain.skel");
assert(myWorld != NULL);

int dof = myWorld->getSkeleton("skeleton 1")->getDof();
int dof = myWorld->getSkeleton("skeleton 1")->getNumDofs();
Eigen::VectorXd initPose = Eigen::VectorXd::Zero(dof);
for (int i = 0; i < 3; i++)
initPose[i] = dart::math::random(-0.5, 0.5);
Expand Down
10 changes: 5 additions & 5 deletions dart/constraint/JointLimitConstraint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -196,7 +196,7 @@ void JointLimitConstraint::update()
// Reset dimention
mDim = 0;

size_t dof = mJoint->getDof();
size_t dof = mJoint->getNumDofs();
for (size_t i = 0; i < dof; ++i)
{
// Lower bound check
Expand Down Expand Up @@ -253,7 +253,7 @@ void JointLimitConstraint::update()
void JointLimitConstraint::getInformation(ConstraintInfo* _lcp)
{
size_t index = 0;
size_t dof = mJoint->getDof();
size_t dof = mJoint->getNumDofs();
for (size_t i = 0; i < dof; ++i)
{
if (mActive[i] == false)
Expand Down Expand Up @@ -306,7 +306,7 @@ void JointLimitConstraint::applyUnitImpulse(size_t _index)
size_t localIndex = 0;
dynamics::Skeleton* skeleton = mJoint->getSkeleton();

size_t dof = mJoint->getDof();
size_t dof = mJoint->getNumDofs();
for (size_t i = 0; i < dof; ++i)
{
if (mActive[i] == false)
Expand All @@ -332,7 +332,7 @@ void JointLimitConstraint::getVelocityChange(double* _delVel, bool _withCfm)
assert(_delVel != NULL && "Null pointer is not allowed.");

size_t localIndex = 0;
size_t dof = mJoint->getDof();
size_t dof = mJoint->getNumDofs();
for (size_t i = 0; i < dof ; ++i)
{
if (mActive[i] == false)
Expand Down Expand Up @@ -373,7 +373,7 @@ void JointLimitConstraint::unexcite()
void JointLimitConstraint::applyImpulse(double* _lambda)
{
size_t localIndex = 0;
size_t dof = mJoint->getDof();
size_t dof = mJoint->getNumDofs();
for (size_t i = 0; i < dof ; ++i)
{
if (mActive[i] == false)
Expand Down
26 changes: 13 additions & 13 deletions dart/dynamics/BodyNode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -760,7 +760,7 @@ void BodyNode::init(Skeleton* _skeleton)
else
mDependentGenCoordIndices.clear();

for (size_t i = 0; i < mParentJoint->getDof(); i++)
for (size_t i = 0; i < mParentJoint->getNumDofs(); i++)
mDependentGenCoordIndices.push_back(mParentJoint->getIndexInSkeleton(i));

// Sort
Expand Down Expand Up @@ -956,7 +956,7 @@ void BodyNode::updateGeneralizedForce(bool _withDampingForces)
{
assert(mParentJoint != NULL);

size_t dof = mParentJoint->getDof();
size_t dof = mParentJoint->getNumDofs();

if (dof > 0)
{
Expand Down Expand Up @@ -1243,7 +1243,7 @@ void BodyNode::updateJointVelocityChange()
//==============================================================================
//void BodyNode::updateBodyVelocityChange()
//{
// if (mParentJoint->getDof() > 0)
// if (mParentJoint->getNumDofs() > 0)
// mDelV = mParentJoint->getLocalJacobian() * mParentJoint->getVelsChange();
// else
// mDelV.setZero();
Expand Down Expand Up @@ -1310,7 +1310,7 @@ void BodyNode::aggregateGravityForceVector(Eigen::VectorXd* _g,
(*it)->mG_F);
}

int nGenCoords = mParentJoint->getDof();
int nGenCoords = mParentJoint->getNumDofs();
if (nGenCoords > 0)
{
Eigen::VectorXd g = -(mParentJoint->getLocalJacobian().transpose() * mG_F);
Expand Down Expand Up @@ -1354,7 +1354,7 @@ void BodyNode::aggregateCombinedVector(Eigen::VectorXd* _Cg,
mCg_F += math::dAdInvT((*it)->getParentJoint()->mT, (*it)->mCg_F);
}

int nGenCoords = mParentJoint->getDof();
int nGenCoords = mParentJoint->getNumDofs();
if (nGenCoords > 0)
{
Eigen::VectorXd Cg
Expand All @@ -1376,7 +1376,7 @@ void BodyNode::aggregateExternalForces(Eigen::VectorXd* _Fext)
(*it)->mFext_F);
}

int nGenCoords = mParentJoint->getDof();
int nGenCoords = mParentJoint->getNumDofs();
if (nGenCoords > 0)
{
Eigen::VectorXd Fext = mParentJoint->getLocalJacobian().transpose()*mFext_F;
Expand All @@ -1389,7 +1389,7 @@ void BodyNode::aggregateExternalForces(Eigen::VectorXd* _Fext)
void BodyNode::updateMassMatrix()
{
mM_dV.setZero();
int dof = mParentJoint->getDof();
int dof = mParentJoint->getNumDofs();
if (dof > 0)
{
mM_dV.noalias() += mParentJoint->getLocalJacobian()
Expand Down Expand Up @@ -1423,7 +1423,7 @@ void BodyNode::aggregateMassMatrix(Eigen::MatrixXd* _MCol, int _col)
assert(!math::isNan(mM_F));

//
int dof = mParentJoint->getDof();
int dof = mParentJoint->getNumDofs();
if (dof > 0)
{
int iStart = mParentJoint->getIndexInSkeleton(0);
Expand Down Expand Up @@ -1456,7 +1456,7 @@ void BodyNode::aggregateAugMassMatrix(Eigen::MatrixXd* _MCol, int _col,
assert(!math::isNan(mM_F));

//
int dof = mParentJoint->getDof();
int dof = mParentJoint->getNumDofs();
if (dof > 0)
{
Eigen::MatrixXd K = Eigen::MatrixXd::Zero(dof, dof);
Expand Down Expand Up @@ -1586,14 +1586,14 @@ void BodyNode::_updateBodyJacobian()
// n: number of dependent coordinates
//--------------------------------------------------------------------------

const int localDof = mParentJoint->getDof();
const int localDof = mParentJoint->getNumDofs();
const int ascendantDof = getNumDependentGenCoords() - localDof;

// Parent Jacobian
if (mParentBodyNode)
{
assert(mParentBodyNode->getBodyJacobian().cols()
+ math::castUIntToInt(mParentJoint->getDof())
+ math::castUIntToInt(mParentJoint->getNumDofs())
== mBodyJacobian.cols());

assert(mParentJoint);
Expand Down Expand Up @@ -1623,15 +1623,15 @@ void BodyNode::_updateBodyJacobianDeriv()
// n: number of dependent coordinates
//--------------------------------------------------------------------------

const int numLocalDOFs = mParentJoint->getDof();
const int numLocalDOFs = mParentJoint->getNumDofs();
const int numParentDOFs = getNumDependentGenCoords() - numLocalDOFs;
math::Jacobian J = getBodyJacobian();

// Parent Jacobian
if (mParentBodyNode)
{
assert(mParentBodyNode->mBodyJacobianDeriv.cols()
+ math::castUIntToInt(mParentJoint->getDof())
+ math::castUIntToInt(mParentJoint->getNumDofs())
== mBodyJacobianDeriv.cols());

assert(mParentJoint);
Expand Down
4 changes: 2 additions & 2 deletions dart/dynamics/Joint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -134,7 +134,7 @@ void Joint::init(Skeleton* _skel)
//==============================================================================
//Eigen::VectorXd Joint::getDampingForces() const
//{
// int numDofs = getDof();
// int numDofs = getNumDofs();
// Eigen::VectorXd dampingForce(numDofs);

// for (int i = 0; i < numDofs; ++i)
Expand All @@ -146,7 +146,7 @@ void Joint::init(Skeleton* _skel)
//==============================================================================
//Eigen::VectorXd Joint::getSpringForces(double _timeStep) const
//{
// int dof = getDof();
// int dof = getNumDofs();
// Eigen::VectorXd springForce(dof);
// for (int i = 0; i < dof; ++i)
// {
Expand Down
Loading

0 comments on commit c155d90

Please sign in to comment.