Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix incorrect rotational motion of BallJoint and FreeJoint #518

Merged
merged 6 commits into from
Oct 15, 2015
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Prev Previous commit
Don't need to compute Jacobians of BallJoint/FreeJoint in the constru…
…ctors

...since it will be updated when they get called by the kinematics auto-updating mechanism
  • Loading branch information
jslee02 committed Oct 14, 2015
commit 95992d2dd14558e1f6f6fbec9f75584192596d64
2 changes: 0 additions & 2 deletions dart/dynamics/BallJoint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,8 +101,6 @@ BallJoint::BallJoint(const Properties& _properties)
: MultiDofJoint<3>(_properties),
mR(Eigen::Isometry3d::Identity())
{
mJacobian
= math::getAdTMatrix(mJointP.mT_ChildBodyToJoint).leftCols<3>();
mJacobianDeriv = Eigen::Matrix<double, 6, 3>::Zero();

setProperties(_properties);
Expand Down
1 change: 0 additions & 1 deletion dart/dynamics/FreeJoint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -529,7 +529,6 @@ FreeJoint::FreeJoint(const Properties& _properties)
: MultiDofJoint<6>(_properties),
mQ(Eigen::Isometry3d::Identity())
{
mJacobian = math::getAdTMatrix(mJointP.mT_ChildBodyToJoint);
mJacobianDeriv = Eigen::Matrix6d::Zero();

setProperties(_properties);
Expand Down